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

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>

Inheritance diagram for planning_interface::PlanningResponseAdapter:
Inheritance graph
[legend]

Public Member Functions

virtual void initialize (const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
 Initialize parameters using the passed Node and parameter namespace. More...
 
virtual std::string getDescription () const =0
 Get a description of this adapter. More...
 
virtual void adapt (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const =0
 Adapt the planning response. More...
 

Detailed Description

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.

Member Function Documentation

◆ adapt()

virtual void planning_interface::PlanningResponseAdapter::adapt ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res 
) const
pure virtual

Adapt the planning response.

Parameters
planning_sceneRepresentation of the environment for the planning
reqMotion planning request with a set of constraints
resMotion planning response containing the solution that is adapted.

Implemented in default_planning_response_adapters::ValidateSolution, default_planning_response_adapters::DisplayMotionPath, default_planning_response_adapters::AddTimeOptimalParameterization, default_planning_response_adapters::AddRuckigTrajectorySmoothing, and planning_pipeline_test::AlwaysSuccessResponseAdapter.

◆ getDescription()

virtual std::string planning_interface::PlanningResponseAdapter::getDescription ( ) const
pure virtual

◆ initialize()

virtual void planning_interface::PlanningResponseAdapter::initialize ( const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)
inlinevirtual

Initialize parameters using the passed Node and parameter namespace.

Parameters
nodeNode instance used by the adapter
parameter_namespaceParameter namespace for adapter

The default implementation is empty

Reimplemented in default_planning_response_adapters::ValidateSolution, default_planning_response_adapters::DisplayMotionPath, and default_planning_response_adapters::AddTimeOptimalParameterization.

Definition at line 59 of file planning_response_adapter.h.


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