moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Types | Public Member Functions | List of all members
planning_request_adapter::PlanningRequestAdapter Class Referenceabstract

Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-processing and/or post-processing) for a motion planner. PlanningRequestAdapter enable using multiple motion planning and trajectory generation algorithms in sequence to produce robust motion plans. More...

#include <planning_request_adapter.h>

Inheritance diagram for planning_request_adapter::PlanningRequestAdapter:
Inheritance graph
[legend]

Public Types

using PlannerFn = std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)>
 Functional interface to call a planning function. More...
 

Public Member Functions

virtual void initialize (const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)=0
 Initialize parameters using the passed Node and parameter namespace. More...
 
virtual std::string getDescription () const =0
 Get a description of this adapter. More...
 
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...
 
virtual bool adaptAndPlan (const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const =0
 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...
 

Detailed Description

Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-processing and/or post-processing) for a motion planner. PlanningRequestAdapter enable using multiple motion planning and trajectory generation algorithms in sequence to produce robust motion plans.

Definition at line 55 of file planning_request_adapter.h.

Member Typedef Documentation

◆ PlannerFn

Functional interface to call a planning function.

Definition at line 59 of file planning_request_adapter.h.

Member Function Documentation

◆ adaptAndPlan() [1/2]

virtual bool planning_request_adapter::PlanningRequestAdapter::adaptAndPlan ( const PlannerFn planner,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res 
) const
pure virtual

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

Implemented in stomp_moveit::StompSmoothingAdapter, chomp::OptimizerAdapter, default_planner_request_adapters::ResolveConstraintFrames, default_planner_request_adapters::FixWorkspaceBounds, default_planner_request_adapters::FixStartStatePathConstraints, default_planner_request_adapters::FixStartStateCollision, default_planner_request_adapters::FixStartStateBounds, default_planner_request_adapters::Empty, default_planner_request_adapters::AddTimeOptimalParameterization, default_planner_request_adapters::AddRuckigTrajectorySmoothing, PrependingPlanningRequestAdapter, and AppendingPlanningRequestAdapter.

◆ adaptAndPlan() [2/2]

bool planning_request_adapter::PlanningRequestAdapter::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.

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

Definition at line 88 of file planning_request_adapter.cpp.

◆ getDescription()

virtual std::string planning_request_adapter::PlanningRequestAdapter::getDescription ( ) const
pure virtual

◆ initialize()

virtual void planning_request_adapter::PlanningRequestAdapter::initialize ( const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)
pure virtual

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