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

#include <iterative_torque_limit_parameterization.h>

Public Member Functions

bool computeTimeStampsWithTorqueLimits (robot_trajectory::RobotTrajectory &trajectory, const geometry_msgs::Vector3 &gravity_vector, const std::vector< geometry_msgs::Wrench > &external_link_wrenches, const std::vector< double > &joint_torque_limits, double accel_limit_decrement_factor, const std::unordered_map< std::string, double > &velocity_limits, const std::unordered_map< std::string, double > &acceleration_limits, const double max_velocity_scaling_factor, const double max_acceleration_scaling_factor) 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...
 
 IterativeTorqueLimitParameterization (const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
 

Private Attributes

TimeOptimalTrajectoryGeneration totg_
 

Detailed Description

Definition at line 74 of file iterative_torque_limit_parameterization.h.

Constructor & Destructor Documentation

◆ IterativeTorqueLimitParameterization()

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

Definition at line 77 of file iterative_torque_limit_parameterization.cpp.

Member Function Documentation

◆ computeTimeStampsWithTorqueLimits()

bool trajectory_processing::IterativeTorqueLimitParameterization::computeTimeStampsWithTorqueLimits ( robot_trajectory::RobotTrajectory trajectory,
const geometry_msgs::Vector3 gravity_vector,
const std::vector< geometry_msgs::Wrench > &  external_link_wrenches,
const std::vector< double > &  joint_torque_limits,
double  accel_limit_decrement_factor,
const std::unordered_map< std::string, double > &  velocity_limits,
const std::unordered_map< std::string, double > &  acceleration_limits,
const double  max_velocity_scaling_factor,
const double  max_acceleration_scaling_factor 
) 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.
gravity_vectorFor example, (0, 0, -9.81). Units are m/s^2
external_link_wrenchesExternally-applied wrenches on each link. TODO(andyz): what frame is this in?
joint_torque_limitsTorque limits for each joint in N*m. Should all be >0.
accel_limit_decrement_factorTypically in the range [0.01-0.1]. This affects how fast acceleration limits are decreased while searching for a solution. Time-optimality of the output is accurate to approximately 100*accel_limit_decrement_factor %. For example, if accel_limit_decrement_factor is 0.1, the output should be within 10% of time-optimal.
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 84 of file iterative_torque_limit_parameterization.cpp.

Member Data Documentation

◆ totg_

TimeOptimalTrajectoryGeneration trajectory_processing::IterativeTorqueLimitParameterization::totg_
private

Definition at line 138 of file iterative_torque_limit_parameterization.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 27 2024 02:25:26