moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | Static Public Attributes | List of all members
chomp::ChompParameters Class Reference

#include <chomp_parameters.h>

Public Member Functions

 ChompParameters ()
 
virtual ~ChompParameters ()
 
void setRecoveryParams (double learning_rate, double ridge_factor, int planning_time_limit, int max_iterations)
 
bool setTrajectoryInitializationMethod (std::string method)
 

Public Attributes

double planning_time_limit_
 
int max_iterations_
 
int max_iterations_after_collision_free_
 
double smoothness_cost_weight_
 
double obstacle_cost_weight_
 
double learning_rate_
 
double smoothness_cost_velocity_
 
double smoothness_cost_acceleration_
 
double smoothness_cost_jerk_
 
bool use_stochastic_descent_
 
double ridge_factor_
 
bool use_pseudo_inverse_
 
double pseudo_inverse_ridge_factor_
 
double joint_update_limit_
 
double min_clearance_
 
double collision_threshold_
 
bool filter_mode_
 
std::string trajectory_initialization_method_
 
bool enable_failure_recovery_
 
int max_recovery_attempts_
 

Static Public Attributes

static const std::vector< std::string > VALID_INITIALIZATION_METHODS
 

Detailed Description

Definition at line 44 of file chomp_parameters.h.

Constructor & Destructor Documentation

◆ ChompParameters()

chomp::ChompParameters::ChompParameters ( )

Definition at line 43 of file chomp_parameters.cpp.

◆ ~ChompParameters()

chomp::ChompParameters::~ChompParameters ( )
virtualdefault

Member Function Documentation

◆ setRecoveryParams()

void chomp::ChompParameters::setRecoveryParams ( double  learning_rate,
double  ridge_factor,
int  planning_time_limit,
int  max_iterations 
)

sets the recovery parameters which can be changed in case CHOMP is not able to find a solution with the parameters set from the chomp_planning.yaml file

Parameters
learning_rate
ridge_factor
planning_time_limit
max_iterations

Definition at line 71 of file chomp_parameters.cpp.

Here is the caller graph for this function:

◆ setTrajectoryInitializationMethod()

bool chomp::ChompParameters::setTrajectoryInitializationMethod ( std::string  method)

sets a valid trajectory initialization method

Returns
true if a valid method (one of VALID_INITIALIZATION_METHODS) was specified

Definition at line 83 of file chomp_parameters.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ collision_threshold_

double chomp::ChompParameters::collision_threshold_

the collision threshold cost that needs to be maintained to avoid collisions

Definition at line 87 of file chomp_parameters.h.

◆ enable_failure_recovery_

bool chomp::ChompParameters::enable_failure_recovery_

if set to true, CHOMP tries to vary certain parameters to try and find a path if an initial path is not found with the specified chomp parameters

Definition at line 93 of file chomp_parameters.h.

◆ filter_mode_

bool chomp::ChompParameters::filter_mode_

Definition at line 88 of file chomp_parameters.h.

◆ joint_update_limit_

double chomp::ChompParameters::joint_update_limit_

set the update limit for the robot joints

Definition at line 85 of file chomp_parameters.h.

◆ learning_rate_

double chomp::ChompParameters::learning_rate_

learning rate used by the optimizer to find the local / global minima while reducing the total cost

Definition at line 74 of file chomp_parameters.h.

◆ max_iterations_

int chomp::ChompParameters::max_iterations_

maximum number of iterations that the planner can take to find a good solution while optimization

Definition at line 68 of file chomp_parameters.h.

◆ max_iterations_after_collision_free_

int chomp::ChompParameters::max_iterations_after_collision_free_

maximum iterations to be performed after a collision free path is found.

Definition at line 69 of file chomp_parameters.h.

◆ max_recovery_attempts_

int chomp::ChompParameters::max_recovery_attempts_

this the maximum recovery attempts to find a collision free path after an initial failure to find a solution

Definition at line 95 of file chomp_parameters.h.

◆ min_clearance_

double chomp::ChompParameters::min_clearance_

the minimum distance that needs to be maintained to avoid obstacles

Definition at line 86 of file chomp_parameters.h.

◆ obstacle_cost_weight_

double chomp::ChompParameters::obstacle_cost_weight_

controls the weight to be given to obstacles towards the final cost CHOMP optimizes over

Definition at line 72 of file chomp_parameters.h.

◆ planning_time_limit_

double chomp::ChompParameters::planning_time_limit_

maximum time the optimizer can take to find a solution before terminating

Definition at line 67 of file chomp_parameters.h.

◆ pseudo_inverse_ridge_factor_

double chomp::ChompParameters::pseudo_inverse_ridge_factor_

set the ridge factor if pseudo inverse is enabled

Definition at line 83 of file chomp_parameters.h.

◆ ridge_factor_

double chomp::ChompParameters::ridge_factor_

the noise added to the diagnal of the total quadratic cost matrix in the objective function

Definition at line 81 of file chomp_parameters.h.

◆ smoothness_cost_acceleration_

double chomp::ChompParameters::smoothness_cost_acceleration_

variables associated with the cost in acceleration

Definition at line 76 of file chomp_parameters.h.

◆ smoothness_cost_jerk_

double chomp::ChompParameters::smoothness_cost_jerk_

variables associated with the cost in jerk

Definition at line 77 of file chomp_parameters.h.

◆ smoothness_cost_velocity_

double chomp::ChompParameters::smoothness_cost_velocity_

variables associated with the cost in velocity

Definition at line 75 of file chomp_parameters.h.

◆ smoothness_cost_weight_

double chomp::ChompParameters::smoothness_cost_weight_

smoothness_cost_weight parameters controls its weight in the final cost that CHOMP is actually optimizing over

Definition at line 70 of file chomp_parameters.h.

◆ trajectory_initialization_method_

std::string chomp::ChompParameters::trajectory_initialization_method_

trajectory initialization method to be specified

Definition at line 91 of file chomp_parameters.h.

◆ use_pseudo_inverse_

bool chomp::ChompParameters::use_pseudo_inverse_

enable pseudo inverse calculations or not.

Definition at line 82 of file chomp_parameters.h.

◆ use_stochastic_descent_

bool chomp::ChompParameters::use_stochastic_descent_

set this to true/false if you want to use stochastic descent while optimizing the cost.

Definition at line 78 of file chomp_parameters.h.

◆ VALID_INITIALIZATION_METHODS

const std::vector< std::string > chomp::ChompParameters::VALID_INITIALIZATION_METHODS
static
Initial value:
{ "quintic-spline", "linear", "cubic",
"fillTrajectory" }

Definition at line 90 of file chomp_parameters.h.


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