moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
stomp_moveit_planner_plugin.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, PickNik Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of PickNik Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
40#include <class_loader/class_loader.hpp>
43
44#include <rclcpp/node.hpp>
45#include <rclcpp/logging.hpp>
46#include <visualization_msgs/msg/marker_array.hpp>
47
48namespace stomp_moveit
49{
50namespace
51{
52rclcpp::Logger getLogger()
53{
54 return moveit::getLogger("moveit.planners.stomp.planner_manager");
55}
56} // namespace
57
58using namespace planning_interface;
59
61{
62public:
64 ~StompPlannerManager() override = default;
65
66 bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
67 const std::string& parameter_namespace) override
68 {
69 robot_model_ = model;
70 node_ = node;
71 parameter_namespace_ = parameter_namespace;
72 param_listener_ = std::make_shared<stomp_moveit::ParamListener>(node, parameter_namespace);
73
74 return true;
75 }
76
77 std::string getDescription() const override
78 {
79 return "STOMP";
80 }
81
82 void getPlanningAlgorithms(std::vector<std::string>& algs) const override
83 {
84 algs = { "STOMP" };
85 }
86
87 PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
88 const MotionPlanRequest& req,
89 moveit_msgs::msg::MoveItErrorCodes& error_code) const override
90 {
91 if (!canServiceRequest(req))
92 {
93 error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
94 return nullptr;
95 }
96
97 const auto params = param_listener_->get_params();
98
99 std::shared_ptr<StompPlanningContext> planning_context =
100 std::make_shared<StompPlanningContext>("STOMP", req.group_name, params);
101 planning_context->setPlanningScene(planning_scene);
102 planning_context->setMotionPlanRequest(req);
103
104 // Only create path publisher if topic parameter has been set
105 if (!params.path_marker_topic.empty())
106 {
107 auto path_publisher = node_->create_publisher<visualization_msgs::msg::MarkerArray>(params.path_marker_topic,
108 rclcpp::SystemDefaultsQoS());
109 planning_context->setPathPublisher(path_publisher);
110 }
111
112 return planning_context;
113 }
114
115 bool canServiceRequest(const MotionPlanRequest& req) const override
116 {
117 if (req.goal_constraints.empty())
118 {
119 RCLCPP_ERROR(getLogger(), "Invalid goal constraints");
120 return false;
121 }
122
123 if (req.group_name.empty() || !robot_model_->hasJointModelGroup(req.group_name))
124 {
125 RCLCPP_ERROR(getLogger(), "Invalid joint group '%s'", req.group_name.c_str());
126 return false;
127 }
128 return true;
129 }
130
132 {
133 }
134
135private:
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_;
140};
141
142} // namespace stomp_moveit
143
Base class for a MoveIt planner.
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 &parameter_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(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
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.