moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Adapter to check the request path validity (collision avoidance, feasibility and constraint satisfaction) More...
Public Member Functions | |
ValidateSolution () | |
void | initialize (const rclcpp::Node::SharedPtr &node, const std::string ¶meter_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 &req, planning_interface::MotionPlanResponse &res) const override |
Adapt the planning response. | |
Adapter to check the request path validity (collision avoidance, feasibility and constraint satisfaction)
Definition at line 52 of file validate_path.cpp.
|
inline |
Definition at line 55 of file validate_path.cpp.
|
inlineoverridevirtual |
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. |
Implements planning_interface::PlanningResponseAdapter.
Definition at line 78 of file validate_path.cpp.
|
inlineoverridevirtual |
Get a description of this adapter.
Implements planning_interface::PlanningResponseAdapter.
Definition at line 73 of file validate_path.cpp.
|
inlineoverridevirtual |
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 from planning_interface::PlanningResponseAdapter.
Definition at line 59 of file validate_path.cpp.