41#include <class_loader/class_loader.hpp>
43#include <moveit_msgs/msg/display_trajectory.hpp>
45#include <default_response_adapter_parameters.hpp>
61 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
64 std::make_unique<default_response_adapter_parameters::ParamListener>(node, parameter_namespace);
66 const auto params = param_listener->get_params();
67 display_path_publisher_ = node->create_publisher<moveit_msgs::msg::DisplayTrajectory>(params.display_path_topic,
68 rclcpp::SystemDefaultsQoS());
73 return std::string(
"DisplayMotionPath");
83 moveit_msgs::msg::DisplayTrajectory disp;
85 disp.trajectory.resize(1);
86 res.
trajectory->getRobotTrajectoryMsg(disp.trajectory.at(0));
88 display_path_publisher_->publish(disp);
92 RCLCPP_WARN(logger_,
"No motion path to display in MotionPlanResponse.");
97 rclcpp::Logger logger_;
98 rclcpp::Publisher<moveit_msgs::msg::DisplayTrajectory>::SharedPtr display_path_publisher_;
Adapter to publish the EE path as marker array via ROS topic if a path exist. Otherwise,...
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
void adapt(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &res) const override
Adapt the planning response.
std::string getDescription() const override
Get a description of this adapter.
Concept in MoveIt which can be used to modify the planning solution (post-processing) in a planning p...
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
Main namespace for MoveIt.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)
Response to a planning query.
robot_trajectory::RobotTrajectoryPtr trajectory