diff --git a/rm_chassis_controllers/src/chassis_base.cpp b/rm_chassis_controllers/src/chassis_base.cpp index f70b2588..ebf7d987 100644 --- a/rm_chassis_controllers/src/chassis_base.cpp +++ b/rm_chassis_controllers/src/chassis_base.cpp @@ -149,13 +149,13 @@ void ChassisBase::update(const ros::Time& time, const ros::Duration& perio vel_cmd_.y = ramp_y_->output(); vel_cmd_.z = cmd_vel.angular.z; } - // test + if (cmd_rt_buffer_.readFromRT()->cmd_chassis_.follow_source_frame.empty()) follow_source_frame_ = "yaw"; else follow_source_frame_ = cmd_rt_buffer_.readFromRT()->cmd_chassis_.follow_source_frame; if (cmd_rt_buffer_.readFromRT()->cmd_chassis_.command_source_frame.empty()) - command_source_frame_ = "bask_link"; + command_source_frame_ = "yaw"; else command_source_frame_ = cmd_rt_buffer_.readFromRT()->cmd_chassis_.command_source_frame; @@ -173,10 +173,10 @@ void ChassisBase::update(const ros::Time& time, const ros::Duration& perio raw(); break; case FOLLOW: - raw(); + follow(time, period); break; case TWIST: - raw(); + twist(time, period); break; }