moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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>
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 ¶meter_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... | |
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.
using planning_request_adapter::PlanningRequestAdapter::PlannerFn = std::function<bool(const planning_scene::PlanningSceneConstPtr&, const planning_interface::MotionPlanRequest&, planning_interface::MotionPlanResponse&)> |
Functional interface to call a planning function.
Definition at line 59 of file planning_request_adapter.h.
|
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.
planner | Pointer to the planner used to solve the passed problem |
planning_scene | Representation of the environment for the planning |
req | Motion planning request with a set of constraints |
res | Reference to which the generated motion plan response is written to |
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.
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.
planner | Pointer to the planner used to solve the passed problem |
planning_scene | Representation of the environment for the planning |
req | Motion planning request with a set of constraints |
res | Reference to which the generated motion plan response is written to |
Definition at line 88 of file planning_request_adapter.cpp.
|
pure virtual |
Get a description of this adapter.
Implemented in 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, stomp_moveit::StompSmoothingAdapter, chomp::OptimizerAdapter, PrependingPlanningRequestAdapter, and AppendingPlanningRequestAdapter.
|
pure virtual |
Initialize parameters using the passed Node and parameter namespace.
node | Node instance used by the adapter |
parameter_namespace | Parameter namespace for adapter If no initialization is needed, simply implement as empty |
Implemented in default_planner_request_adapters::FixWorkspaceBounds, default_planner_request_adapters::FixStartStateCollision, default_planner_request_adapters::FixStartStateBounds, default_planner_request_adapters::AddTimeOptimalParameterization, stomp_moveit::StompSmoothingAdapter, chomp::OptimizerAdapter, default_planner_request_adapters::ResolveConstraintFrames, default_planner_request_adapters::FixStartStatePathConstraints, default_planner_request_adapters::Empty, default_planner_request_adapters::AddRuckigTrajectorySmoothing, PrependingPlanningRequestAdapter, and AppendingPlanningRequestAdapter.