41#include <rclcpp/logging.hpp>
42#include <rclcpp/node.hpp>
59 virtual void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace){};
#define MOVEIT_CLASS_FORWARD(C)
Concept in MoveIt which can be used to modify the planning solution (post-processing) in a planning p...
virtual void adapt(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const =0
Adapt the planning response.
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.
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
Response to a planning query.