time_optimal_trajectory_generation.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011-2012, Georgia Tech Research Corporation
3  * All rights reserved.
4  *
5  * Author: Tobias Kunz <tobias@gatech.edu>
6  * Date: 05/2012
7  *
8  * Humanoid Robotics Lab Georgia Institute of Technology
9  * Director: Mike Stilman http://www.golems.org
10  *
11  * Algorithm details and publications:
12  * http://www.golems.org/node/1570
13  *
14  * This file is provided under the following "BSD-style" License:
15  * Redistribution and use in source and binary forms, with or
16  * without modification, are permitted provided that the following
17  * conditions are met:
18  * * Redistributions of source code must retain the above copyright
19  * notice, this list of conditions and the following disclaimer.
20  * * Redistributions in binary form must reproduce the above
21  * copyright notice, this list of conditions and the following
22  * disclaimer in the documentation and/or other materials provided
23  * with the distribution.
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
25  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
26  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
27  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
28  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
29  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
30  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
31  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
32  * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
33  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  */
38 
39 #pragma once
40 
41 #include <Eigen/Core>
42 #include <list>
45 #include <unordered_map>
46 
47 namespace trajectory_processing
48 {
50 {
51 public:
52  PathSegment(double length = 0.0) : length_(length)
53  {
54  }
55  virtual ~PathSegment() // is required for destructing derived classes
56  {
57  }
58  double getLength() const
59  {
60  return length_;
61  }
62  virtual Eigen::VectorXd getConfig(double s) const = 0;
63  virtual Eigen::VectorXd getTangent(double s) const = 0;
64  virtual Eigen::VectorXd getCurvature(double s) const = 0;
65  virtual std::list<double> getSwitchingPoints() const = 0;
66  virtual PathSegment* clone() const = 0;
67 
68  double position_;
69 
70 protected:
71  double length_;
72 };
73 
74 class Path
75 {
76 public:
77  Path(const std::list<Eigen::VectorXd>& path, double max_deviation = 0.0);
78  Path(const Path& path);
79  double getLength() const;
80  Eigen::VectorXd getConfig(double s) const;
81  Eigen::VectorXd getTangent(double s) const;
82  Eigen::VectorXd getCurvature(double s) const;
83 
89  double getNextSwitchingPoint(double s, bool& discontinuity) const;
90 
92  std::list<std::pair<double, bool>> getSwitchingPoints() const;
93 
94 private:
95  PathSegment* getPathSegment(double& s) const;
96  double length_;
97  std::list<std::pair<double, bool>> switching_points_;
98  std::list<std::unique_ptr<PathSegment>> path_segments_;
99 };
100 
102 {
103 public:
105  Trajectory(const Path& path, const Eigen::VectorXd& max_velocity, const Eigen::VectorXd& max_acceleration,
106  double time_step = 0.001);
107 
108  ~Trajectory();
109 
113  bool isValid() const;
114 
116  double getDuration() const;
117 
120  Eigen::VectorXd getPosition(double time) const;
122  Eigen::VectorXd getVelocity(double time) const;
124  Eigen::VectorXd getAcceleration(double time) const;
125 
126 private:
128  {
130  {
131  }
132  TrajectoryStep(double path_pos, double path_vel) : path_pos_(path_pos), path_vel_(path_vel)
133  {
134  }
135  double path_pos_;
136  double path_vel_;
137  double time_;
138  };
139 
140  bool getNextSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point, double& before_acceleration,
141  double& after_acceleration);
142  bool getNextAccelerationSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
143  double& before_acceleration, double& after_acceleration);
144  bool getNextVelocitySwitchingPoint(double path_pos, TrajectoryStep& next_switching_point, double& before_acceleration,
145  double& after_acceleration);
146  bool integrateForward(std::list<TrajectoryStep>& trajectory, double acceleration);
147  void integrateBackward(std::list<TrajectoryStep>& start_trajectory, double path_pos, double path_vel,
148  double acceleration);
149  double getMinMaxPathAcceleration(double path_position, double path_velocity, bool max);
150  double getMinMaxPhaseSlope(double path_position, double path_velocity, bool max);
151  double getAccelerationMaxPathVelocity(double path_pos) const;
152  double getVelocityMaxPathVelocity(double path_pos) const;
153  double getAccelerationMaxPathVelocityDeriv(double path_pos);
154  double getVelocityMaxPathVelocityDeriv(double path_pos);
155 
156  std::list<TrajectoryStep>::const_iterator getTrajectorySegment(double time) const;
157 
159  Eigen::VectorXd max_velocity_;
160  Eigen::VectorXd max_acceleration_;
161  unsigned int joint_num_;
162  bool valid_;
163  std::list<TrajectoryStep> trajectory_;
164  std::list<TrajectoryStep> end_trajectory_; // non-empty only if the trajectory generation failed.
165 
166  const double time_step_;
167 
168  mutable double cached_time_;
169  mutable std::list<TrajectoryStep>::const_iterator cached_trajectory_segment_;
170 };
171 
174 {
175 public:
176  TimeOptimalTrajectoryGeneration(const double path_tolerance = 0.1, const double resample_dt = 0.1,
177  const double min_angle_change = 0.001);
178 
191  bool computeTimeStamps(robot_trajectory::RobotTrajectory& trajectory, const double max_velocity_scaling_factor = 1.0,
192  const double max_acceleration_scaling_factor = 1.0) const override
193  {
194  std::unordered_map<std::string, double> empty;
195  return computeTimeStamps(trajectory, empty, empty, max_velocity_scaling_factor, max_acceleration_scaling_factor);
196  }
197 
213  const std::unordered_map<std::string, double>& velocity_limits,
214  const std::unordered_map<std::string, double>& acceleration_limits,
215  const double max_velocity_scaling_factor = 1.0,
216  const double max_acceleration_scaling_factor = 1.0) const;
217 
218 private:
224  bool hasMixedJointTypes(const moveit::core::JointModelGroup* group) const;
225 
231  double verifyScalingFactor(const double requested_scaling_factor) const;
232 
233  const double path_tolerance_;
234  const double resample_dt_;
235  const double min_angle_change_;
236 };
237 } // namespace trajectory_processing
trajectory_processing::Trajectory::TrajectoryStep::path_pos_
double path_pos_
Definition: time_optimal_trajectory_generation.h:135
trajectory_processing::PathSegment::getSwitchingPoints
virtual std::list< double > getSwitchingPoints() const =0
trajectory_processing::Path::getPathSegment
PathSegment * getPathSegment(double &s) const
Definition: time_optimal_trajectory_generation.cpp:260
trajectory_processing::Trajectory::getVelocityMaxPathVelocity
double getVelocityMaxPathVelocity(double path_pos) const
Definition: time_optimal_trajectory_generation.cpp:737
trajectory_processing::Trajectory::getVelocity
Eigen::VectorXd getVelocity(double time) const
Return the velocity vector for a given point in time.
Definition: time_optimal_trajectory_generation.cpp:822
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
trajectory_processing::Trajectory::cached_trajectory_segment_
std::list< TrajectoryStep >::const_iterator cached_trajectory_segment_
Definition: time_optimal_trajectory_generation.h:169
trajectory_processing::Trajectory::TrajectoryStep
Definition: time_optimal_trajectory_generation.h:127
trajectory_processing::Trajectory::TrajectoryStep::TrajectoryStep
TrajectoryStep(double path_pos, double path_vel)
Definition: time_optimal_trajectory_generation.h:132
s
XmlRpcServer s
trajectory_processing::Path::getLength
double getLength() const
Definition: time_optimal_trajectory_generation.cpp:255
trajectory_processing::PathSegment::getTangent
virtual Eigen::VectorXd getTangent(double s) const =0
trajectory_processing::Trajectory::getTrajectorySegment
std::list< TrajectoryStep >::const_iterator getTrajectorySegment(double time) const
Definition: time_optimal_trajectory_generation.cpp:782
trajectory_processing::Path::length_
double length_
Definition: time_optimal_trajectory_generation.h:96
trajectory_processing::Trajectory::TrajectoryStep::time_
double time_
Definition: time_optimal_trajectory_generation.h:137
trajectory_processing::PathSegment::PathSegment
PathSegment(double length=0.0)
Definition: time_optimal_trajectory_generation.h:52
robot_trajectory.h
trajectory_processing::Trajectory::~Trajectory
~Trajectory()
Definition: time_optimal_trajectory_generation.cpp:359
trajectory_processing::TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration
TimeOptimalTrajectoryGeneration(const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
Definition: time_optimal_trajectory_generation.cpp:859
robot_trajectory::RobotTrajectory
Maintain a sequence of waypoints and the time durations between these waypoints.
Definition: robot_trajectory.h:84
trajectory_processing::Path::switching_points_
std::list< std::pair< double, bool > > switching_points_
Definition: time_optimal_trajectory_generation.h:97
trajectory_processing::Trajectory::max_velocity_
Eigen::VectorXd max_velocity_
Definition: time_optimal_trajectory_generation.h:159
trajectory_processing::PathSegment::getCurvature
virtual Eigen::VectorXd getCurvature(double s) const =0
trajectory_processing::Path::getNextSwitchingPoint
double getNextSwitchingPoint(double s, bool &discontinuity) const
Get the next switching point.
Definition: time_optimal_trajectory_generation.cpp:292
trajectory_processing::Trajectory::cached_time_
double cached_time_
Definition: time_optimal_trajectory_generation.h:168
trajectory_processing::TimeOptimalTrajectoryGeneration
Definition: time_optimal_trajectory_generation.h:173
time_parameterization.h
trajectory_processing::TimeParameterization
Definition: time_parameterization.h:11
trajectory_processing::Trajectory::integrateBackward
void integrateBackward(std::list< TrajectoryStep > &start_trajectory, double path_pos, double path_vel, double acceleration)
Definition: time_optimal_trajectory_generation.cpp:626
trajectory_processing::Trajectory::valid_
bool valid_
Definition: time_optimal_trajectory_generation.h:162
trajectory_processing::TimeOptimalTrajectoryGeneration::path_tolerance_
const double path_tolerance_
Definition: time_optimal_trajectory_generation.h:233
trajectory_processing::Trajectory::getAccelerationMaxPathVelocityDeriv
double getAccelerationMaxPathVelocityDeriv(double path_pos)
Definition: time_optimal_trajectory_generation.cpp:748
trajectory_processing::Trajectory::getDuration
double getDuration() const
Returns the optimal duration of the trajectory.
Definition: time_optimal_trajectory_generation.cpp:777
trajectory_processing::Trajectory::TrajectoryStep::TrajectoryStep
TrajectoryStep()
Definition: time_optimal_trajectory_generation.h:129
trajectory_processing::Trajectory::TrajectoryStep::path_vel_
double path_vel_
Definition: time_optimal_trajectory_generation.h:136
trajectory_processing::Trajectory::max_acceleration_
Eigen::VectorXd max_acceleration_
Definition: time_optimal_trajectory_generation.h:160
trajectory_processing::Trajectory::time_step_
const double time_step_
Definition: time_optimal_trajectory_generation.h:166
trajectory_processing::Trajectory::getNextSwitchingPoint
bool getNextSwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
Definition: time_optimal_trajectory_generation.cpp:364
trajectory_processing::Trajectory::getNextAccelerationSwitchingPoint
bool getNextAccelerationSwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
Definition: time_optimal_trajectory_generation.cpp:411
trajectory_processing::Trajectory::getMinMaxPathAcceleration
double getMinMaxPathAcceleration(double path_position, double path_velocity, bool max)
Definition: time_optimal_trajectory_generation.cpp:683
trajectory_processing
Definition: iterative_spline_parameterization.h:43
trajectory_processing::Path::Path
Path(const std::list< Eigen::VectorXd > &path, double max_deviation=0.0)
Definition: time_optimal_trajectory_generation.cpp:192
trajectory_processing::Trajectory::trajectory_
std::list< TrajectoryStep > trajectory_
Definition: time_optimal_trajectory_generation.h:163
trajectory_processing::Path::getConfig
Eigen::VectorXd getConfig(double s) const
Definition: time_optimal_trajectory_generation.cpp:274
trajectory_processing::TimeOptimalTrajectoryGeneration::hasMixedJointTypes
bool hasMixedJointTypes(const moveit::core::JointModelGroup *group) const
Check if a combination of revolute and prismatic joints is used. path_tolerance_ is not valid,...
Definition: time_optimal_trajectory_generation.cpp:1046
trajectory_processing::Trajectory::Trajectory
Trajectory(const Path &path, const Eigen::VectorXd &max_velocity, const Eigen::VectorXd &max_acceleration, double time_step=0.001)
Generates a time-optimal trajectory.
Definition: time_optimal_trajectory_generation.cpp:313
trajectory_processing::Trajectory::getVelocityMaxPathVelocityDeriv
double getVelocityMaxPathVelocityDeriv(double path_pos)
Definition: time_optimal_trajectory_generation.cpp:754
trajectory_processing::Trajectory::getAcceleration
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
Definition: time_optimal_trajectory_generation.cpp:839
trajectory_processing::Trajectory::end_trajectory_
std::list< TrajectoryStep > end_trajectory_
Definition: time_optimal_trajectory_generation.h:164
trajectory_processing::Trajectory
Definition: time_optimal_trajectory_generation.h:101
trajectory_processing::TimeOptimalTrajectoryGeneration::resample_dt_
const double resample_dt_
Definition: time_optimal_trajectory_generation.h:234
trajectory_processing::PathSegment::position_
double position_
Definition: time_optimal_trajectory_generation.h:68
trajectory_processing::Trajectory::getMinMaxPhaseSlope
double getMinMaxPhaseSlope(double path_position, double path_velocity, bool max)
Definition: time_optimal_trajectory_generation.cpp:701
trajectory_processing::Path
Definition: time_optimal_trajectory_generation.h:74
trajectory_processing::Path::getSwitchingPoints
std::list< std::pair< double, bool > > getSwitchingPoints() const
Return a list of all switching points as a pair (arc length to switching point, discontinuity)
Definition: time_optimal_trajectory_generation.cpp:308
trajectory_processing::Trajectory::getAccelerationMaxPathVelocity
double getAccelerationMaxPathVelocity(double path_pos) const
Definition: time_optimal_trajectory_generation.cpp:706
trajectory_processing::TimeOptimalTrajectoryGeneration::computeTimeStamps
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Definition: time_optimal_trajectory_generation.h:191
trajectory_processing::Trajectory::getNextVelocitySwitchingPoint
bool getNextVelocitySwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
Definition: time_optimal_trajectory_generation.cpp:461
length
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
trajectory_processing::Path::path_segments_
std::list< std::unique_ptr< PathSegment > > path_segments_
Definition: time_optimal_trajectory_generation.h:98
trajectory_processing::Path::getTangent
Eigen::VectorXd getTangent(double s) const
Definition: time_optimal_trajectory_generation.cpp:280
trajectory_processing::Trajectory::joint_num_
unsigned int joint_num_
Definition: time_optimal_trajectory_generation.h:161
trajectory_processing::TimeOptimalTrajectoryGeneration::min_angle_change_
const double min_angle_change_
Definition: time_optimal_trajectory_generation.h:235
trajectory_processing::Trajectory::integrateForward
bool integrateForward(std::list< TrajectoryStep > &trajectory, double acceleration)
Definition: time_optimal_trajectory_generation.cpp:510
trajectory_processing::Trajectory::path_
Path path_
Definition: time_optimal_trajectory_generation.h:158
trajectory_processing::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(IterativeParabolicTimeParameterization)
This class modifies the timestamps of a trajectory to respect velocity and acceleration constraints.
trajectory_processing::PathSegment::length_
double length_
Definition: time_optimal_trajectory_generation.h:71
trajectory_processing::PathSegment::getLength
double getLength() const
Definition: time_optimal_trajectory_generation.h:58
trajectory_processing::Path::getCurvature
Eigen::VectorXd getCurvature(double s) const
Definition: time_optimal_trajectory_generation.cpp:286
trajectory_processing::TimeOptimalTrajectoryGeneration::verifyScalingFactor
double verifyScalingFactor(const double requested_scaling_factor) const
Check if the requested scaling factor is valid and if not, return 1.0.
Definition: time_optimal_trajectory_generation.cpp:1063
trajectory_processing::Trajectory::getPosition
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
Definition: time_optimal_trajectory_generation.cpp:805
trajectory_processing::PathSegment::clone
virtual PathSegment * clone() const =0
trajectory_processing::Trajectory::isValid
bool isValid() const
Call this method after constructing the object to make sure the trajectory generation succeeded witho...
Definition: time_optimal_trajectory_generation.cpp:772
trajectory_processing::PathSegment
Definition: time_optimal_trajectory_generation.h:49
trajectory_processing::PathSegment::getConfig
virtual Eigen::VectorXd getConfig(double s) const =0
trajectory_processing::PathSegment::~PathSegment
virtual ~PathSegment()
Definition: time_optimal_trajectory_generation.h:55


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri May 3 2024 02:28:41