trajectory_generation.cpp
Go to the documentation of this file.
1 
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Wim Meeussen
36  *********************************************************************/
37 
38 #include <ros/ros.h>
40 #include <kdl/velocityprofile_trap.hpp>
41 
42 
43 namespace trajectory{
44 
45  TrajectoryGenerator::TrajectoryGenerator(double max_vel, double max_acc, unsigned int size)
46  : generators_(size)
47  {
48  for (unsigned int i=0; i<size; i++)
49  generators_[i] = new KDL::VelocityProfile_Trap(max_vel, max_acc);
50  }
51 
52 
54  {
55  for (unsigned int i=0; i<generators_.size(); i++)
56  delete generators_[i];
57  }
58 
59  void TrajectoryGenerator::generate(const trajectory_msgs::JointTrajectory& traj_in, trajectory_msgs::JointTrajectory& traj_out)
60  {
61  ROS_DEBUG("Generating trajectory for list of points of size %d", (int) traj_in.points.size());
62 
63  // check trajectory message
64  if (traj_in.points.size() < 2){
65  ROS_WARN("Trajectory message should contain at least two points, but it contains %d points. Returning original trajectory", (int)traj_in.points.size());
66  traj_out = traj_in;
67  throw ros::Exception("Trajectory contains fewer than two points.");
68  }
69 
70  // default result
71  trajectory_msgs::JointTrajectory traj_res = traj_in;
72  traj_res.points.clear();
73  trajectory_msgs::JointTrajectoryPoint points_tmp;
74  points_tmp.positions.resize(generators_.size());
75  points_tmp.velocities.resize(generators_.size());
76  points_tmp.accelerations.resize(generators_.size());
77 
78  double initial_time = traj_in.points[0].time_from_start.toSec();
79 
80  for (unsigned int pnt=0; pnt<traj_in.points.size()-1; pnt++){
81  // check
82  if (traj_in.points[pnt].positions.size() != generators_.size() ||
83  traj_in.points[pnt+1].positions.size() != generators_.size()){
84  ROS_ERROR("The point lists in the trajectory do not have the same size as the generators");
85  return;
86  }
87 
88  // generate initial profiles
89  for (unsigned int i=0; i<generators_.size(); i++)
90  generators_[i]->SetProfile(traj_in.points[pnt].positions[i], traj_in.points[pnt+1].positions[i]);
91 
92  // find profile that takes most time
93  double max_time = (traj_in.points[pnt+1].time_from_start - traj_in.points[pnt].time_from_start).toSec();
94  for (unsigned int i=0; i<generators_.size(); i++)
95  if (generators_[i]->Duration() > max_time)
96  max_time = generators_[i]->Duration();
97 
98  // generate profiles with max time
99  for (unsigned int i=0; i<generators_.size(); i++)
100  generators_[i]->SetProfileDuration(traj_in.points[pnt].positions[i], traj_in.points[pnt+1].positions[i], max_time);
101 
102  // copy results in trajectory message
103  unsigned int steps = fmax(10, (unsigned int)(max_time / 0.1));
104  double time = 0;
105  for (unsigned int s=0; s<=steps; s++){
106  for (unsigned int i=0; i<generators_.size(); i++){
107  points_tmp.positions[i] = generators_[i]->Pos(time);
108  points_tmp.velocities[i] = generators_[i]->Vel(time);
109  points_tmp.accelerations[i] = generators_[i]->Acc(time);
110  }
111  points_tmp.time_from_start = ros::Duration(initial_time) + ros::Duration(time);
112  traj_res.points.push_back(points_tmp);
113  time += max_time/(double)steps;
114  }
115  initial_time += max_time;
116  }
117  traj_out = traj_res;
118  }
119 
120 
121 
122 }
TrajectoryGenerator(double max_vel, double max_acc, unsigned int size)
XmlRpcServer s
#define ROS_WARN(...)
void generate(const trajectory_msgs::JointTrajectory &traj_in, trajectory_msgs::JointTrajectory &traj_out)
std::vector< KDL::VelocityProfile * > generators_
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


joint_trajectory_generator
Author(s): Eitan Marder-Eppstein, Wim Meeusen
autogenerated on Fri Jun 7 2019 22:06:38