Base class of trajectory generators.
More...
#include <trajectory_generator.h>
|
std::unique_ptr< KDL::VelocityProfile > | cartesianTrapVelocityProfile (const double &max_velocity_scaling_factor, const double &max_acceleration_scaling_factor, const std::unique_ptr< KDL::Path > &path) const |
| build cartesian velocity profile for the path More...
|
|
Base class of trajectory generators.
Note: All derived classes cannot have a start velocity
Definition at line 92 of file trajectory_generator.h.
◆ TrajectoryGenerator()
◆ ~TrajectoryGenerator()
virtual pilz_industrial_motion_planner::TrajectoryGenerator::~TrajectoryGenerator |
( |
| ) |
|
|
virtualdefault |
◆ cartesianTrapVelocityProfile()
std::unique_ptr< KDL::VelocityProfile > pilz_industrial_motion_planner::TrajectoryGenerator::cartesianTrapVelocityProfile |
( |
const double & |
max_velocity_scaling_factor, |
|
|
const double & |
max_acceleration_scaling_factor, |
|
|
const std::unique_ptr< KDL::Path > & |
path |
|
) |
| const |
|
protected |
build cartesian velocity profile for the path
Uses the path to get the cartesian length and the angular distance from start to goal. The trap profile returns uses the longer distance of translational and rotational motion.
Definition at line 274 of file trajectory_generator.cpp.
◆ generate()
generate robot trajectory with given sampling time
- Parameters
-
req | motion plan request |
res | motion plan response |
sampling_time | sampling time of the generate trajectory |
- Returns
- motion plan succeed/fail, detailed information in motion plan response
Definition at line 293 of file trajectory_generator.cpp.
◆ clock_
const std::unique_ptr<rclcpp::Clock> pilz_industrial_motion_planner::TrajectoryGenerator::clock_ |
|
protected |
◆ MAX_SCALING_FACTOR
constexpr double pilz_industrial_motion_planner::TrajectoryGenerator::MAX_SCALING_FACTOR { 1. } |
|
staticconstexprprotected |
◆ MIN_SCALING_FACTOR
constexpr double pilz_industrial_motion_planner::TrajectoryGenerator::MIN_SCALING_FACTOR { 0.0001 } |
|
staticconstexprprotected |
◆ planner_limits_
◆ robot_model_
const moveit::core::RobotModelConstPtr pilz_industrial_motion_planner::TrajectoryGenerator::robot_model_ |
|
protected |
◆ VELOCITY_TOLERANCE
constexpr double pilz_industrial_motion_planner::TrajectoryGenerator::VELOCITY_TOLERANCE { 1e-8 } |
|
staticconstexprprotected |
The documentation for this class was generated from the following files: