moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
38 namespace
39 {
40 const rclcpp::Logger LOGGER = rclcpp::get_logger("hybrid_planning_manager");
41 } // namespace
42 
44 {
45 using namespace std::chrono_literals;
46 
48  : Node("hybrid_planning_manager", options), initialized_(false), stop_hybrid_planning_(false)
49 {
50  // Initialize hybrid planning component after construction
51  // TODO(sjahr) Remove once life cycle component nodes are available
52  timer_ = this->create_wall_timer(1ms, [this]() {
53  if (initialized_)
54  {
55  timer_->cancel();
56  }
57  else
58  {
59  if (!this->initialize())
60  {
61  const std::string error = "Failed to initialize global planner";
62  timer_->cancel();
63  throw std::runtime_error(error);
64  }
65  initialized_ = true;
66  }
67  });
68 }
69 
71 {
72  // Load planning logic plugin
73  try
74  {
75  planner_logic_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<PlannerLogicInterface>>(
76  "moveit_hybrid_planning", "moveit::hybrid_planning::PlannerLogicInterface");
77  }
78  catch (pluginlib::PluginlibException& ex)
79  {
80  RCLCPP_ERROR(LOGGER, "Exception while creating planner logic plugin loader '%s'", ex.what());
81  }
82  // TODO(sjahr) Refactor parameter declaration and use repository wide solution
83  std::string logic_plugin_name = "";
84  if (this->has_parameter("planner_logic_plugin_name"))
85  {
86  this->get_parameter<std::string>("planner_logic_plugin_name", logic_plugin_name);
87  }
88  else
89  {
90  logic_plugin_name = this->declare_parameter<std::string>("planner_logic_plugin_name",
91  "moveit::hybrid_planning/ReplanInvalidatedTrajectory");
92  }
93  try
94  {
95  planner_logic_instance_ = planner_logic_plugin_loader_->createUniqueInstance(logic_plugin_name);
96  if (!planner_logic_instance_->initialize(HybridPlanningManager::shared_from_this()))
97  {
98  throw std::runtime_error("Unable to initialize planner logic plugin");
99  }
100  RCLCPP_INFO(LOGGER, "Using planner logic interface '%s'", logic_plugin_name.c_str());
101  }
102  catch (pluginlib::PluginlibException& ex)
103  {
104  RCLCPP_ERROR(LOGGER, "Exception while loading planner logic '%s': '%s'", logic_plugin_name.c_str(), ex.what());
105  }
106 
107  // Initialize local planning action client
108  std::string local_planning_action_name = this->declare_parameter<std::string>("local_planning_action_name", "");
109  this->get_parameter<std::string>("local_planning_action_name", local_planning_action_name);
110  if (local_planning_action_name.empty())
111  {
112  RCLCPP_ERROR(LOGGER, "local_planning_action_name parameter was not defined");
113  return false;
114  }
115  local_planner_action_client_ =
116  rclcpp_action::create_client<moveit_msgs::action::LocalPlanner>(this, local_planning_action_name);
117  if (!local_planner_action_client_->wait_for_action_server(2s))
118  {
119  RCLCPP_ERROR(LOGGER, "Local planner action server not available after waiting");
120  return false;
121  }
122 
123  // Initialize global planning action client
124  std::string global_planning_action_name = this->declare_parameter<std::string>("global_planning_action_name", "");
125  this->get_parameter<std::string>("global_planning_action_name", global_planning_action_name);
126  if (global_planning_action_name.empty())
127  {
128  RCLCPP_ERROR(LOGGER, "global_planning_action_name parameter was not defined");
129  return false;
130  }
131  global_planner_action_client_ =
132  rclcpp_action::create_client<moveit_msgs::action::GlobalPlanner>(this, global_planning_action_name);
133  if (!global_planner_action_client_->wait_for_action_server(2s))
134  {
135  RCLCPP_ERROR(LOGGER, "Global planner action server not available after waiting");
136  return false;
137  }
138 
139  // Initialize hybrid planning action server
140  std::string hybrid_planning_action_name = this->declare_parameter<std::string>("hybrid_planning_action_name", "");
141  this->get_parameter<std::string>("hybrid_planning_action_name", hybrid_planning_action_name);
142  if (hybrid_planning_action_name.empty())
143  {
144  RCLCPP_ERROR(LOGGER, "hybrid_planning_action_name parameter was not defined");
145  return false;
146  }
147  cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
148  hybrid_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::HybridPlanner>(
149  this->get_node_base_interface(), this->get_node_clock_interface(), this->get_node_logging_interface(),
150  this->get_node_waitables_interface(), hybrid_planning_action_name,
151  // Goal callback
152  [](const rclcpp_action::GoalUUID& /*unused*/,
153  const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Goal>& /*unused*/) {
154  RCLCPP_INFO(LOGGER, "Received goal request");
155  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
156  },
157  // Cancel callback
158  [this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>>& /*unused*/) {
160  RCLCPP_INFO(LOGGER, "Received request to cancel goal");
161  return rclcpp_action::CancelResponse::ACCEPT;
162  },
163  // Execution callback
164  [this](std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>> goal_handle) {
165  // this needs to return quickly to avoid blocking the executor, so spin up a new thread
166  if (long_callback_thread_.joinable())
167  {
169  }
170  long_callback_thread_ = std::thread(&HybridPlanningManager::executeHybridPlannerGoal, this, goal_handle);
171  },
172  rcl_action_server_get_default_options(), cb_group_);
173 
174  // Initialize global solution subscriber
175  global_solution_sub_ = create_subscription<moveit_msgs::msg::MotionPlanResponse>(
176  "global_trajectory", rclcpp::SystemDefaultsQoS(),
177  [this](const moveit_msgs::msg::MotionPlanResponse::ConstSharedPtr& /* unused */) {
178  // react is defined in a hybrid_planning_manager plugin
179  ReactionResult reaction_result = planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_SOLUTION_AVAILABLE);
180  if (reaction_result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
181  {
182  auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
183  result->error_code.val = reaction_result.error_code.val;
184  result->error_message = reaction_result.error_message;
185  hybrid_planning_goal_handle_->abort(result);
186  RCLCPP_ERROR(LOGGER, "Hybrid Planning Manager failed to react to '%s'", reaction_result.event.c_str());
187  }
188  });
189  return true;
190 }
191 
193 {
194  // Prevent any new global or local requests from going out
195  stop_hybrid_planning_ = true;
196  // Cancel local action
197  local_planner_action_client_->async_cancel_all_goals();
198  // Cancel global action
199  global_planner_action_client_->async_cancel_all_goals();
200  if (long_callback_thread_.joinable())
201  {
202  long_callback_thread_.join();
203  }
204 }
205 
207  std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>> goal_handle)
208 {
209  // Reset the "stop" flag if it was set previously
210  stop_hybrid_planning_ = false;
211 
212  // Pass goal handle to class member
213  hybrid_planning_goal_handle_ = std::move(goal_handle);
214 
215  // react is defined in a hybrid_planning_manager plugin
216  ReactionResult reaction_result =
217  planner_logic_instance_->react(HybridPlanningEvent::HYBRID_PLANNING_REQUEST_RECEIVED);
218  if (reaction_result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
219  {
220  auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
221  result->error_code.val = reaction_result.error_code.val;
222  result->error_message = reaction_result.error_message;
223  hybrid_planning_goal_handle_->abort(result);
224  RCLCPP_ERROR_STREAM(LOGGER, "Hybrid Planning Manager failed to react to " << reaction_result.event);
225  }
226 }
227 
229 {
230  auto global_goal_options = rclcpp_action::Client<moveit_msgs::action::GlobalPlanner>::SendGoalOptions();
231 
232  // Add goal response callback
233  global_goal_options.goal_response_callback =
234  [this](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::SharedPtr& goal_handle) {
235  auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
236  auto& feedback = planning_progress->feedback;
237  if (!goal_handle)
238  {
239  feedback = "Global goal was rejected by server";
240  }
241  else
242  {
243  feedback = "Global goal accepted by server";
244  }
245  hybrid_planning_goal_handle_->publish_feedback(planning_progress);
246  };
247  // Add result callback
248  global_goal_options.result_callback =
249  [this](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::WrappedResult& global_result) {
250  // Reaction result from the latest event
251  ReactionResult reaction_result =
252  ReactionResult(HybridPlanningEvent::UNDEFINED, "", moveit_msgs::msg::MoveItErrorCodes::FAILURE);
253  switch (global_result.code)
254  {
255  case rclcpp_action::ResultCode::SUCCEEDED:
256  reaction_result = planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_SUCCESSFUL);
257  break;
258  case rclcpp_action::ResultCode::CANCELED:
259  reaction_result = planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_CANCELED);
260  break;
261  case rclcpp_action::ResultCode::ABORTED:
262  reaction_result = planner_logic_instance_->react(HybridPlanningEvent::GLOBAL_PLANNING_ACTION_ABORTED);
263  break;
264  default:
265  break;
266  }
267  // Abort hybrid planning if reaction fails
268  if (reaction_result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
269  {
270  auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
271  result->error_code.val = reaction_result.error_code.val;
272  result->error_message = reaction_result.error_message;
273 
274  hybrid_planning_goal_handle_->abort(result);
275  RCLCPP_ERROR(LOGGER, "Hybrid Planning Manager failed to react to '%s'", reaction_result.event.c_str());
276  }
277  };
278 
279  // Forward global trajectory goal from hybrid planning request TODO(sjahr) pass goal as function argument
280  auto global_goal_msg = moveit_msgs::action::GlobalPlanner::Goal();
281  global_goal_msg.motion_sequence =
282  (hybrid_planning_goal_handle_->get_goal())->motion_sequence; // latest desired motion sequence;
283  global_goal_msg.planning_group = (hybrid_planning_goal_handle_->get_goal())->planning_group; // planning_group_;
284 
285  if (stop_hybrid_planning_)
286  {
287  return false;
288  }
289 
290  // Send global planning goal and wait until it's accepted
291  auto goal_handle_future = global_planner_action_client_->async_send_goal(global_goal_msg, global_goal_options);
292  return true; // return always success TODO(sjahr) add more error checking
293 };
294 
296 {
297  // Setup empty dummy goal (Global trajectory is subscribed by the local planner) TODO(sjahr) pass goal as function argument
298  auto local_goal_msg = moveit_msgs::action::LocalPlanner::Goal();
299  auto local_goal_options = rclcpp_action::Client<moveit_msgs::action::LocalPlanner>::SendGoalOptions();
300  rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr goal_handle;
301 
302  // Add goal response callback
303  local_goal_options.goal_response_callback =
304  [this](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& goal_handle) {
305  auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
306  auto& feedback = planning_progress->feedback;
307  if (!goal_handle)
308  {
309  feedback = "Local goal was rejected by server";
310  }
311  else
312  {
313  feedback = "Local goal accepted by server";
314  }
315  hybrid_planning_goal_handle_->publish_feedback(planning_progress);
316  };
317 
318  // Add feedback callback
319  local_goal_options.feedback_callback =
320  [this](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& /*unused*/,
321  const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Feedback>& local_planner_feedback) {
322  // react is defined in a hybrid_planning_manager plugin
323  ReactionResult reaction_result = planner_logic_instance_->react(local_planner_feedback->feedback);
324  if (reaction_result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
325  {
326  auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
327  result->error_code.val = reaction_result.error_code.val;
328  result->error_message = reaction_result.error_message;
329  hybrid_planning_goal_handle_->abort(result);
330  RCLCPP_ERROR(LOGGER, "Hybrid Planning Manager failed to react to '%s'", reaction_result.event.c_str());
331  }
332  };
333 
334  // Add result callback to print the result
335  local_goal_options.result_callback =
336  [this](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::WrappedResult& local_result) {
337  // Reaction result from the latest event
338  ReactionResult reaction_result =
339  ReactionResult(HybridPlanningEvent::UNDEFINED, "", moveit_msgs::msg::MoveItErrorCodes::FAILURE);
340  switch (local_result.code)
341  {
342  case rclcpp_action::ResultCode::SUCCEEDED:
343  reaction_result = planner_logic_instance_->react(HybridPlanningEvent::LOCAL_PLANNING_ACTION_SUCCESSFUL);
344  break;
345  case rclcpp_action::ResultCode::CANCELED:
346  reaction_result = planner_logic_instance_->react(HybridPlanningEvent::LOCAL_PLANNING_ACTION_CANCELED);
347  break;
348  case rclcpp_action::ResultCode::ABORTED:
349  reaction_result = planner_logic_instance_->react(HybridPlanningEvent::LOCAL_PLANNING_ACTION_ABORTED);
350  break;
351  default:
352  break;
353  }
354  // Abort hybrid planning if reaction fails
355  if (reaction_result.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
356  {
357  const moveit_msgs::action::HybridPlanner::Result result([reaction_result]() {
358  moveit_msgs::action::HybridPlanner::Result result;
359  result.error_code.val = reaction_result.error_code.val;
360  result.error_message = reaction_result.error_message;
361  return result;
362  }());
363  hybrid_planning_goal_handle_->abort(std::make_shared<moveit_msgs::action::HybridPlanner::Result>(result));
364  RCLCPP_ERROR_STREAM(LOGGER, "Hybrid Planning Manager failed to react to " << reaction_result.event);
365  }
366  };
367 
368  if (stop_hybrid_planning_)
369  {
370  return false;
371  }
372 
373  // Send global planning goal
374  auto goal_handle_future = local_planner_action_client_->async_send_goal(local_goal_msg, local_goal_options);
375  return true; // return always success TODO(sjahr) add more error checking
376 }
377 
379 {
380  // Return hybrid planning action result dependent on the function's argument
381  auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
382  if (success)
383  {
384  result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
385  hybrid_planning_goal_handle_->succeed(result);
386  }
387  else
388  {
389  result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
390  hybrid_planning_goal_handle_->abort(result);
391  }
392 }
393 } // namespace moveit::hybrid_planning
394 
395 // Register the component with class_loader
396 #include <rclcpp_components/register_node_macro.hpp>
397 RCLCPP_COMPONENTS_REGISTER_NODE(moveit::hybrid_planning::HybridPlanningManager)
HybridPlanningManager(const rclcpp::NodeOptions &options)
Constructor.
std::shared_ptr< HybridPlanningManager > shared_from_this()
void executeHybridPlannerGoal(std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::HybridPlanner >> goal_handle)
const rclcpp::Logger LOGGER
Definition: async_test.h:31