Planner parameters provided with the MotionPlanRequest. More...
#include <planning_component.h>
Public Member Functions | |
| void | load (const ros::NodeHandle &nh, const std::string ¶m_namespace="") | 
Public Attributes | |
| double | max_acceleration_scaling_factor | 
| double | max_velocity_scaling_factor | 
| std::string | planner_id | 
| int | planning_attempts | 
| std::string | planning_pipeline | 
| double | planning_time | 
Planner parameters provided with the MotionPlanRequest.
Definition at line 123 of file planning_component.h.
      
  | 
  inline | 
Definition at line 132 of file planning_component.h.
| double moveit_cpp::PlanningComponent::PlanRequestParameters::max_acceleration_scaling_factor | 
Definition at line 130 of file planning_component.h.
| double moveit_cpp::PlanningComponent::PlanRequestParameters::max_velocity_scaling_factor | 
Definition at line 129 of file planning_component.h.
| std::string moveit_cpp::PlanningComponent::PlanRequestParameters::planner_id | 
Definition at line 125 of file planning_component.h.
| int moveit_cpp::PlanningComponent::PlanRequestParameters::planning_attempts | 
Definition at line 127 of file planning_component.h.
| std::string moveit_cpp::PlanningComponent::PlanRequestParameters::planning_pipeline | 
Definition at line 126 of file planning_component.h.
| double moveit_cpp::PlanningComponent::PlanRequestParameters::planning_time | 
Definition at line 128 of file planning_component.h.