moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | List of all members
moveit_cpp::PlanningComponent::PlanRequestParameters Struct Reference

Planner parameters provided with the MotionPlanRequest. More...

#include <planning_component.h>

Public Member Functions

template<typename T >
void declareOrGetParam (const rclcpp::Node::SharedPtr &node, const std::string &param_name, T &output_value, T default_value)
 
void load (const rclcpp::Node::SharedPtr &node, const std::string &param_namespace="")
 

Public Attributes

std::string planner_id
 
std::string planning_pipeline
 
int planning_attempts
 
double planning_time
 
double max_velocity_scaling_factor
 
double max_acceleration_scaling_factor
 

Detailed Description

Planner parameters provided with the MotionPlanRequest.

Definition at line 59 of file planning_component.h.

Member Function Documentation

◆ declareOrGetParam()

template<typename T >
void moveit_cpp::PlanningComponent::PlanRequestParameters::declareOrGetParam ( const rclcpp::Node::SharedPtr &  node,
const std::string &  param_name,
T &  output_value,
default_value 
)
inline

Definition at line 69 of file planning_component.h.

◆ load()

void moveit_cpp::PlanningComponent::PlanRequestParameters::load ( const rclcpp::Node::SharedPtr &  node,
const std::string &  param_namespace = "" 
)
inline

Definition at line 82 of file planning_component.h.

Here is the caller graph for this function:

Member Data Documentation

◆ max_acceleration_scaling_factor

double moveit_cpp::PlanningComponent::PlanRequestParameters::max_acceleration_scaling_factor

Definition at line 66 of file planning_component.h.

◆ max_velocity_scaling_factor

double moveit_cpp::PlanningComponent::PlanRequestParameters::max_velocity_scaling_factor

Definition at line 65 of file planning_component.h.

◆ planner_id

std::string moveit_cpp::PlanningComponent::PlanRequestParameters::planner_id

Definition at line 61 of file planning_component.h.

◆ planning_attempts

int moveit_cpp::PlanningComponent::PlanRequestParameters::planning_attempts

Definition at line 63 of file planning_component.h.

◆ planning_pipeline

std::string moveit_cpp::PlanningComponent::PlanRequestParameters::planning_pipeline

Definition at line 62 of file planning_component.h.

◆ planning_time

double moveit_cpp::PlanningComponent::PlanRequestParameters::planning_time

Definition at line 64 of file planning_component.h.


The documentation for this struct was generated from the following file: