moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
hybrid_planning_manager.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2020, 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
37#include <hp_manager_parameters.hpp>
39
41{
42using namespace std::chrono_literals;
43
44namespace
45{
46rclcpp::Logger getLogger()
47{
48 return moveit::getLogger("moveit.hybrid_planning.manager");
49}
50} // namespace
51
52HybridPlanningManager::HybridPlanningManager(const rclcpp::NodeOptions& options)
53 : node_{ std::make_shared<rclcpp::Node>("hybrid_planning_manager", options) }, stop_hybrid_planning_(false)
54{
55 // Load planning logic plugin
56 try
57 {
58 planner_logic_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<PlannerLogicInterface>>(
59 "moveit_hybrid_planning", "moveit::hybrid_planning::PlannerLogicInterface");
60 }
61 catch (pluginlib::PluginlibException& ex)
62 {
63 RCLCPP_ERROR(getLogger(), "Exception while creating planner logic plugin loader '%s'", ex.what());
64 }
65
66 auto param_listener = hp_manager_parameters::ParamListener(node_, "");
67 const auto params = param_listener.get_params();
68 try
69 {
70 planner_logic_instance_ = planner_logic_plugin_loader_->createUniqueInstance(params.planner_logic_plugin_name);
71 if (!planner_logic_instance_->initialize())
72 {
73 throw std::runtime_error("Unable to initialize planner logic plugin");
74 }
75 RCLCPP_INFO(getLogger(), "Using planner logic interface '%s'", params.planner_logic_plugin_name.c_str());
76 }
77 catch (pluginlib::PluginlibException& ex)
78 {
79 RCLCPP_ERROR(getLogger(), "Exception while loading planner logic '%s': '%s'",
80 params.planner_logic_plugin_name.c_str(), ex.what());
81 return;
82 }
83
84 // Initialize local planning action client
85 local_planner_action_client_ =
86 rclcpp_action::create_client<moveit_msgs::action::LocalPlanner>(node_, "local_planning_action");
87 if (!local_planner_action_client_->wait_for_action_server(2s))
88 {
89 RCLCPP_ERROR(getLogger(), "Local planner action server not available after waiting");
90 return;
91 }
92
93 // Initialize global planning action client
94 global_planner_action_client_ =
95 rclcpp_action::create_client<moveit_msgs::action::GlobalPlanner>(node_, "global_planning_action");
96 if (!global_planner_action_client_->wait_for_action_server(2s))
97 {
98 RCLCPP_ERROR(getLogger(), "Global planner action server not available after waiting");
99 return;
100 }
101
102 // Initialize hybrid planning action server
103 cb_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
104 hybrid_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::HybridPlanner>(
105 node_, "run_hybrid_planning",
106 // Goal callback
107 [](const rclcpp_action::GoalUUID& /*unused*/,
108 const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Goal>& /*unused*/) {
109 RCLCPP_INFO(getLogger(), "Received goal request");
110 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
111 },
112 // Cancel callback
113 [&](const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>>& /*unused*/) {
115 RCLCPP_INFO(getLogger(), "Received request to cancel goal");
116 return rclcpp_action::CancelResponse::ACCEPT;
117 },
118 // Execution callback
119 [&](const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>>& goal_handle) {
120 // this needs to return quickly to avoid blocking the executor, so spin up a new thread
121 if (long_callback_thread_.joinable())
122 {
124 }
125 long_callback_thread_ = std::thread(&HybridPlanningManager::executeHybridPlannerGoal, this, goal_handle);
126 },
127 rcl_action_server_get_default_options(), cb_group_);
128
129 // Initialize global solution subscriber
130 global_solution_sub_ = node_->create_subscription<moveit_msgs::msg::MotionPlanResponse>(
131 "global_trajectory", rclcpp::SystemDefaultsQoS(),
132 [&](const moveit_msgs::msg::MotionPlanResponse::ConstSharedPtr& /* unused */) {
133 // react is defined in a hybrid_planning_manager plugin
135 });
136}
137
139{
140 // Prevent any new global or local requests from going out
141 stop_hybrid_planning_ = true;
142 // Cancel local action
143 local_planner_action_client_->async_cancel_all_goals();
144 // Cancel global action
145 global_planner_action_client_->async_cancel_all_goals();
146 if (long_callback_thread_.joinable())
147 {
148 long_callback_thread_.join();
149 }
150}
151
153 std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>> goal_handle)
154{
155 // Reset the "stop" flag if it was set previously
156 stop_hybrid_planning_ = false;
157
158 // Pass goal handle to class member
159 hybrid_planning_goal_handle_ = std::move(goal_handle);
160
161 // react is defined in a hybrid_planning_manager plugin
163}
164
166{
167 auto global_goal_options = rclcpp_action::Client<moveit_msgs::action::GlobalPlanner>::SendGoalOptions();
168
169 // Add goal response callback
170 global_goal_options.goal_response_callback =
171 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::SharedPtr& goal_handle) {
172 auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
173 auto& feedback = planning_progress->feedback;
174 if (!goal_handle)
175 {
176 feedback = "Global goal was rejected by server";
177 }
178 else
179 {
180 feedback = "Global goal accepted by server";
181 }
182 hybrid_planning_goal_handle_->publish_feedback(planning_progress);
183 };
184 // Add result callback
185 global_goal_options.result_callback =
186 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::WrappedResult& global_result) {
187 // Reaction result from the latest event
188 ReactionResult reaction_result =
189 ReactionResult(HybridPlanningEvent::UNDEFINED, "", moveit_msgs::msg::MoveItErrorCodes::FAILURE);
190 switch (global_result.code)
191 {
192 case rclcpp_action::ResultCode::SUCCEEDED:
193 reaction_result = planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_SUCCESSFUL);
194 break;
195 case rclcpp_action::ResultCode::CANCELED:
196 reaction_result = planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_CANCELED);
197 break;
198 case rclcpp_action::ResultCode::ABORTED:
199 reaction_result = planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_ABORTED);
200 break;
201 default:
202 break;
203 }
204 // Abort hybrid planning if reaction fails
205 processReactionResult(reaction_result);
206 };
207
208 // Forward global trajectory goal from hybrid planning request TODO(sjahr) pass goal as function argument
209 auto global_goal_msg = moveit_msgs::action::GlobalPlanner::Goal();
210 global_goal_msg.motion_sequence =
211 (hybrid_planning_goal_handle_->get_goal())->motion_sequence; // latest desired motion sequence;
212 global_goal_msg.planning_group = (hybrid_planning_goal_handle_->get_goal())->planning_group; // planning_group_;
213
214 if (stop_hybrid_planning_)
215 {
216 return false;
217 }
218
219 // Send global planning goal and wait until it's accepted
220 auto goal_handle_future = global_planner_action_client_->async_send_goal(global_goal_msg, global_goal_options);
221 return true; // return always success TODO(sjahr) add more error checking
222};
223
225{
226 // Setup empty dummy goal (Global trajectory is subscribed by the local planner) TODO(sjahr) pass goal as function argument
227 auto local_goal_msg = moveit_msgs::action::LocalPlanner::Goal();
228 auto local_goal_options = rclcpp_action::Client<moveit_msgs::action::LocalPlanner>::SendGoalOptions();
229 rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr goal_handle;
230
231 // Add goal response callback
232 local_goal_options.goal_response_callback =
233 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& goal_handle) {
234 auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
235 auto& feedback = planning_progress->feedback;
236 if (!goal_handle)
237 {
238 feedback = "Local goal was rejected by server";
239 }
240 else
241 {
242 feedback = "Local goal accepted by server";
243 }
244 hybrid_planning_goal_handle_->publish_feedback(planning_progress);
245 };
246
247 // Add feedback callback
248 local_goal_options.feedback_callback =
249 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& /*unused*/,
250 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Feedback>& local_planner_feedback) {
251 processReactionResult(planner_logic_instance_->react(local_planner_feedback->feedback));
252 };
253
254 // Add result callback to print the result
255 local_goal_options.result_callback =
256 [&](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::WrappedResult& local_result) {
257 // Reaction result from the latest event
258 ReactionResult reaction_result =
259 ReactionResult(HybridPlanningEvent::UNDEFINED, "", moveit_msgs::msg::MoveItErrorCodes::FAILURE);
260 switch (local_result.code)
261 {
262 case rclcpp_action::ResultCode::SUCCEEDED:
263 reaction_result = planner_logic_instance_->react(HybridPlanningEvent::LOCAL_PLANNING_ACTION_SUCCESSFUL);
264 break;
265 case rclcpp_action::ResultCode::CANCELED:
266 reaction_result = planner_logic_instance_->react(HybridPlanningEvent::LOCAL_PLANNING_ACTION_CANCELED);
267 break;
268 case rclcpp_action::ResultCode::ABORTED:
269 reaction_result = planner_logic_instance_->react(HybridPlanningEvent::LOCAL_PLANNING_ACTION_ABORTED);
270 break;
271 default:
272 break;
273 }
274 processReactionResult(reaction_result);
275 };
276
277 if (stop_hybrid_planning_)
278 {
279 return false;
280 }
281
282 // Send global planning goal
283 auto goal_handle_future = local_planner_action_client_->async_send_goal(local_goal_msg, local_goal_options);
284 return true; // return always success TODO(sjahr) add more error checking
285}
286
288{
289 // Return hybrid planning action result dependent on the function's argument
290 auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
291 if (success)
292 {
293 result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
294 hybrid_planning_goal_handle_->succeed(result);
295 }
296 else
297 {
298 result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
299 hybrid_planning_goal_handle_->abort(result);
300 }
301}
302
304{
305 if (result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
306 {
307 auto hp_result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
308 hp_result->error_code.val = result.error_code.val;
309 hp_result->error_message = result.error_message;
310 hybrid_planning_goal_handle_->abort(hp_result);
311 RCLCPP_ERROR(getLogger(), "Hybrid Planning Manager failed to react to '%s'", result.event.c_str());
312 return;
313 }
314
315 switch (result.action)
316 {
318 // Do nothing
319 break;
322 break;
325 break;
328 break;
331 break;
332 default:
333 RCLCPP_ERROR(getLogger(), "Unknown reaction result code. No actions taken by the hybrid planning manager.");
334 }
335}
336} // namespace moveit::hybrid_planning
337
338// Register the component with class_loader
339#include <rclcpp_components/register_node_macro.hpp>
340RCLCPP_COMPONENTS_REGISTER_NODE(moveit::hybrid_planning::HybridPlanningManager)
void executeHybridPlannerGoal(std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::HybridPlanner > > goal_handle)
HybridPlanningManager(const rclcpp::NodeOptions &options)
Constructor.
void processReactionResult(const ReactionResult &result)
Process the action result and do an action call if necessary.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79