30 #include <cartesian_control_msgs/FollowCartesianTrajectoryGoal.h>
31 #include <cartesian_control_msgs/FollowCartesianTrajectoryResult.h>
32 #include <cartesian_control_msgs/FollowCartesianTrajectoryFeedback.h>
33 #include <control_msgs/FollowJointTrajectoryGoal.h>
34 #include <control_msgs/FollowJointTrajectoryFeedback.h>
103 template <
class TrajectoryType,
class FeedbackType>
155 bool setGoal(TrajectoryType goal);
230 for (
const std::string& joint : resources)
249 control_msgs::FollowJointTrajectoryGoal tmp = goal;
253 auto msg = goal.trajectory.joint_names;
254 auto expected = joint_names_;
255 std::vector<size_t> msg_joints(msg.size());
256 if (msg.size() != expected.size())
259 ROS_WARN(
"Not forwarding trajectory. It contains wrong number of joints");
262 for (
auto msg_it = msg.begin(); msg_it != msg.end(); ++msg_it)
264 auto expected_it = std::find(expected.begin(), expected.end(), *msg_it);
265 if (expected.end() == expected_it)
267 ROS_WARN_STREAM(
"Not forwarding trajectory. It contains at least one unexpected joint name: " << *msg_it);
272 const size_t msg_dist = std::distance(msg.begin(), msg_it);
273 const size_t expected_dist = std::distance(expected.begin(), expected_it);
274 msg_joints[msg_dist] = expected_dist;
279 tmp.trajectory.joint_names = expected;
280 tmp.trajectory.points.clear();
282 for (
auto point : goal.trajectory.points)
284 trajectory_msgs::JointTrajectoryPoint p{ point };
286 for (
size_t i = 0; i < expected.size(); ++i)
288 auto jnt_id = msg_joints[i];
290 if (point.positions.size() == expected.size())
291 p.positions[jnt_id] = point.positions[i];
292 if (point.velocities.size() == expected.size())
293 p.velocities[jnt_id] = point.velocities[i];
294 if (point.accelerations.size() == expected.size())
295 p.accelerations[jnt_id] = point.accelerations[i];
296 if (point.effort.size() == expected.size())
297 p.effort[jnt_id] = point.effort[i];
299 tmp.trajectory.points.push_back(p);
302 if (goal_callback_ !=
nullptr)
314 if (goal_callback_ !=
nullptr)
316 goal_callback_(goal);