38 #ifndef TRAJECTORY_UNWRAP_H_
39 #define TRAJECTORY_UNWRAP_H_
43 #include <urdf/joint.h>
44 #include <trajectory_msgs/JointTrajectory.h>
49 void unwrap(
urdf::Model &robot_model,
const trajectory_msgs::JointTrajectory& traj_in,
50 trajectory_msgs::JointTrajectory& traj_out)
55 int num_jnts = traj_in.joint_names.size();
56 int traj_pnts = traj_in.points.size();
59 for(
int i=0; i<num_jnts; i++)
61 joint = robot_model.getJoint(traj_in.joint_names[i]);
62 if(joint->type == urdf::Joint::REVOLUTE)
64 for(
int j=1; j<traj_pnts; j++)
69 traj_out.points[j].positions[i] = traj_out.points[j-1].positions[i] + diff;
72 if(joint->type == urdf::Joint::CONTINUOUS)
74 for(
int j=1; j<traj_pnts; j++)
76 traj_out.points[j].positions[i] = traj_out.points[j-1].positions[i] +
angles::shortest_angular_distance(traj_out.points[j-1].positions[i],traj_out.points[j].positions[i]);