30 #include <geometry_msgs/PoseStamped.h>
31 #include <geometry_msgs/TwistStamped.h>
34 #include <kdl/tree.hpp>
36 #include <kdl/jntarray.hpp>
41 #include "kdl/chainiksolvervel_wdls.hpp"
42 #include "kdl/frames.hpp"
43 #include "kdl/framevel.hpp"
44 #include "kdl/jntarrayvel.hpp"
51 template <
class HWInterface,
class HandleType>
55 std::string robot_description;
56 std::vector<std::string> joint_names;
63 auto* hw_interface = hw->
get<HWInterface>();
71 if (!controller_nh.
getParam(
"joints", joint_names))
76 for (
size_t i = 0; i < joint_names.size(); ++i)
78 joint_handles_.push_back(hw_interface->getHandle(joint_names[i]));
82 if (!root_nh.
getParam(
"robot_description", robot_description))
84 ROS_ERROR_STREAM(ns <<
": Failed to load robot_description from parameter server");
87 if (!controller_nh.
getParam(
"base", robot_base_))
92 if (!controller_nh.
getParam(
"tip", robot_tip_))
99 if (!robot_model.
initString(robot_description))
101 ROS_ERROR_STREAM(ns <<
": Failed to parse urdf model from robot_description");
109 if (!robot_tree.getChain(robot_base_, robot_tip_, robot_chain_))
115 fk_solver_ = std::make_unique<KDL::ChainFkSolverVel_recursive>(robot_chain_);
120 template <
class HWInterface,
class HandleType>
123 const size_t size = joint_handles_.size();
125 KDL::JntArrayVel current(size);
129 for (
size_t i = 0; i < size; ++i)
131 current.q(i) = joint_handles_[i].getPosition();
132 current.qdot(i) = joint_handles_[i].getVelocity();
134 fk_solver_->JntToCart(current, pose);
138 state.
p.x() = pose.value().p.x();
139 state.
p.y() = pose.value().p.y();
140 state.
p.z() = pose.value().p.z();
141 pose.value().M.GetQuaternion(state.
q.x(), state.
q.y(), state.
q.z(), state.
q.w());
144 state.
v.x() = pose.deriv().vel.x();
146 state.
v.y() = pose.deriv().vel.y();
148 state.
v.z() = pose.deriv().vel.z();
150 state.
w.x() = pose.deriv().rot.x();
152 state.
w.y() = pose.deriv().rot.y();
154 state.
w.z() = pose.deriv().rot.z();
177 if (!controller_nh.
getParam(
"base", base_))
182 if (!controller_nh.
getParam(
"tip", tip_))
188 handle_ = cmd_interface->getHandle(tip_);
195 geometry_msgs::Pose target;
197 target.position.x =
cmd.p.x();
198 target.position.y =
cmd.p.y();
199 target.position.z =
cmd.p.z();
200 target.orientation.x =
cmd.q.x();
201 target.orientation.y =
cmd.q.y();
202 target.orientation.z =
cmd.q.z();
203 target.orientation.w =
cmd.q.w();
205 handle_.setCommand(target);
210 geometry_msgs::Pose pose = handle_.getPose();
211 geometry_msgs::Twist twist = handle_.getTwist();
212 geometry_msgs::Accel accel = handle_.getAccel();
215 state.
p.x() = pose.position.x;
216 state.
p.y() = pose.position.y;
217 state.
p.z() = pose.position.z;
218 state.
q.x() = pose.orientation.x;
219 state.
q.y() = pose.orientation.y;
220 state.
q.z() = pose.orientation.z;
221 state.
q.w() = pose.orientation.w;
223 state.
v.x() = twist.linear.x;
224 state.
v.y() = twist.linear.y;
225 state.
v.z() = twist.linear.z;
226 state.
w.x() = twist.angular.x;
227 state.
w.y() = twist.angular.y;
228 state.
w.z() = twist.angular.z;
230 state.
v_dot.x() = accel.linear.x;
231 state.
v_dot.y() = accel.linear.y;
232 state.
v_dot.z() = accel.linear.z;
233 state.
w_dot.x() = accel.angular.x;
234 state.
w_dot.y() = accel.angular.y;
235 state.
w_dot.z() = accel.angular.z;
248 if (!Base::init(hw, root_nh, controller_nh))
254 std::string solver_type = controller_nh.
param(
"ik_solver", std::string(
"example_solver"));
256 solver_loader_ = std::make_unique<pluginlib::ClassLoader<IKSolver>>(
"cartesian_trajectory_controller",
"ros_"
262 ik_solver_.reset(solver_loader_->createUnmanagedInstance(solver_type));
270 if (!ik_solver_->init(robot_chain_, root_nh, controller_nh))
280 const size_t size = joint_handles_.size();
282 KDL::JntArray current(size);
283 KDL::JntArray target(size);
286 goal.p[0] =
cmd.p.x();
287 goal.p[1] =
cmd.p.y();
288 goal.p[2] =
cmd.p.z();
289 goal.M = KDL::Rotation::Quaternion(
cmd.q.x(),
cmd.q.y(),
cmd.q.z(),
cmd.q.w());
292 for (
size_t i = 0; i < size; ++i)
294 current(i) = joint_handles_[i].getPosition();
298 ik_solver_->cartToJnt(current, goal, target);
301 for (
size_t i = 0; i < size; ++i)
303 joint_handles_[i].setCommand(target(i));
315 if (!Base::init(hw, root_nh, controller_nh))
320 ik_solver_ = std::make_unique<KDL::ChainIkSolverVel_wdls>(robot_chain_);
326 const size_t size = joint_handles_.size();
328 KDL::JntArray current(size);
329 KDL::JntArray target(size);
332 goal.vel[0] =
cmd.v.x();
333 goal.vel[1] =
cmd.v.y();
334 goal.vel[2] =
cmd.v.z();
335 goal.rot[0] =
cmd.w.x();
336 goal.rot[1] =
cmd.w.y();
337 goal.rot[2] =
cmd.w.z();
340 for (
size_t i = 0; i < size; ++i)
342 current(i) = joint_handles_[i].getPosition();
346 ik_solver_->CartToJnt(current, goal, target);
349 for (
size_t i = 0; i < size; ++i)
351 joint_handles_[i].setCommand(target(i));
363 if (!Base::init(hw, root_nh, controller_nh))
369 pose_publisher_ = controller_nh.
advertise<geometry_msgs::PoseStamped>(
"reference_pose", 10);
370 twist_publisher_ = controller_nh.
advertise<geometry_msgs::TwistStamped>(
"reference_twist", 10);
378 geometry_msgs::PoseStamped p;
379 p.header.frame_id = this->robot_base_;
381 p.pose.position.x =
cmd.p.x();
382 p.pose.position.y =
cmd.p.y();
383 p.pose.position.z =
cmd.p.z();
384 p.pose.orientation.x =
cmd.q.x();
385 p.pose.orientation.y =
cmd.q.y();
386 p.pose.orientation.z =
cmd.q.z();
387 p.pose.orientation.w =
cmd.q.w();
389 pose_publisher_.publish(p);
392 geometry_msgs::TwistStamped t;
393 t.header.frame_id = this->robot_base_;
395 t.twist.linear.x =
cmd.v.x();
396 t.twist.linear.y =
cmd.v.y();
397 t.twist.linear.z =
cmd.v.z();
398 t.twist.angular.x =
cmd.w.x();
399 t.twist.angular.y =
cmd.w.y();
400 t.twist.angular.z =
cmd.w.z();
402 twist_publisher_.publish(t);