Public Member Functions | Private Member Functions | Private Attributes | List of all members
trajectory_processing::TimeOptimalTrajectoryGeneration Class Reference

#include <time_optimal_trajectory_generation.h>

Inheritance diagram for trajectory_processing::TimeOptimalTrajectoryGeneration:
Inheritance graph
[legend]

Public Member Functions

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_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints. More...
 
bool computeTimeStamps (robot_trajectory::RobotTrajectory &trajectory, const std::unordered_map< std::string, double > &velocity_limits, const std::unordered_map< std::string, double > &acceleration_limits, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const
 Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints. More...
 
 TimeOptimalTrajectoryGeneration (const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
 
- Public Member Functions inherited from trajectory_processing::TimeParameterization
virtual ~TimeParameterization ()=default
 

Private Member Functions

bool hasMixedJointTypes (const moveit::core::JointModelGroup *group) const
 Check if a combination of revolute and prismatic joints is used. path_tolerance_ is not valid, if so. More...
 
double verifyScalingFactor (const double requested_scaling_factor) const
 Check if the requested scaling factor is valid and if not, return 1.0. More...
 

Private Attributes

const double min_angle_change_
 
const double path_tolerance_
 
const double resample_dt_
 

Detailed Description

Definition at line 173 of file time_optimal_trajectory_generation.h.

Constructor & Destructor Documentation

◆ TimeOptimalTrajectoryGeneration()

trajectory_processing::TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration ( const double  path_tolerance = 0.1,
const double  resample_dt = 0.1,
const double  min_angle_change = 0.001 
)

Definition at line 859 of file time_optimal_trajectory_generation.cpp.

Member Function Documentation

◆ computeTimeStamps() [1/2]

bool trajectory_processing::TimeOptimalTrajectoryGeneration::computeTimeStamps ( robot_trajectory::RobotTrajectory trajectory,
const double  max_velocity_scaling_factor = 1.0,
const double  max_acceleration_scaling_factor = 1.0 
) const
inlineoverridevirtual

Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints.

Parameters
[in,out]trajectoryA path which needs time-parameterization. It's OK if this path has already been time-parameterized; this function will re-time-parameterize it.
max_velocity_scaling_factorA factor in the range [0,1] which can slow down the trajectory.
max_acceleration_scaling_factorA factor in the range [0,1] which can slow down the trajectory.

Implements trajectory_processing::TimeParameterization.

Definition at line 191 of file time_optimal_trajectory_generation.h.

◆ computeTimeStamps() [2/2]

bool trajectory_processing::TimeOptimalTrajectoryGeneration::computeTimeStamps ( robot_trajectory::RobotTrajectory trajectory,
const std::unordered_map< std::string, double > &  velocity_limits,
const std::unordered_map< std::string, double > &  acceleration_limits,
const double  max_velocity_scaling_factor = 1.0,
const double  max_acceleration_scaling_factor = 1.0 
) const

Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints.

Parameters
[in,out]trajectoryA path which needs time-parameterization. It's OK if this path has already been time-parameterized; this function will re-time-parameterize it.
velocity_limitsJoint names and velocity limits in rad/s
acceleration_limitsJoint names and acceleration limits in rad/s^2
max_velocity_scaling_factorA factor in the range [0,1] which can slow down the trajectory.
max_acceleration_scaling_factorA factor in the range [0,1] which can slow down the trajectory.

Definition at line 865 of file time_optimal_trajectory_generation.cpp.

◆ hasMixedJointTypes()

bool trajectory_processing::TimeOptimalTrajectoryGeneration::hasMixedJointTypes ( const moveit::core::JointModelGroup group) const
private

Check if a combination of revolute and prismatic joints is used. path_tolerance_ is not valid, if so.

Parameters
groupThe JointModelGroup to check.
Returns
true if there are mixed joints.

Definition at line 1046 of file time_optimal_trajectory_generation.cpp.

◆ verifyScalingFactor()

double trajectory_processing::TimeOptimalTrajectoryGeneration::verifyScalingFactor ( const double  requested_scaling_factor) const
private

Check if the requested scaling factor is valid and if not, return 1.0.

Parameters
requested_scaling_factorThe desired maximum scaling factor to apply to the velocity or acceleration limits
Returns
The user requested scaling factor, if it is valid. Otherwise, return 1.0.

Definition at line 1063 of file time_optimal_trajectory_generation.cpp.

Member Data Documentation

◆ min_angle_change_

const double trajectory_processing::TimeOptimalTrajectoryGeneration::min_angle_change_
private

Definition at line 235 of file time_optimal_trajectory_generation.h.

◆ path_tolerance_

const double trajectory_processing::TimeOptimalTrajectoryGeneration::path_tolerance_
private

Definition at line 233 of file time_optimal_trajectory_generation.h.

◆ resample_dt_

const double trajectory_processing::TimeOptimalTrajectoryGeneration::resample_dt_
private

Definition at line 234 of file time_optimal_trajectory_generation.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:42