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