Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <joint_trajectory_generator/trajectory_generation.h>
00040 #include <kdl/velocityprofile_trap.hpp>
00041
00042
00043 namespace trajectory{
00044
00045 TrajectoryGenerator::TrajectoryGenerator(double max_vel, double max_acc, unsigned int size)
00046 : generators_(size)
00047 {
00048 for (unsigned int i=0; i<size; i++)
00049 generators_[i] = new KDL::VelocityProfile_Trap(max_vel, max_acc);
00050 }
00051
00052
00053 TrajectoryGenerator::~TrajectoryGenerator()
00054 {
00055 for (unsigned int i=0; i<generators_.size(); i++)
00056 delete generators_[i];
00057 }
00058
00059 void TrajectoryGenerator::generate(const trajectory_msgs::JointTrajectory& traj_in, trajectory_msgs::JointTrajectory& traj_out)
00060 {
00061 ROS_DEBUG("Generating trajectory for list of points of size %d", (int) traj_in.points.size());
00062
00063
00064 if (traj_in.points.size() < 2){
00065 ROS_WARN("Trajectory message should contain at least two points, but it contains %d points. Returning original trajectory", (int)traj_in.points.size());
00066 traj_out = traj_in;
00067 throw ros::Exception("Trajectory contains fewer than two points.");
00068 }
00069
00070
00071 trajectory_msgs::JointTrajectory traj_res = traj_in;
00072 traj_res.points.clear();
00073 trajectory_msgs::JointTrajectoryPoint points_tmp;
00074 points_tmp.positions.resize(generators_.size());
00075 points_tmp.velocities.resize(generators_.size());
00076 points_tmp.accelerations.resize(generators_.size());
00077
00078 double initial_time = traj_in.points[0].time_from_start.toSec();
00079
00080 for (unsigned int pnt=0; pnt<traj_in.points.size()-1; pnt++){
00081
00082 if (traj_in.points[pnt].positions.size() != generators_.size() ||
00083 traj_in.points[pnt+1].positions.size() != generators_.size()){
00084 ROS_ERROR("The point lists in the trajectory do not have the same size as the generators");
00085 return;
00086 }
00087
00088
00089 for (unsigned int i=0; i<generators_.size(); i++)
00090 generators_[i]->SetProfile(traj_in.points[pnt].positions[i], traj_in.points[pnt+1].positions[i]);
00091
00092
00093 double max_time = (traj_in.points[pnt+1].time_from_start - traj_in.points[pnt].time_from_start).toSec();
00094 for (unsigned int i=0; i<generators_.size(); i++)
00095 if (generators_[i]->Duration() > max_time)
00096 max_time = generators_[i]->Duration();
00097
00098
00099 for (unsigned int i=0; i<generators_.size(); i++)
00100 generators_[i]->SetProfileDuration(traj_in.points[pnt].positions[i], traj_in.points[pnt+1].positions[i], max_time);
00101
00102
00103 unsigned int steps = fmax(10, (unsigned int)(max_time / 0.1));
00104 double time = 0;
00105 for (unsigned int s=0; s<=steps; s++){
00106 for (unsigned int i=0; i<generators_.size(); i++){
00107 points_tmp.positions[i] = generators_[i]->Pos(time);
00108 points_tmp.velocities[i] = generators_[i]->Vel(time);
00109 points_tmp.accelerations[i] = generators_[i]->Acc(time);
00110 }
00111 points_tmp.time_from_start = ros::Duration(initial_time) + ros::Duration(time);
00112 traj_res.points.push_back(points_tmp);
00113 time += max_time/(double)steps;
00114 }
00115 initial_time += max_time;
00116 }
00117 traj_out = traj_res;
00118 }
00119
00120
00121
00122 }