moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_trajectory.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Adam Leeper */
36 
37 #pragma once
38 
41 #include <moveit_msgs/msg/robot_trajectory.hpp>
42 #include <moveit_msgs/msg/robot_state.hpp>
43 #include <deque>
44 #include <memory>
45 #include <optional>
46 
47 #include <rcl/error_handling.h>
48 #include <rcl/time.h>
49 #include <rclcpp/clock.hpp>
50 #include <rclcpp/rclcpp.hpp>
51 #include <rclcpp/time.hpp>
52 #include <rclcpp/utilities.hpp>
53 
55 {
56 MOVEIT_CLASS_FORWARD(RobotTrajectory); // Defines RobotTrajectoryPtr, ConstPtr, WeakPtr... etc
57 
61 {
62 public:
64  explicit RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model);
65 
70  RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group);
71 
78  RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model, const moveit::core::JointModelGroup* group);
79 
82 
87  RobotTrajectory(const RobotTrajectory& other, bool deepcopy = false);
88 
89  const moveit::core::RobotModelConstPtr& getRobotModel() const
90  {
91  return robot_model_;
92  }
93 
95  {
96  return group_;
97  }
98 
99  const std::string& getGroupName() const;
100 
101  RobotTrajectory& setGroupName(const std::string& group_name)
102  {
103  group_ = robot_model_->getJointModelGroup(group_name);
104  return *this;
105  }
106 
107  std::size_t getWayPointCount() const
108  {
109  return waypoints_.size();
110  }
111 
112  std::size_t size() const
113  {
114  assert(waypoints_.size() == duration_from_previous_.size());
115  return waypoints_.size();
116  }
117 
118  const moveit::core::RobotState& getWayPoint(std::size_t index) const
119  {
120  return *waypoints_[index];
121  }
122 
124  {
125  return *waypoints_.back();
126  }
127 
129  {
130  return *waypoints_.front();
131  }
132 
133  moveit::core::RobotStatePtr& getWayPointPtr(std::size_t index)
134  {
135  return waypoints_[index];
136  }
137 
138  moveit::core::RobotStatePtr& getLastWayPointPtr()
139  {
140  return waypoints_.back();
141  }
142 
143  moveit::core::RobotStatePtr& getFirstWayPointPtr()
144  {
145  return waypoints_.front();
146  }
147 
148  const std::deque<double>& getWayPointDurations() const
149  {
150  return duration_from_previous_;
151  }
152 
157  double getWayPointDurationFromStart(std::size_t index) const;
158 
159  [[deprecated]] double getWaypointDurationFromStart(std::size_t index) const;
160 
161  double getWayPointDurationFromPrevious(std::size_t index) const
162  {
163  if (duration_from_previous_.size() > index)
164  return duration_from_previous_[index];
165  else
166  return 0.0;
167  }
168 
169  RobotTrajectory& setWayPointDurationFromPrevious(std::size_t index, double value)
170  {
171  if (duration_from_previous_.size() <= index)
172  duration_from_previous_.resize(index + 1, 0.0);
173  duration_from_previous_[index] = value;
174  return *this;
175  }
176 
177  bool empty() const
178  {
179  return waypoints_.empty();
180  }
181 
188  {
189  return addSuffixWayPoint(std::make_shared<moveit::core::RobotState>(state), dt);
190  }
191 
197  RobotTrajectory& addSuffixWayPoint(const moveit::core::RobotStatePtr& state, double dt)
198  {
199  state->update();
200  waypoints_.push_back(state);
201  duration_from_previous_.push_back(dt);
202  return *this;
203  }
204 
206  {
207  return addPrefixWayPoint(std::make_shared<moveit::core::RobotState>(state), dt);
208  }
209 
210  RobotTrajectory& addPrefixWayPoint(const moveit::core::RobotStatePtr& state, double dt)
211  {
212  state->update();
213  waypoints_.push_front(state);
214  duration_from_previous_.push_front(dt);
215  return *this;
216  }
217 
218  RobotTrajectory& insertWayPoint(std::size_t index, const moveit::core::RobotState& state, double dt)
219  {
220  return insertWayPoint(index, std::make_shared<moveit::core::RobotState>(state), dt);
221  }
222 
223  RobotTrajectory& insertWayPoint(std::size_t index, const moveit::core::RobotStatePtr& state, double dt)
224  {
225  state->update();
226  waypoints_.insert(waypoints_.begin() + index, state);
227  duration_from_previous_.insert(duration_from_previous_.begin() + index, dt);
228  return *this;
229  }
230 
241  RobotTrajectory& append(const RobotTrajectory& source, double dt, size_t start_index = 0,
242  size_t end_index = std::numeric_limits<std::size_t>::max());
243 
245 
247  {
248  waypoints_.clear();
249  duration_from_previous_.clear();
250  return *this;
251  }
252 
253  double getDuration() const;
254 
255  double getAverageSegmentDuration() const;
256 
257  void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory& trajectory,
258  const std::vector<std::string>& joint_filter = std::vector<std::string>()) const;
259 
267  const trajectory_msgs::msg::JointTrajectory& trajectory);
268 
276  const moveit_msgs::msg::RobotTrajectory& trajectory);
277 
286  const moveit_msgs::msg::RobotState& state,
287  const moveit_msgs::msg::RobotTrajectory& trajectory);
288 
290 
293 
300  void findWayPointIndicesForDurationAfterStart(const double& duration, int& before, int& after, double& blend) const;
301 
302  // TODO support visitor function for interpolation, or at least different types.
309  bool getStateAtDurationFromStart(const double request_duration, moveit::core::RobotStatePtr& output_state) const;
310 
311  class Iterator
312  {
313  std::deque<moveit::core::RobotStatePtr>::iterator waypoint_iterator_;
314  std::deque<double>::iterator duration_iterator_;
315 
316  public:
317  explicit Iterator(const std::deque<moveit::core::RobotStatePtr>::iterator& waypoint_iterator,
318  const std::deque<double>::iterator& duration_iterator)
319  : waypoint_iterator_(waypoint_iterator), duration_iterator_(duration_iterator)
320  {
321  }
323  {
324  waypoint_iterator_++;
325  duration_iterator_++;
326  return *this;
327  }
329  {
330  Iterator retval = *this;
331  ++(*this);
332  return retval;
333  }
334  bool operator==(const Iterator& other) const
335  {
336  return ((waypoint_iterator_ == other.waypoint_iterator_) && (duration_iterator_ == other.duration_iterator_));
337  }
338  bool operator!=(const Iterator& other) const
339  {
340  return !(*this == other);
341  }
342  std::pair<moveit::core::RobotStatePtr, double> operator*() const
343  {
344  return std::pair{ *waypoint_iterator_, *duration_iterator_ };
345  }
346 
347  // iterator traits
348  using difference_type = long;
349  using value_type = std::pair<moveit::core::RobotStatePtr, double>;
350  using pointer = const std::pair<moveit::core::RobotStatePtr, double>*;
351  using reference = std::pair<moveit::core::RobotStatePtr, double>;
352  using iterator_category = std::input_iterator_tag;
353  };
354 
356  {
357  assert(waypoints_.size() == duration_from_previous_.size());
358  return Iterator(waypoints_.begin(), duration_from_previous_.begin());
359  }
361  {
362  assert(waypoints_.size() == duration_from_previous_.size());
363  return Iterator(waypoints_.end(), duration_from_previous_.end());
364  }
378  void print(std::ostream& out, std::vector<int> variable_indexes = std::vector<int>()) const;
379 
380 private:
381  moveit::core::RobotModelConstPtr robot_model_;
382  const moveit::core::JointModelGroup* group_;
383  std::deque<moveit::core::RobotStatePtr> waypoints_;
384  std::deque<double> duration_from_previous_;
385  rclcpp::Clock clock_ros_;
386 };
387 
389 std::ostream& operator<<(std::ostream& out, const RobotTrajectory& trajectory);
390 
397 [[nodiscard]] double path_length(RobotTrajectory const& trajectory);
398 
403 [[nodiscard]] std::optional<double> smoothness(RobotTrajectory const& trajectory);
404 
409 [[nodiscard]] std::optional<double> waypoint_density(RobotTrajectory const& trajectory);
410 
411 } // namespace robot_trajectory
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const std::pair< moveit::core::RobotStatePtr, double > * pointer
Iterator(const std::deque< moveit::core::RobotStatePtr >::iterator &waypoint_iterator, const std::deque< double >::iterator &duration_iterator)
std::pair< moveit::core::RobotStatePtr, double > reference
std::pair< moveit::core::RobotStatePtr, double > value_type
bool operator!=(const Iterator &other) const
bool operator==(const Iterator &other) const
std::pair< moveit::core::RobotStatePtr, double > operator*() const
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & insertWayPoint(std::size_t index, const moveit::core::RobotStatePtr &state, double dt)
void swap(robot_trajectory::RobotTrajectory &other)
RobotTrajectory & setWayPointDurationFromPrevious(std::size_t index, double value)
double getWaypointDurationFromStart(std::size_t index) const
RobotTrajectory & addPrefixWayPoint(const moveit::core::RobotStatePtr &state, double dt)
const std::string & getGroupName() const
const moveit::core::RobotModelConstPtr & getRobotModel() const
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
RobotTrajectory(const moveit::core::RobotModelConstPtr &robot_model)
construct a trajectory for the whole robot
RobotTrajectory::Iterator end()
void print(std::ostream &out, std::vector< int > variable_indexes=std::vector< int >()) const
Print information about the trajectory.
bool getStateAtDurationFromStart(const double request_duration, moveit::core::RobotStatePtr &output_state) const
Gets a robot state corresponding to a supplied duration from start for the trajectory,...
const moveit::core::JointModelGroup * getGroup() const
void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
RobotTrajectory & setGroupName(const std::string &group_name)
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
const moveit::core::RobotState & getFirstWayPoint() const
RobotTrajectory & setRobotTrajectoryMsg(const moveit::core::RobotState &reference_state, const trajectory_msgs::msg::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
RobotTrajectory::Iterator begin()
RobotTrajectory & operator=(const RobotTrajectory &)=default
RobotTrajectory & append(const RobotTrajectory &source, double dt, size_t start_index=0, size_t end_index=std::numeric_limits< std::size_t >::max())
Add a specified part of a trajectory to the end of the current trajectory. The default (when start_in...
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
const std::deque< double > & getWayPointDurations() const
RobotTrajectory & insertWayPoint(std::size_t index, const moveit::core::RobotState &state, double dt)
double getWayPointDurationFromPrevious(std::size_t index) const
void findWayPointIndicesForDurationAfterStart(const double &duration, int &before, int &after, double &blend) const
Finds the waypoint indices before and after a duration from start.
RobotTrajectory & addPrefixWayPoint(const moveit::core::RobotState &state, double dt)
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotStatePtr &state, double dt)
Add a point to the trajectory.
moveit::core::RobotStatePtr & getLastWayPointPtr()
const moveit::core::RobotState & getWayPoint(std::size_t index) const
moveit::core::RobotStatePtr & getFirstWayPointPtr()
const moveit::core::RobotState & getLastWayPoint() const
double path_length(RobotTrajectory const &trajectory)
Calculate the path length of a given trajectory based on the accumulated robot state distances....
std::optional< double > waypoint_density(RobotTrajectory const &trajectory)
Calculate the waypoint density of a trajectory.
std::ostream & operator<<(std::ostream &out, const RobotTrajectory &trajectory)
Operator overload for printing trajectory to a stream.
std::optional< double > smoothness(RobotTrajectory const &trajectory)
Calculate the smoothness of a given trajectory.
MOVEIT_CLASS_FORWARD(RobotTrajectory)