moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Concept in MoveIt which can be used to modify the planning solution (post-processing) in a planning pipeline. PlanningResponseAdapters enable using for example smoothing and trajectory generation algorithms in sequence to produce a trajectory. More...
#include <planning_response_adapter.h>
Public Member Functions | |
virtual void | initialize (const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) |
Initialize parameters using the passed Node and parameter namespace. | |
virtual std::string | getDescription () const =0 |
Get a description of this adapter. | |
virtual void | adapt (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const =0 |
Adapt the planning response. | |
Concept in MoveIt which can be used to modify the planning solution (post-processing) in a planning pipeline. PlanningResponseAdapters enable using for example smoothing and trajectory generation algorithms in sequence to produce a trajectory.
Definition at line 52 of file planning_response_adapter.h.
|
pure virtual |
Adapt the planning response.
planning_scene | Representation of the environment for the planning |
req | Motion planning request with a set of constraints |
res | Motion planning response containing the solution that is adapted. |
Implemented in planning_pipeline_test::AlwaysSuccessResponseAdapter, default_planning_response_adapters::AddRuckigTrajectorySmoothing, default_planning_response_adapters::AddTimeOptimalParameterization, default_planning_response_adapters::DisplayMotionPath, and default_planning_response_adapters::ValidateSolution.
|
pure virtual |
Get a description of this adapter.
Implemented in planning_pipeline_test::AlwaysSuccessResponseAdapter, default_planning_response_adapters::AddRuckigTrajectorySmoothing, default_planning_response_adapters::AddTimeOptimalParameterization, default_planning_response_adapters::DisplayMotionPath, and default_planning_response_adapters::ValidateSolution.
|
inlinevirtual |
Initialize parameters using the passed Node and parameter namespace.
node | Node instance used by the adapter |
parameter_namespace | Parameter namespace for adapter |
The default implementation is empty
Reimplemented in default_planning_response_adapters::AddTimeOptimalParameterization, default_planning_response_adapters::DisplayMotionPath, and default_planning_response_adapters::ValidateSolution.
Definition at line 59 of file planning_response_adapter.h.