40#include <class_loader/class_loader.hpp>
44#include <rclcpp/node.hpp>
45#include <rclcpp/logging.hpp>
46#include <visualization_msgs/msg/marker_array.hpp>
66 bool initialize(
const moveit::core::RobotModelConstPtr& model,
const rclcpp::Node::SharedPtr& node,
67 const std::string& parameter_namespace)
override
71 parameter_namespace_ = parameter_namespace;
72 param_listener_ = std::make_shared<stomp_moveit::ParamListener>(node, parameter_namespace);
89 moveit_msgs::msg::MoveItErrorCodes& error_code)
const override
93 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
97 const auto params = param_listener_->get_params();
99 std::shared_ptr<StompPlanningContext> planning_context =
100 std::make_shared<StompPlanningContext>(
"STOMP", req.group_name, params);
102 planning_context->setMotionPlanRequest(req);
105 if (!params.path_marker_topic.empty())
107 auto path_publisher = node_->create_publisher<visualization_msgs::msg::MarkerArray>(params.path_marker_topic,
108 rclcpp::SystemDefaultsQoS());
109 planning_context->setPathPublisher(path_publisher);
112 return planning_context;
117 if (req.goal_constraints.empty())
119 RCLCPP_ERROR(getLogger(),
"Invalid goal constraints");
123 if (req.group_name.empty() || !robot_model_->hasJointModelGroup(req.group_name))
125 RCLCPP_ERROR(getLogger(),
"Invalid joint group '%s'", req.group_name.c_str());
136 moveit::core::RobotModelConstPtr robot_model_;
137 rclcpp::Node::SharedPtr node_;
138 std::string parameter_namespace_;
139 std::shared_ptr<stomp_moveit::ParamListener> param_listener_;
Base class for a MoveIt planner.
StompPlannerManager()=default
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
void setPlannerConfigurations(const PlannerConfigurationMap &) override
Specify the settings to be used for specific algorithms.
PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
Construct a planning context given the current scene and a planning request. If a problem is encounte...
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
std::string getDescription() const override
Get a short string that identifies the planning interface.
~StompPlannerManager() override=default
bool canServiceRequest(const MotionPlanRequest &req) const override
Determine whether this plugin instance is able to represent this planning request.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
This namespace includes the base class for MoveIt planners.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
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)
Planning Context implementation for STOMP.