moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
default_planner_request_adapters::FixStartStateBounds Class Reference

Fix start state bounds adapter fixes the start state to be within the joint limits specified in the URDF. More...

Inheritance diagram for default_planner_request_adapters::FixStartStateBounds:
Inheritance graph
[legend]
Collaboration diagram for default_planner_request_adapters::FixStartStateBounds:
Collaboration graph
[legend]

Public Member Functions

void initialize (const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
 Initialize parameters using the passed Node and parameter namespace. More...
 
std::string getDescription () const override
 Get a description of this adapter. More...
 
bool adaptAndPlan (const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
 Adapt the planning request if needed, call the planner function planner and update the planning response if needed. If the response is changed, the index values of the states added without planning are added to added_path_index. More...
 
- Public Member Functions inherited from planning_request_adapter::PlanningRequestAdapter
bool adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
 Adapt the planning request if needed, call the planner function planner and update the planning response if needed. If the response is changed, the index values of the states added without planning are added to added_path_index. More...
 

Additional Inherited Members

- Public Types inherited from planning_request_adapter::PlanningRequestAdapter
using PlannerFn = std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)>
 Functional interface to call a planning function. More...
 

Detailed Description

Fix start state bounds adapter fixes the start state to be within the joint limits specified in the URDF.

Definition at line 63 of file fix_start_state_bounds.cpp.

Member Function Documentation

◆ adaptAndPlan()

bool default_planner_request_adapters::FixStartStateBounds::adaptAndPlan ( const PlannerFn planner,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res 
) const
inlineoverridevirtual

Adapt the planning request if needed, call the planner function planner and update the planning response if needed. If the response is changed, the index values of the states added without planning are added to added_path_index.

Parameters
plannerPointer to the planner used to solve the passed problem
planning_sceneRepresentation of the environment for the planning
reqMotion planning request with a set of constraints
resReference to which the generated motion plan response is written to
Returns
True if response got generated correctly

Implements planning_request_adapter::PlanningRequestAdapter.

Definition at line 77 of file fix_start_state_bounds.cpp.

Here is the call graph for this function:

◆ getDescription()

std::string default_planner_request_adapters::FixStartStateBounds::getDescription ( ) const
inlineoverridevirtual

Get a description of this adapter.

Returns
Returns a short string that identifies the planning request adapter

Implements planning_request_adapter::PlanningRequestAdapter.

Definition at line 72 of file fix_start_state_bounds.cpp.

Here is the caller graph for this function:

◆ initialize()

void default_planner_request_adapters::FixStartStateBounds::initialize ( const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)
inlineoverridevirtual

Initialize parameters using the passed Node and parameter namespace.

Parameters
nodeNode instance used by the adapter
parameter_namespaceParameter namespace for adapter If no initialization is needed, simply implement as empty

Implements planning_request_adapter::PlanningRequestAdapter.

Definition at line 66 of file fix_start_state_bounds.cpp.


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