39 #include <kdl/velocityprofile_trap.hpp>
47 for (
unsigned int i=0; i<size; i++)
48 generators_[i] =
new KDL::VelocityProfile_Trap(max_vel, max_acc);
52 TrajectoryGenerator::~TrajectoryGenerator()
54 for (
unsigned int i=0; i<generators_.size(); i++)
55 delete generators_[i];
58 void TrajectoryGenerator::generate(
const trajectory_msgs::JointTrajectory& traj_in, trajectory_msgs::JointTrajectory& traj_out)
60 ROS_INFO(
"Generating trajectory for list of points of size %d", (
int) traj_in.points.size());
63 if (traj_in.points.size() < 2){
64 ROS_WARN(
"Trajectory message should contain at least two points, but it contains %d joints. Returning original trajectory", (
int)traj_in.points.size());
70 trajectory_msgs::JointTrajectory traj_res = traj_in;
71 traj_res.points.clear();
72 trajectory_msgs::JointTrajectoryPoint points_tmp;
73 points_tmp.positions.resize(generators_.size());
74 points_tmp.velocities.resize(generators_.size());
75 points_tmp.accelerations.resize(generators_.size());
77 double initial_time = traj_in.points[0].time_from_start.toSec();
79 for (
unsigned int pnt=0; pnt<traj_in.points.size()-1; pnt++){
81 if (traj_in.points[pnt].positions.size() != generators_.size() ||
82 traj_in.points[pnt+1].positions.size() != generators_.size()){
83 ROS_ERROR(
"The point lists in the trajectory do not have the same size as the generators");
88 for (
unsigned int i=0; i<generators_.size(); i++)
89 generators_[i]->SetProfile(traj_in.points[pnt].positions[i], traj_in.points[pnt+1].positions[i]);
92 double max_time = (traj_in.points[pnt+1].time_from_start - traj_in.points[pnt].time_from_start).toSec();
93 for (
unsigned int i=0; i<generators_.size(); i++)
94 if (generators_[i]->Duration() > max_time)
95 max_time = generators_[i]->Duration();
98 for (
unsigned int i=0; i<generators_.size(); i++)
99 generators_[i]->SetProfileDuration(traj_in.points[pnt].positions[i], traj_in.points[pnt+1].positions[i], max_time);
102 unsigned int steps = fmax(10, (
unsigned int)(max_time / 0.1));
104 for (
unsigned int s=0;
s<=steps;
s++){
105 for (
unsigned int i=0; i<generators_.size(); i++){
106 points_tmp.positions[i] = generators_[i]->Pos(time);
107 points_tmp.velocities[i] = generators_[i]->Vel(time);
108 points_tmp.accelerations[i] = generators_[i]->Acc(time);
111 traj_res.points.push_back(points_tmp);
112 time += max_time/(double)steps;
114 initial_time += max_time;