joint_trajectory_msg_utils.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 #pragma once
31 
32 
33 #include <algorithm>
34 #include <iterator>
35 #include <string>
36 #include <vector>
37 
38 #include <ros/console.h>
39 #include <ros/time.h>
40 #include <trajectory_msgs/JointTrajectory.h>
41 
43 
45 {
46 namespace internal
47 {
48 
50 {
51 public:
52  IsBeforePoint(const ros::Time& msg_start_time) : msg_start_time_(msg_start_time) {}
53 
54  bool operator()(const ros::Time& time, const trajectory_msgs::JointTrajectoryPoint& point)
55  {
56  const ros::Time point_start_time = msg_start_time_ + point.time_from_start;
57  return time < point_start_time;
58  }
59 
60 private:
62 };
63 
69 inline ros::Time startTime(const trajectory_msgs::JointTrajectory& msg,
70  const ros::Time& time)
71 {
72  return msg.header.stamp.isZero() ? time : msg.header.stamp;
73 }
74 
75 } // namespace
76 
83 inline bool isValid(const trajectory_msgs::JointTrajectoryPoint& point, const unsigned int joint_dim)
84 {
85  if (!point.positions.empty() && point.positions.size() != joint_dim) {return false;}
86  if (!point.velocities.empty() && point.velocities.size() != joint_dim) {return false;}
87  if (!point.accelerations.empty() && point.accelerations.size() != joint_dim) {return false;}
88  return true;
89 }
90 
95 inline bool isValid(const trajectory_msgs::JointTrajectory& msg)
96 {
97  const std::vector<std::string>::size_type joint_dim = msg.joint_names.size();
98 
99  typedef std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator PointConstIterator;
100 
101  for (PointConstIterator it = msg.points.begin(); it != msg.points.end(); ++it)
102  {
103  const std::iterator_traits<PointConstIterator>::difference_type index = std::distance(msg.points.begin(), it);
104 
105  if(!isValid(*it, joint_dim))
106  {
107  ROS_ERROR_STREAM("Invalid trajectory point at index: " << index <<
108  ". Size mismatch in joint names, position, velocity or acceleration data.");
109  return false;
110  }
111  }
112  return true;
113 }
114 
119 inline bool isTimeStrictlyIncreasing(const trajectory_msgs::JointTrajectory& msg)
120 {
121  if (msg.points.size() < 2) {return true;}
122 
123  typedef std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator PointConstIterator;
124 
125  PointConstIterator it = msg.points.begin();
126  PointConstIterator end_it = --msg.points.end();
127  while (it != end_it)
128  {
129  const ros::Duration& t1 = it->time_from_start;
130  const ros::Duration& t2 = (++it)->time_from_start;
131  if (t1 >= t2) {return false;}
132  }
133  return true;
134 }
135 
150 inline std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator
151 findPoint(const trajectory_msgs::JointTrajectory& msg,
152  const ros::Time& time)
153 {
154  // Message trajectory start time
155  // If message time is == 0.0, the trajectory should start at the current time
156  const ros::Time msg_start_time = internal::startTime(msg, time);
157  internal::IsBeforePoint isBeforePoint(msg_start_time);
158 
159  typedef std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator ConstIterator;
160  const ConstIterator first = msg.points.begin();
161  const ConstIterator last = msg.points.end();
162 
163  return (first == last || isBeforePoint(time, *first))
164  ? last // Optimization when time preceeds all segments, or when an empty range is passed
165  : --std::upper_bound(first, last, time, isBeforePoint); // Notice decrement operator
166 }
167 
168 } // namespace
joint_trajectory_controller::isValid
bool isValid(const trajectory_msgs::JointTrajectoryPoint &point, const unsigned int joint_dim)
Definition: joint_trajectory_msg_utils.h:83
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
joint_trajectory_controller::internal::IsBeforePoint::IsBeforePoint
IsBeforePoint(const ros::Time &msg_start_time)
Definition: joint_trajectory_msg_utils.h:52
time.h
trajectory_interface.h
joint_trajectory_controller::findPoint
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.
Definition: joint_trajectory_msg_utils.h:151
console.h
joint_trajectory_controller::internal::IsBeforePoint
Definition: joint_trajectory_msg_utils.h:49
joint_trajectory_controller
Definition: hold_trajectory_builder.h:35
TimeBase< Time, Duration >::isZero
bool isZero() const
joint_trajectory_controller::internal::IsBeforePoint::msg_start_time_
ros::Time msg_start_time_
Definition: joint_trajectory_msg_utils.h:61
ros::Time
ros::Duration
joint_trajectory_controller::isTimeStrictlyIncreasing
bool isTimeStrictlyIncreasing(const trajectory_msgs::JointTrajectory &msg)
Definition: joint_trajectory_msg_utils.h:119
joint_trajectory_controller::internal::IsBeforePoint::operator()
bool operator()(const ros::Time &time, const trajectory_msgs::JointTrajectoryPoint &point)
Definition: joint_trajectory_msg_utils.h:54
joint_trajectory_controller::internal::startTime
ros::Time startTime(const trajectory_msgs::JointTrajectory &msg, const ros::Time &time)
Definition: joint_trajectory_msg_utils.h:69


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sun Mar 3 2024 03:19:26