moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
pilz_industrial_motion_planner::TrajectoryGenerator Class Referenceabstract

Base class of trajectory generators. More...

#include <trajectory_generator.h>

Inheritance diagram for pilz_industrial_motion_planner::TrajectoryGenerator:
Inheritance graph
[legend]
Collaboration diagram for pilz_industrial_motion_planner::TrajectoryGenerator:
Collaboration graph
[legend]

Classes

class  MotionPlanInfo
 This class is used to extract needed information from motion plan request. More...
 

Public Member Functions

 TrajectoryGenerator (const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
 
virtual ~TrajectoryGenerator ()=default
 
bool generate (const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, double sampling_time=0.1)
 generate robot trajectory with given sampling time More...
 

Protected Member Functions

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...
 

Protected Attributes

const moveit::core::RobotModelConstPtr robot_model_
 
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
 
const std::unique_ptr< rclcpp::Clock > clock_
 

Static Protected Attributes

static constexpr double MIN_SCALING_FACTOR { 0.0001 }
 
static constexpr double MAX_SCALING_FACTOR { 1. }
 
static constexpr double VELOCITY_TOLERANCE { 1e-8 }
 

Detailed Description

Base class of trajectory generators.

Note: All derived classes cannot have a start velocity

Definition at line 92 of file trajectory_generator.h.

Constructor & Destructor Documentation

◆ TrajectoryGenerator()

pilz_industrial_motion_planner::TrajectoryGenerator::TrajectoryGenerator ( const moveit::core::RobotModelConstPtr &  robot_model,
const pilz_industrial_motion_planner::LimitsContainer planner_limits 
)
inline

Definition at line 95 of file trajectory_generator.h.

◆ ~TrajectoryGenerator()

virtual pilz_industrial_motion_planner::TrajectoryGenerator::~TrajectoryGenerator ( )
virtualdefault

Member Function Documentation

◆ 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 284 of file trajectory_generator.cpp.

Here is the call graph for this function:

◆ generate()

bool pilz_industrial_motion_planner::TrajectoryGenerator::generate ( const planning_scene::PlanningSceneConstPtr &  scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res,
double  sampling_time = 0.1 
)

generate robot trajectory with given sampling time

Parameters
reqmotion plan request
resmotion plan response
sampling_timesampling time of the generate trajectory
Returns
motion plan succeed/fail, detailed information in motion plan response

Definition at line 303 of file trajectory_generator.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ clock_

const std::unique_ptr<rclcpp::Clock> pilz_industrial_motion_planner::TrajectoryGenerator::clock_
protected

Definition at line 277 of file trajectory_generator.h.

◆ MAX_SCALING_FACTOR

constexpr double pilz_industrial_motion_planner::TrajectoryGenerator::MAX_SCALING_FACTOR { 1. }
staticconstexprprotected

Definition at line 275 of file trajectory_generator.h.

◆ MIN_SCALING_FACTOR

constexpr double pilz_industrial_motion_planner::TrajectoryGenerator::MIN_SCALING_FACTOR { 0.0001 }
staticconstexprprotected

Definition at line 274 of file trajectory_generator.h.

◆ planner_limits_

const pilz_industrial_motion_planner::LimitsContainer pilz_industrial_motion_planner::TrajectoryGenerator::planner_limits_
protected

Definition at line 273 of file trajectory_generator.h.

◆ robot_model_

const moveit::core::RobotModelConstPtr pilz_industrial_motion_planner::TrajectoryGenerator::robot_model_
protected

Definition at line 272 of file trajectory_generator.h.

◆ VELOCITY_TOLERANCE

constexpr double pilz_industrial_motion_planner::TrajectoryGenerator::VELOCITY_TOLERANCE { 1e-8 }
staticconstexprprotected

Definition at line 276 of file trajectory_generator.h.


The documentation for this class was generated from the following files: