init_joint_trajectory.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics S.L. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #ifndef JOINT_TRAJECTORY_CONTROLLER_INIT_JOINT_TRAJECTORY_H
31 #define JOINT_TRAJECTORY_CONTROLLER_INIT_JOINT_TRAJECTORY_H
32 
33 // C++ standard
34 #include <algorithm>
35 #include <iomanip>
36 #include <sstream>
37 #include <stdexcept>
38 #include <vector>
39 
40 // Boost
41 #include <boost/shared_ptr.hpp>
42 
43 // ROS messages
44 #include <control_msgs/FollowJointTrajectoryAction.h>
45 #include <trajectory_msgs/JointTrajectoryPoint.h>
46 
47 // ros_controls
49 
50 // Project
53 
55 {
56 
57 namespace internal
58 {
64 template <class T>
65 inline std::vector<unsigned int> mapping(const T& t1, const T& t2)
66 {
67  typedef unsigned int SizeType;
68 
69  // t1 must be a subset of t2
70  if (t1.size() > t2.size()) {return std::vector<SizeType>();}
71 
72  std::vector<SizeType> mapping_vector(t1.size()); // Return value
73  for (typename T::const_iterator t1_it = t1.begin(); t1_it != t1.end(); ++t1_it)
74  {
75  typename T::const_iterator t2_it = std::find(t2.begin(), t2.end(), *t1_it);
76  if (t2.end() == t2_it) {return std::vector<SizeType>();}
77  else
78  {
79  const SizeType t1_dist = std::distance(t1.begin(), t1_it);
80  const SizeType t2_dist = std::distance(t2.begin(), t2_it);
81  mapping_vector[t1_dist] = t2_dist;
82  }
83  }
84  return mapping_vector;
85 }
86 
87 } // namespace
88 
93 template <class Trajectory>
95 {
98  typedef typename Trajectory::value_type TrajectoryPerJoint;
99  typedef typename TrajectoryPerJoint::value_type Segment;
100  typedef typename Segment::Scalar Scalar;
101 
103  : current_trajectory(0),
104  joint_names(0),
105  angle_wraparound(0),
106  rt_goal_handle(),
107  default_tolerances(0),
108  other_time_base(0),
109  allow_partial_joints_goal(false),
110  error_string(0)
111  {}
112 
113  Trajectory* current_trajectory;
114  std::vector<std::string>* joint_names;
115  std::vector<bool>* angle_wraparound;
116  RealtimeGoalHandlePtr rt_goal_handle;
120  std::string* error_string;
121 
122  void setErrorString(const std::string &msg) const
123  {
124  if(error_string)
125  {
126  *error_string = msg;
127  }
128  }
129 };
130 
131 template <class Trajectory>
132 bool isNotEmpty(typename Trajectory::value_type trajPerJoint)
133 {
134  return !trajPerJoint.empty();
135 };
136 
202 // TODO: Return useful bits of current trajectory if input msg is useless?
203 template <class Trajectory>
204 Trajectory initJointTrajectory(const trajectory_msgs::JointTrajectory& msg,
205  const ros::Time& time,
208 {
209  typedef typename Trajectory::value_type TrajectoryPerJoint;
210  typedef typename TrajectoryPerJoint::value_type Segment;
211  typedef typename Segment::Scalar Scalar;
212  typedef typename TrajectoryPerJoint::const_iterator TrajIter;
213 
214  const unsigned int n_joints = msg.joint_names.size();
215 
216  const ros::Time msg_start_time = internal::startTime(msg, time); // Message start time
217 
218  ROS_DEBUG_STREAM("Figuring out new trajectory starting at time "
219  << std::fixed << std::setprecision(3) << msg_start_time.toSec());
220 
221  std::string error_string;
222 
223  // Empty trajectory
224  if (msg.points.empty())
225  {
226  error_string = "Trajectory message contains empty trajectory. Nothing to convert.";
227  ROS_DEBUG_STREAM(error_string);
228  options.setErrorString(error_string);
229  return Trajectory();
230  }
231 
232  // Non strictly-monotonic waypoints
233  if (!isTimeStrictlyIncreasing(msg))
234  {
235  error_string = "Trajectory message contains waypoints that are not strictly increasing in time.";
236  ROS_ERROR_STREAM(error_string);
237  options.setErrorString(error_string);
238  return Trajectory();
239  }
240 
241  // Validate options
242  const bool has_current_trajectory = options.current_trajectory && !options.current_trajectory->empty();
243  const bool has_joint_names = options.joint_names && !options.joint_names->empty();
244  const bool has_angle_wraparound = options.angle_wraparound && !options.angle_wraparound->empty();
245  const bool has_rt_goal_handle = options.rt_goal_handle != NULL;
246  const bool has_other_time_base = options.other_time_base != NULL;
247  const bool has_default_tolerances = options.default_tolerances != NULL;
248 
249  if (!has_current_trajectory && has_angle_wraparound)
250  {
251  ROS_WARN("Vector specifying whether joints wrap around will not be used because no current trajectory was given.");
252  }
253 
254  // Compute trajectory start time and data extraction time associated to the 'other' time base, if it applies
255  // The o_ prefix indicates that time values are represented in this 'other' time base.
256  ros::Time o_time;
257  ros::Time o_msg_start_time;
258  if (has_other_time_base)
259  {
260  ros::Duration msg_start_duration = msg_start_time - time;
261  o_time = *options.other_time_base;
262  o_msg_start_time = o_time + msg_start_duration;
263  ROS_DEBUG_STREAM("Using alternate time base. In it, the new trajectory starts at time "
264  << std::fixed << std::setprecision(3) << o_msg_start_time.toSec());
265  }
266  else
267  {
268  o_time = time;
269  o_msg_start_time = msg_start_time;
270  }
271 
272  const std::vector<std::string> joint_names = has_joint_names ? *(options.joint_names) : msg.joint_names;
273 
274  if (has_angle_wraparound)
275  {
276  // Preconditions
277  const unsigned int n_angle_wraparound = options.angle_wraparound->size();
278  if (n_angle_wraparound != joint_names.size())
279  {
280  error_string = "Cannot create trajectory from message. "
281  "Vector specifying whether joints wrap around has an invalid size.";
282  ROS_ERROR_STREAM(error_string);
283  options.setErrorString(error_string);
284  return Trajectory();
285  }
286  }
287 
288  // If partial joints goals are not allowed, goal should specify all controller joints
289  if (!options.allow_partial_joints_goal)
290  {
291  if (msg.joint_names.size() != joint_names.size())
292  {
293  error_string = "Cannot create trajectory from message. It does not contain the expected joints.";
294  ROS_ERROR_STREAM(error_string);
295  options.setErrorString(error_string);
296  return Trajectory();
297  }
298  }
299 
300  // Mapping vector contains the map between the message joint order and the expected joint order
301  // If unspecified, a trivial map is computed
302  std::vector<unsigned int> mapping_vector = internal::mapping(msg.joint_names,joint_names);
303 
304  if (mapping_vector.empty())
305  {
306  error_string = "Cannot create trajectory from message. It does not contain the expected joints.";
307  ROS_ERROR_STREAM(error_string);
308  options.setErrorString(error_string);
309  return Trajectory();
310  }
311 
312  // Tolerances to be used in all new segments
313  SegmentTolerances<Scalar> tolerances = has_default_tolerances ?
314  *(options.default_tolerances) : SegmentTolerances<Scalar>(n_joints);
315 
316  if (has_rt_goal_handle && options.rt_goal_handle->gh_.getGoal())
317  {
318  updateSegmentTolerances<Scalar>(*(options.rt_goal_handle->gh_.getGoal()), joint_names, tolerances);
319  }
320 
321  // Find first point of new trajectory occurring after current time
322  // This point is used later on in this function, but is computed here, in advance because if the trajectory message
323  // contains a trajectory in the past, we can quickly return without spending additional computational resources
324  std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator
325  msg_it = findPoint(msg, time); // Points to last point occurring before current time (NOTE: Using time, not o_time)
326  if (msg_it == msg.points.end())
327  {
328  msg_it = msg.points.begin(); // Entire trajectory is after current time
329  }
330  else
331  {
332  ++msg_it; // Points to first point after current time OR sequence end
333  if (msg_it == msg.points.end())
334  {
335  ros::Duration last_point_dur = time - (msg_start_time + (--msg_it)->time_from_start);
336  std::stringstream error_stringstream;
337  error_stringstream << "Dropping all " << msg.points.size();
338  error_stringstream << " trajectory point(s), as they occur before the current time.\n";
339  error_stringstream << "Last point is " << last_point_dur.toSec();
340  error_stringstream << "s in the past.";
341 
342  error_string = error_stringstream.str();
343  ROS_WARN_STREAM(error_string);
344  options.setErrorString(error_string);
345  return Trajectory();
346  }
347  else if ( // If the first point is at time zero and no start time is set in the header, skip it silently
348  msg.points.begin()->time_from_start.isZero() &&
349  msg.header.stamp.isZero() &&
350  std::distance(msg.points.begin(), msg_it) == 1
351  )
352  {
353  ROS_DEBUG_STREAM("Dropping first trajectory point at time=0. " <<
354  "First valid point will be reached at time_from_start " <<
355  std::fixed << std::setprecision(3) << msg_it->time_from_start.toSec() << "s.");
356  }
357  else
358  {
359  ros::Duration next_point_dur = msg_start_time + msg_it->time_from_start - time;
360  ROS_WARN_STREAM("Dropping first " << std::distance(msg.points.begin(), msg_it) <<
361  " trajectory point(s) out of " << msg.points.size() <<
362  ", as they occur before the current time.\n" <<
363  "First valid point will be reached in " << std::fixed << std::setprecision(3) <<
364  next_point_dur.toSec() << "s.");
365  }
366  }
367 
368  // Initialize result trajectory: combination of:
369  // - Useful segments of currently followed trajectory
370  // - Useful segments of new trajectory (contained in ROS message)
371  Trajectory result_traj; // Currently empty
372 
373  // Set active goal to segments after current time
374  if (has_current_trajectory)
375  {
376  result_traj = *(options.current_trajectory);
377 
378  //Iterate to all segments after current time to set the new goal handler
379  for (unsigned int joint_id=0; joint_id < joint_names.size();joint_id++)
380  {
381  const TrajectoryPerJoint& curr_joint_traj = result_traj[joint_id];
382  TrajIter active_seg = findSegment(curr_joint_traj, o_time.toSec()); // Currently active segment
383 
384  while (std::distance(active_seg, curr_joint_traj.end())>=1)
385  {
386  (result_traj[joint_id])[std::distance(curr_joint_traj.begin(),active_seg)].setGoalHandle(options.rt_goal_handle);
387  ++active_seg;
388  }
389  }
390  }
391  else
392  result_traj.resize(joint_names.size());
393 
394  //Iterate through the joints that are in the message, in the order of the mapping vector
395  //for (unsigned int joint_id=0; joint_id < joint_names.size();joint_id++)
396  for (unsigned int msg_joint_it=0; msg_joint_it < mapping_vector.size();msg_joint_it++)
397  {
398  std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator it = msg_it;
399  if (!isValid(*it, it->positions.size()))
400  throw(std::invalid_argument("Size mismatch in trajectory point position, velocity or acceleration data."));
401 
402  TrajectoryPerJoint result_traj_per_joint; // Currently empty
403  unsigned int joint_id = mapping_vector[msg_joint_it];
404 
405  // Initialize offsets due to wrapping joints to zero
406  std::vector<Scalar> position_offset(1, 0.0);
407 
408  //Initialize segment tolerance per joint
409  SegmentTolerancesPerJoint<Scalar> tolerances_per_joint;
410  tolerances_per_joint.state_tolerance = tolerances.state_tolerance[joint_id];
411  tolerances_per_joint.goal_state_tolerance = tolerances.goal_state_tolerance[joint_id];
412  tolerances_per_joint.goal_time_tolerance = tolerances.goal_time_tolerance;
413 
414  // Bridge current trajectory to new one
415  if (has_current_trajectory)
416  {
417  const TrajectoryPerJoint& curr_joint_traj = (*options.current_trajectory)[joint_id];
418 
419  // Get the last time and state that will be executed from the current trajectory
420  const typename Segment::Time last_curr_time = std::max(o_msg_start_time.toSec(), o_time.toSec()); // Important!
421  typename Segment::State last_curr_state;
422  sample(curr_joint_traj, last_curr_time, last_curr_state);
423 
424  // Get the first time and state that will be executed from the new trajectory
425  trajectory_msgs::JointTrajectoryPoint point_per_joint;
426  if (!it->positions.empty()) {point_per_joint.positions.resize(1, it->positions[msg_joint_it]);}
427  if (!it->velocities.empty()) {point_per_joint.velocities.resize(1, it->velocities[msg_joint_it]);}
428  if (!it->accelerations.empty()) {point_per_joint.accelerations.resize(1, it->accelerations[msg_joint_it]);}
429  point_per_joint.time_from_start = it->time_from_start;
430 
431  const typename Segment::Time first_new_time = o_msg_start_time.toSec() + (it->time_from_start).toSec();
432  typename Segment::State first_new_state(point_per_joint); // Here offsets are not yet applied
433 
434  // Compute offsets due to wrapping joints
435  if (has_angle_wraparound)
436  {
437  position_offset[0] = wraparoundJointOffset(last_curr_state.position[0],
438  first_new_state.position[0],
439  (*options.angle_wraparound)[joint_id]);
440  }
441 
442  // Apply offset to first state that will be executed from the new trajectory
443  first_new_state = typename Segment::State(point_per_joint, position_offset); // Now offsets are applied
444 
445  // Add useful segments of current trajectory to result
446  {
447  TrajIter first = findSegment(curr_joint_traj, o_time.toSec()); // Currently active segment
448  TrajIter last = findSegment(curr_joint_traj, last_curr_time); // Segment active when new trajectory starts
449  if (first == curr_joint_traj.end() || last == curr_joint_traj.end())
450  {
451  error_string = "Unexpected error: Could not find segments in current trajectory. Please contact the package maintainer.";
452  ROS_ERROR_STREAM(error_string);
453  options.setErrorString(error_string);
454  return Trajectory();
455  }
456  result_traj_per_joint.insert(result_traj_per_joint.begin(), first, ++last); // Range [first,last) will still be executed
457  }
458 
459  // Add segment bridging current and new trajectories to result
460  Segment bridge_seg(last_curr_time, last_curr_state,
461  first_new_time, first_new_state);
462  bridge_seg.setGoalHandle(options.rt_goal_handle);
463  if (has_rt_goal_handle) {bridge_seg.setTolerances(tolerances_per_joint);}
464  result_traj_per_joint.push_back(bridge_seg);
465  }
466 
467  // Constants used in log statement at the end
468  const unsigned int num_old_segments = result_traj_per_joint.size() -1;
469  const unsigned int num_new_segments = std::distance(it, msg.points.end()) -1;
470 
471  // Add useful segments of new trajectory to result
472  // - Construct all trajectory segments occurring after current time
473  // - As long as there remain two trajectory points we can construct the next trajectory segment
474  while (std::distance(it, msg.points.end()) >= 2)
475  {
476  std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator next_it = it; ++next_it;
477 
478  trajectory_msgs::JointTrajectoryPoint it_point_per_joint, next_it_point_per_joint;
479 
480  if (!isValid(*it, it->positions.size()))
481  throw(std::invalid_argument("Size mismatch in trajectory point position, velocity or acceleration data."));
482  if (!it->positions.empty()) {it_point_per_joint.positions.resize(1, it->positions[msg_joint_it]);}
483  if (!it->velocities.empty()) {it_point_per_joint.velocities.resize(1, it->velocities[msg_joint_it]);}
484  if (!it->accelerations.empty()) {it_point_per_joint.accelerations.resize(1, it->accelerations[msg_joint_it]);}
485  it_point_per_joint.time_from_start = it->time_from_start;
486 
487  if (!isValid(*next_it, next_it->positions.size()))
488  throw(std::invalid_argument("Size mismatch in trajectory point position, velocity or acceleration data."));
489  if (!next_it->positions.empty()) {next_it_point_per_joint.positions.resize(1, next_it->positions[msg_joint_it]);}
490  if (!next_it->velocities.empty()) {next_it_point_per_joint.velocities.resize(1, next_it->velocities[msg_joint_it]);}
491  if (!next_it->accelerations.empty()) {next_it_point_per_joint.accelerations.resize(1, next_it->accelerations[msg_joint_it]);}
492  next_it_point_per_joint.time_from_start = next_it->time_from_start;
493 
494  Segment segment(o_msg_start_time, it_point_per_joint, next_it_point_per_joint, position_offset);
495  segment.setGoalHandle(options.rt_goal_handle);
496  if (has_rt_goal_handle) {segment.setTolerances(tolerances_per_joint);}
497  result_traj_per_joint.push_back(segment);
498  ++it;
499  }
500 
501  // Useful debug info
502  std::stringstream log_str;
503  log_str << "Trajectory of joint " << joint_names[joint_id] << "has " << result_traj_per_joint.size() << " segments";
504  if (has_current_trajectory)
505  {
506  log_str << ":";
507  log_str << "\n- " << num_old_segments << " segment(s) will still be executed from previous trajectory.";
508  log_str << "\n- 1 segment added for transitioning between the current trajectory and first point of the input message.";
509  if (num_new_segments > 0) {log_str << "\n- " << num_new_segments << " new segments (" << (num_new_segments + 1) <<
510  " points) taken from the input trajectory.";}
511  }
512  else {log_str << ".";}
513  ROS_DEBUG_STREAM(log_str.str());
514 
515  if (result_traj_per_joint.size() > 0)
516  result_traj[joint_id] = result_traj_per_joint;
517  }
518 
519  // If the trajectory for all joints is empty, empty the trajectory vector
520  typename Trajectory::const_iterator trajIter = std::find_if (result_traj.begin(), result_traj.end(), isNotEmpty<Trajectory>);
521  if (trajIter == result_traj.end())
522  {
523  result_traj.clear();
524  }
525 
526  return result_traj;
527 }
528 
529 } // namespace
530 
531 #endif // header guard
std::vector< StateTolerances< Scalar > > state_tolerance
Definition: tolerances.h:82
Trajectory initJointTrajectory(const trajectory_msgs::JointTrajectory &msg, const ros::Time &time, const InitJointTrajectoryOptions< Trajectory > &options=InitJointTrajectoryOptions< Trajectory >())
Initialize a joint trajectory from ROS message data.
boost::shared_ptr< RealtimeGoalHandle > RealtimeGoalHandlePtr
Trajectory::const_iterator sample(const Trajectory &trajectory, const typename Trajectory::value_type::Time &time, typename Trajectory::value_type::State &state)
Sample a trajectory at a specified time.
TrajectoryIterator findSegment(TrajectoryIterator first, TrajectoryIterator last, const Time &time)
Find an iterator to the segment containing a specified time.
#define ROS_WARN(...)
bool isTimeStrictlyIncreasing(const trajectory_msgs::JointTrajectory &msg)
options
Scalar wraparoundJointOffset(const Scalar &prev_position, const Scalar &next_position, const bool &angle_wraparound)
realtime_tools::RealtimeServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RealtimeGoalHandle
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
std::vector< unsigned int > mapping(const T &t1, const T &t2)
bool isNotEmpty(typename Trajectory::value_type trajPerJoint)
std::vector< trajectory_msgs::JointTrajectoryPoint >::const_iterator findPoint(const trajectory_msgs::JointTrajectory &msg, const ros::Time &time)
Find an iterator to the trajectory point with the greatest start time < time.
Options used when initializing a joint trajectory from ROS message data.
Trajectory segment tolerances per Joint.
Definition: tolerances.h:95
#define ROS_ERROR_STREAM(args)
std::vector< StateTolerances< Scalar > > goal_state_tolerance
Definition: tolerances.h:85
ros::Time startTime(const trajectory_msgs::JointTrajectory &msg, const ros::Time &time)
bool isValid(const trajectory_msgs::JointTrajectoryPoint &point, const unsigned int joint_dim)
Trajectory segment tolerances.
Definition: tolerances.h:73


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Apr 18 2020 03:58:18