moveit2
The MoveIt Motion Planning Framework for ROS 2.
local_planner_component.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 
36 
39 
41 
42 #include <moveit_msgs/msg/constraints.hpp>
43 
45 {
46 using namespace std::chrono_literals;
47 
48 namespace
49 {
50 const rclcpp::Logger LOGGER = rclcpp::get_logger("local_planner_component");
51 const auto JOIN_THREAD_TIMEOUT = std::chrono::seconds(1);
52 
53 // If the trajectory progress reaches more than 0.X the global goal state is considered as reached
54 constexpr float PROGRESS_THRESHOLD = 0.995;
55 } // namespace
56 
58  : node_{ std::make_shared<rclcpp::Node>("local_planner_component", options) }
59 {
61  local_planner_feedback_ = std::make_shared<moveit_msgs::action::LocalPlanner::Feedback>();
62 
63  if (!this->initialize())
64  {
65  throw std::runtime_error("Failed to initialize local planner component");
66  }
67 }
68 
70 {
71  // Load planner parameter
72  config_.load(node_);
73 
74  // Validate config
75  if (config_.local_solution_topic_type == "std_msgs/Float64MultiArray")
76  {
77  if ((config_.publish_joint_positions && config_.publish_joint_velocities) ||
79  {
80  RCLCPP_ERROR(LOGGER, "When publishing a std_msgs/Float64MultiArray, you must select positions OR velocities. "
81  "Enabling both or none is not possible!");
82  return false;
83  }
84  }
85 
86  // Configure planning scene monitor
87  planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
88  node_, "robot_description", tf_buffer_, "local_planner/planning_scene_monitor");
89  if (!planning_scene_monitor_->getPlanningScene())
90  {
91  RCLCPP_ERROR(LOGGER, "Unable to configure planning scene monitor");
92  return false;
93  }
94 
95  // Start state and scene monitors
96  planning_scene_monitor_->startSceneMonitor(config_.monitored_planning_scene_topic);
97  planning_scene_monitor_->startWorldGeometryMonitor(config_.collision_object_topic);
98  planning_scene_monitor_->startStateMonitor(config_.joint_states_topic);
99 
100  // Load trajectory operator plugin
101  try
102  {
103  trajectory_operator_loader_ = std::make_unique<pluginlib::ClassLoader<TrajectoryOperatorInterface>>(
104  "moveit_hybrid_planning", "moveit::hybrid_planning::TrajectoryOperatorInterface");
105  }
106  catch (pluginlib::PluginlibException& ex)
107  {
108  RCLCPP_ERROR(LOGGER, "Exception while creating trajectory operator plugin loader: '%s'", ex.what());
109  return false;
110  }
111  try
112  {
113  trajectory_operator_instance_ =
114  trajectory_operator_loader_->createUniqueInstance(config_.trajectory_operator_plugin_name);
115  if (!trajectory_operator_instance_->initialize(node_, planning_scene_monitor_->getRobotModel(),
116  config_.group_name)) // TODO(sjahr) add default group param
117  throw std::runtime_error("Unable to initialize trajectory operator plugin");
118  RCLCPP_INFO(LOGGER, "Using trajectory operator interface '%s'", config_.trajectory_operator_plugin_name.c_str());
119  }
120  catch (pluginlib::PluginlibException& ex)
121  {
122  RCLCPP_ERROR(LOGGER, "Exception while loading trajectory operator '%s': '%s'",
123  config_.trajectory_operator_plugin_name.c_str(), ex.what());
124  return false;
125  }
126 
127  // Load local constraint solver
128  try
129  {
130  local_constraint_solver_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<LocalConstraintSolverInterface>>(
131  "moveit_hybrid_planning", "moveit::hybrid_planning::LocalConstraintSolverInterface");
132  }
133  catch (pluginlib::PluginlibException& ex)
134  {
135  RCLCPP_ERROR(LOGGER, "Exception while creating constraint solver plugin loader '%s'", ex.what());
136  return false;
137  }
138  try
139  {
140  local_constraint_solver_instance_ =
141  local_constraint_solver_plugin_loader_->createUniqueInstance(config_.local_constraint_solver_plugin_name);
142  if (!local_constraint_solver_instance_->initialize(node_, planning_scene_monitor_, config_.group_name))
143  throw std::runtime_error("Unable to initialize constraint solver plugin");
144  RCLCPP_INFO(LOGGER, "Using constraint solver interface '%s'", config_.local_constraint_solver_plugin_name.c_str());
145  }
146  catch (pluginlib::PluginlibException& ex)
147  {
148  RCLCPP_ERROR(LOGGER, "Exception while loading constraint solver '%s': '%s'",
149  config_.local_constraint_solver_plugin_name.c_str(), ex.what());
150  return false;
151  }
152 
153  // Initialize local planning request action server
154  cb_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
155  local_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::LocalPlanner>(
156  node_, config_.local_planning_action_name,
157  // Goal callback
158  [this](const rclcpp_action::GoalUUID& /*unused*/,
159  const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal>& /*unused*/) {
160  RCLCPP_INFO(LOGGER, "Received local planning goal request");
161  // If another goal is active, cancel it and reject this goal
162  if (long_callback_thread_.joinable())
163  {
164  // Try to terminate the execution thread
165  auto future = std::async(std::launch::async, &std::thread::join, &long_callback_thread_);
166  if (future.wait_for(JOIN_THREAD_TIMEOUT) == std::future_status::timeout)
167  {
168  RCLCPP_WARN(LOGGER, "Another goal was running. Rejecting the new hybrid planning goal.");
169  return rclcpp_action::GoalResponse::REJECT;
170  }
171  }
172  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
173  },
174  // Cancel callback
175  [this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::LocalPlanner>>& /*unused*/) {
176  RCLCPP_INFO(LOGGER, "Received request to cancel local planning goal");
177  state_ = LocalPlannerState::ABORT;
178  if (long_callback_thread_.joinable())
179  {
180  long_callback_thread_.join();
181  }
182  return rclcpp_action::CancelResponse::ACCEPT;
183  },
184  // Execution callback
185  [this](std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::LocalPlanner>> goal_handle) {
186  local_planning_goal_handle_ = std::move(goal_handle);
187  // Check if a previous goal was running and needs to be cancelled.
188  if (long_callback_thread_.joinable())
189  {
190  long_callback_thread_.join();
191  }
192  // Start a local planning loop.
193  // This needs to return quickly to avoid blocking the executor, so run the local planner in a new thread.
194  auto local_planner_timer = [&]() {
195  timer_ =
196  node_->create_wall_timer(1s / config_.local_planning_frequency, [this]() { return executeIteration(); });
197  };
198  long_callback_thread_ = std::thread(local_planner_timer);
199  },
200  rcl_action_server_get_default_options(), cb_group_);
201 
202  // Initialize global trajectory listener
203  global_solution_subscriber_ = node_->create_subscription<moveit_msgs::msg::MotionPlanResponse>(
204  config_.global_solution_topic, rclcpp::SystemDefaultsQoS(),
205  [this](const moveit_msgs::msg::MotionPlanResponse::ConstSharedPtr& msg) {
206  // Add received trajectory to internal reference trajectory
207  robot_trajectory::RobotTrajectory new_trajectory(planning_scene_monitor_->getRobotModel(), msg->group_name);
208  moveit::core::RobotState start_state(planning_scene_monitor_->getRobotModel());
209  moveit::core::robotStateMsgToRobotState(msg->trajectory_start, start_state);
210  new_trajectory.setRobotTrajectoryMsg(start_state, msg->trajectory);
211  *local_planner_feedback_ = trajectory_operator_instance_->addTrajectorySegment(new_trajectory);
212 
213  // Feedback is only send when the hybrid planning architecture should react to a discrete event that occurred
214  // when the reference trajectory is updated
215  if (!local_planner_feedback_->feedback.empty())
216  {
217  local_planning_goal_handle_->publish_feedback(local_planner_feedback_);
218  }
219 
220  // Update local planner state
222  });
223 
224  // Initialize local solution publisher
225  RCLCPP_INFO(LOGGER, "Using '%s' as local solution topic type", config_.local_solution_topic_type.c_str());
226  if (config_.local_solution_topic_type == "trajectory_msgs/JointTrajectory")
227  {
228  local_trajectory_publisher_ =
229  node_->create_publisher<trajectory_msgs::msg::JointTrajectory>(config_.local_solution_topic, 1);
230  }
231  else if (config_.local_solution_topic_type == "std_msgs/Float64MultiArray")
232  {
233  local_solution_publisher_ =
234  node_->create_publisher<std_msgs::msg::Float64MultiArray>(config_.local_solution_topic, 1);
235  }
236  else if (config_.local_solution_topic_type == "CUSTOM")
237  {
238  // Local solution publisher is defined by the local constraint solver plugin
239  }
240 
242  return true;
243 }
244 
245 void LocalPlannerComponent::executeIteration()
246 {
247  auto result = std::make_shared<moveit_msgs::action::LocalPlanner::Result>();
248 
249  // Do different things depending on the planner's internal state
250  switch (state_)
251  {
252  // Wait for global solution to be published
253  case LocalPlannerState::AWAIT_GLOBAL_TRAJECTORY:
254  // Do nothing
255  return;
256  // Notify action client that local planning failed
257  case LocalPlannerState::ABORT:
258  {
259  result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
260  result->error_message = "Local planner is in an aborted state. Resetting.";
261  local_planning_goal_handle_->abort(result);
262  reset();
263  return;
264  }
265  // If the planner received an action request and a global solution it starts to plan locally
266  case LocalPlannerState::LOCAL_PLANNING_ACTIVE:
267  {
268  planning_scene_monitor_->updateSceneWithCurrentState();
269 
270  // Read current robot state
271  const moveit::core::RobotState current_robot_state = [this] {
272  planning_scene_monitor::LockedPlanningSceneRO ls(planning_scene_monitor_);
273  return ls->getCurrentState();
274  }();
275 
276  // Check if the global goal is reached
277  if (trajectory_operator_instance_->getTrajectoryProgress(current_robot_state) > PROGRESS_THRESHOLD)
278  {
279  local_planning_goal_handle_->succeed(result);
280  reset();
281  return;
282  }
283 
284  // Get local goal trajectory to follow
285  robot_trajectory::RobotTrajectory local_trajectory =
286  robot_trajectory::RobotTrajectory(planning_scene_monitor_->getRobotModel(), config_.group_name);
287  *local_planner_feedback_ =
288  trajectory_operator_instance_->getLocalTrajectory(current_robot_state, local_trajectory);
289 
290  // Feedback is only sent when the hybrid planning architecture should react to a discrete event that occurred
291  // during the identification of the local planning problem
292  if (!local_planner_feedback_->feedback.empty())
293  {
294  local_planning_goal_handle_->publish_feedback(local_planner_feedback_);
295  RCLCPP_ERROR(LOGGER, "Local planner somehow failed");
296  reset();
297  return;
298  }
299 
300  // Solve local planning problem
301  trajectory_msgs::msg::JointTrajectory local_solution;
302 
303  // Feedback is only send when the hybrid planning architecture should react to a discrete event that occurred
304  // while computing a local solution
305  *local_planner_feedback_ = local_constraint_solver_instance_->solve(
306  local_trajectory, local_planning_goal_handle_->get_goal(), local_solution);
307 
308  // Feedback is only send when the hybrid planning architecture should react to a discrete event
309  if (!local_planner_feedback_->feedback.empty())
310  {
311  local_planning_goal_handle_->publish_feedback(local_planner_feedback_);
312  return;
313  }
314 
315  // Use a configurable message interface like MoveIt servo
316  // (See https://github.com/ros-planning/moveit2/blob/main/moveit_ros/moveit_servo/src/servo_calcs.cpp)
317  // Format outgoing msg in the right format
318  // (trajectory_msgs/JointTrajectory or joint positions/velocities in form of std_msgs/Float64MultiArray).
319  if (config_.local_solution_topic_type == "trajectory_msgs/JointTrajectory")
320  {
321  local_trajectory_publisher_->publish(local_solution);
322  }
323  else if (config_.local_solution_topic_type == "std_msgs/Float64MultiArray")
324  {
325  // Transform "trajectory_msgs/JointTrajectory" to "std_msgs/Float64MultiArray"
326  auto joints = std::make_unique<std_msgs::msg::Float64MultiArray>();
327  if (!local_solution.points.empty())
328  {
329  if (config_.publish_joint_positions)
330  {
331  joints->data = local_solution.points[0].positions;
332  }
333  else if (config_.publish_joint_velocities)
334  {
335  joints->data = local_solution.points[0].velocities;
336  }
337  }
338  local_solution_publisher_->publish(std::move(joints));
339  }
340  else if (config_.local_solution_topic_type == "CUSTOM")
341  {
342  // Local solution publisher is defined by the local constraint solver plugin
343  }
344  return;
345  }
346  default:
347  {
348  result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
349  result->error_message = "Unexpected failure.";
350  local_planning_goal_handle_->abort(result);
351  RCLCPP_ERROR(LOGGER, "Local planner somehow failed"); // TODO(sjahr) Add more detailed failure information
352  reset();
353  return;
354  }
355  }
356 };
357 
358 void LocalPlannerComponent::reset()
359 {
360  local_constraint_solver_instance_->reset();
361  trajectory_operator_instance_->reset();
362  timer_->cancel();
363  state_ = LocalPlannerState::AWAIT_GLOBAL_TRAJECTORY;
364 }
365 } // namespace moveit::hybrid_planning
366 
367 // Register the component with class_loader
368 #include <rclcpp_components/register_node_macro.hpp>
369 RCLCPP_COMPONENTS_REGISTER_NODE(moveit::hybrid_planning::LocalPlannerComponent)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
LocalPlannerComponent(const rclcpp::NodeOptions &options)
Constructor.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Maintain a sequence of waypoints and the time durations between these waypoints.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
const rclcpp::Logger LOGGER
Definition: async_test.h:31