joint_trajectory_segment.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 // C++ standard
34 #include <cmath>
35 #include <stdexcept>
36 #include <string>
37 #include <vector>
38 
39 // angles
40 #include <angles/angles.h>
41 
42 // ROS messages
43 #include <control_msgs/FollowJointTrajectoryAction.h>
44 #include <trajectory_msgs/JointTrajectoryPoint.h>
45 
46 // ros_controls
48 
49 // Project
52 
54 {
55 
69 template <class Segment>
70 class JointTrajectorySegment : public Segment
71 {
72 public:
73  typedef typename Segment::Scalar Scalar;
74  typedef typename Segment::Time Time;
75 
78 
79  struct State : public Segment::State
80  {
81  typedef typename Segment::State::Scalar Scalar;
82  State() : Segment::State() {}
83  State(unsigned int size) : Segment::State(size) {}
84 
93  State(const trajectory_msgs::JointTrajectoryPoint& point,
94  const std::vector<Scalar>& position_offset = std::vector<Scalar>())
95  {
96  init(point, position_offset);
97  }
98 
99  void init(const trajectory_msgs::JointTrajectoryPoint& point,
100  const std::vector<Scalar>& position_offset = std::vector<Scalar>())
101  {
102  using std::invalid_argument;
103 
104  const unsigned int joint_dim = point.positions.size();
105 
106  // Preconditions
107  if (!isValid(point, joint_dim))
108  {
109  throw(invalid_argument("Size mismatch in trajectory point position, velocity or acceleration data."));
110  }
111  if (!position_offset.empty() && joint_dim != position_offset.size())
112  {
113  throw(invalid_argument("Size mismatch between trajectory point "
114  "and vector specifying whether joints wrap around."));
115  }
116 
117  // Initialize state
118  if (!point.positions.empty()) {this->position.resize(joint_dim);}
119  if (!point.velocities.empty()) {this->velocity.resize(joint_dim);}
120  if (!point.accelerations.empty()) {this->acceleration.resize(joint_dim);}
121 
122  for (unsigned int i = 0; i < joint_dim; ++i)
123  {
124  // Apply position offset only if it was specified
125  const Scalar offset = position_offset.empty() ? 0.0 : position_offset[i];
126 
127  if (!point.positions.empty()) {this->position[i] = point.positions[i] + offset;}
128  if (!point.velocities.empty()) {this->velocity[i] = point.velocities[i];}
129  if (!point.accelerations.empty()) {this->acceleration[i] = point.accelerations[i];}
130  }
131  }
132  };
133 
142  JointTrajectorySegment(const Time& start_time,
143  const State& start_state,
144  const Time& end_time,
145  const State& end_state)
146  : rt_goal_handle_(),
147  tolerances_()
148  {
149  Segment::init(start_time, start_state, end_time, end_state);
150  }
151 
163  JointTrajectorySegment(const ros::Time& traj_start_time,
164  const trajectory_msgs::JointTrajectoryPoint& start_point,
165  const trajectory_msgs::JointTrajectoryPoint& end_point,
166  const std::vector<Scalar>& position_offset = std::vector<Scalar>())
167  : rt_goal_handle_(),
168  tolerances_()
169  {
170  if (start_point.positions.size() != end_point.positions.size())
171  {
172  throw(std::invalid_argument("Can't construct segment from ROS message: "
173  "Start/end points data size mismatch."));
174  }
175 
176  const Time start_time = (traj_start_time + start_point.time_from_start).toSec();
177  const Time end_time = (traj_start_time + end_point.time_from_start).toSec();
178 
179  try
180  {
181  const State start_state(start_point, position_offset);
182  const State end_state(end_point, position_offset);
183 
184  this->init(start_time, start_state,
185  end_time, end_state);
186  }
187  catch(const std::invalid_argument& ex)
188  {
189  std::string msg = "Can't construct segment from ROS message: " + std::string(ex.what());
190  throw(std::invalid_argument(msg));
191  }
192  }
193 
195  RealtimeGoalHandlePtr getGoalHandle() const {return rt_goal_handle_;}
196 
198  void setGoalHandle(RealtimeGoalHandlePtr rt_goal_handle) {rt_goal_handle_ = rt_goal_handle;}
199 
202 
204  void setTolerances(const SegmentTolerancesPerJoint<Scalar>& tolerances) {tolerances_ = tolerances;}
205 
206 private:
207  RealtimeGoalHandlePtr rt_goal_handle_;
209 };
210 
220 template <class Scalar>
221 Scalar wraparoundJointOffset(const Scalar& prev_position,
222  const Scalar& next_position,
223  const bool& angle_wraparound)
224 {
225  // Return value
226  Scalar pos_offset = 0.0;
227 
228  if (angle_wraparound)
229  {
230  Scalar dist = angles::shortest_angular_distance(prev_position, next_position);
231 
232  // Deal with singularity at M_PI shortest distance
233  if (std::abs(std::abs(dist) - M_PI) < 1e-9)
234  {
235  dist = next_position > prev_position ? std::abs(dist) : -std::abs(dist);
236  }
237  pos_offset = (prev_position + dist) - next_position;
238  }
239 
240  return pos_offset;
241 }
242 
243 } // namespace
boost::shared_ptr< RealtimeGoalHandle > RealtimeGoalHandlePtr
const SegmentTolerancesPerJoint< Scalar > & getTolerances() const
void init(const trajectory_msgs::JointTrajectoryPoint &point, const std::vector< Scalar > &position_offset=std::vector< Scalar >())
void setGoalHandle(RealtimeGoalHandlePtr rt_goal_handle)
Set the (realtime) goal handle associated to this segment.
realtime_tools::RealtimeServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RealtimeGoalHandle
Scalar wraparoundJointOffset(const Scalar &prev_position, const Scalar &next_position, const bool &angle_wraparound)
State(const trajectory_msgs::JointTrajectoryPoint &point, const std::vector< Scalar > &position_offset=std::vector< Scalar >())
Class representing a multi-dimensional quintic spline segment with a start and end time...
Trajectory segment tolerances per Joint.
Definition: tolerances.h:95
JointTrajectorySegment(const ros::Time &traj_start_time, const trajectory_msgs::JointTrajectoryPoint &start_point, const trajectory_msgs::JointTrajectoryPoint &end_point, const std::vector< Scalar > &position_offset=std::vector< Scalar >())
Construct a segment from start and end points (boundary conditions) specified in ROS message format...
JointTrajectorySegment(const Time &start_time, const State &start_state, const Time &end_time, const State &end_state)
Construct segment from start and end states (boundary conditions).
void setTolerances(const SegmentTolerancesPerJoint< Scalar > &tolerances)
Set the tolerances this segment is associated to.
bool isValid(const trajectory_msgs::JointTrajectoryPoint &point, const unsigned int joint_dim)
def shortest_angular_distance(from_angle, to_angle)


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Feb 3 2023 03:19:15