moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | List of all members
default_planning_response_adapters::DisplayMotionPath Class Reference

Adapter to publish the EE path as marker array via ROS topic if a path exist. Otherwise, a warning is printed but this adapter cannot fail. More...

Inheritance diagram for default_planning_response_adapters::DisplayMotionPath:
Inheritance graph
[legend]
Collaboration diagram for default_planning_response_adapters::DisplayMotionPath:
Collaboration graph
[legend]

Public Member Functions

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

Detailed Description

Adapter to publish the EE path as marker array via ROS topic if a path exist. Otherwise, a warning is printed but this adapter cannot fail.

Definition at line 54 of file display_motion_path.cpp.

Constructor & Destructor Documentation

◆ DisplayMotionPath()

default_planning_response_adapters::DisplayMotionPath::DisplayMotionPath ( )
inline

Definition at line 57 of file display_motion_path.cpp.

Member Function Documentation

◆ adapt()

void default_planning_response_adapters::DisplayMotionPath::adapt ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res 
) const
inlineoverridevirtual

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.

Implements planning_interface::PlanningResponseAdapter.

Definition at line 76 of file display_motion_path.cpp.

Here is the call graph for this function:

◆ getDescription()

std::string default_planning_response_adapters::DisplayMotionPath::getDescription ( ) const
inlineoverridevirtual

Get a description of this adapter.

Returns
Returns a short string that identifies the planning response adapter

Implements planning_interface::PlanningResponseAdapter.

Definition at line 71 of file display_motion_path.cpp.

Here is the caller graph for this function:

◆ initialize()

void default_planning_response_adapters::DisplayMotionPath::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

The default implementation is empty

Reimplemented from planning_interface::PlanningResponseAdapter.

Definition at line 61 of file display_motion_path.cpp.


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