Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion rm_gimbal_controllers/src/gimbal_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,7 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro

ctrls_.insert(std::make_pair(axis, std::make_unique<effort_controllers::JointVelocityController>()));
pid_pos_.insert(std::make_pair(axis, std::make_unique<control_toolbox::Pid>()));
pos_des_in_limit_.insert(std::make_pair(axis, true));
pos_state_pub_.insert(std::make_pair(
axis, std::make_unique<realtime_tools::RealtimePublisher<rm_msgs::GimbalPosState>>(nh, "pos_state", 1)));

Expand Down Expand Up @@ -207,7 +208,7 @@ void Controller::setDes(const ros::Time& time, double yaw_des, double pitch_des)
odom2gimbal_des.setRPY(0, pitch_des, yaw_des);
tf2::Quaternion base2gimbal_des = odom2base.inverse() * odom2gimbal_des;
for (const auto& it : joint_urdfs_)
pos_des_in_limit_.insert(std::make_pair(it.first, setDesIntoLimit(base2gimbal_des, it.second, base2gimbal_des)));
pos_des_in_limit_[it.first] = setDesIntoLimit(base2gimbal_des, it.second, base2gimbal_des);
odom2gimbal_des_.transform.rotation = tf2::toMsg(odom2base * base2gimbal_des);
odom2gimbal_des_.header.stamp = time;
robot_state_handle_.setTransform(odom2gimbal_des_, "rm_gimbal_controllers");
Expand Down
Loading