Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
planner_server.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2019 Samsung Research America
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include <chrono>
17 #include <cmath>
18 #include <iomanip>
19 #include <iostream>
20 #include <limits>
21 #include <iterator>
22 #include <memory>
23 #include <string>
24 #include <vector>
25 #include <utility>
26 
27 #include "builtin_interfaces/msg/duration.hpp"
28 #include "lifecycle_msgs/msg/state.hpp"
29 #include "nav2_util/costmap.hpp"
30 #include "nav2_util/node_utils.hpp"
31 #include "nav2_util/geometry_utils.hpp"
32 #include "nav2_costmap_2d/cost_values.hpp"
33 
34 #include "nav2_planner/planner_server.hpp"
35 
36 using namespace std::chrono_literals;
37 using rcl_interfaces::msg::ParameterType;
38 using std::placeholders::_1;
39 
40 namespace nav2_planner
41 {
42 
43 PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
44 : nav2_util::LifecycleNode("planner_server", "", options),
45  gp_loader_("nav2_core", "nav2_core::GlobalPlanner"),
46  default_ids_{"GridBased"},
47  default_types_{"nav2_navfn_planner::NavfnPlanner"},
48  costmap_update_timeout_(1s),
49  costmap_(nullptr)
50 {
51  RCLCPP_INFO(get_logger(), "Creating");
52 
53  // Declare this node's parameters
54  declare_parameter("planner_plugins", default_ids_);
55  declare_parameter("expected_planner_frequency", 1.0);
56  declare_parameter("action_server_result_timeout", 10.0);
57  declare_parameter("costmap_update_timeout", 1.0);
58 
59  get_parameter("planner_plugins", planner_ids_);
60  if (planner_ids_ == default_ids_) {
61  for (size_t i = 0; i < default_ids_.size(); ++i) {
62  declare_parameter(default_ids_[i] + ".plugin", default_types_[i]);
63  }
64  }
65 
66  // Setup the global costmap
67  costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
68  "global_costmap", std::string{get_namespace()}, "global_costmap",
69  get_parameter("use_sim_time").as_bool());
70 }
71 
73 {
74  /*
75  * Backstop ensuring this state is destroyed, even if deactivate/cleanup are
76  * never called.
77  */
78  planners_.clear();
79  costmap_thread_.reset();
80 }
81 
82 nav2_util::CallbackReturn
83 PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
84 {
85  RCLCPP_INFO(get_logger(), "Configuring");
86 
87  costmap_ros_->configure();
88  costmap_ = costmap_ros_->getCostmap();
89 
90  if (!costmap_ros_->getUseRadius()) {
91  collision_checker_ =
92  std::make_unique<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(
93  costmap_);
94  }
95 
96  // Launch a thread to run the costmap node
97  costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
98 
99  RCLCPP_DEBUG(
100  get_logger(), "Costmap size: %d,%d",
101  costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
102 
103  tf_ = costmap_ros_->getTfBuffer();
104 
105  planner_types_.resize(planner_ids_.size());
106 
107  auto node = shared_from_this();
108 
109  for (size_t i = 0; i != planner_ids_.size(); i++) {
110  try {
111  planner_types_[i] = nav2_util::get_plugin_type_param(
112  node, planner_ids_[i]);
113  nav2_core::GlobalPlanner::Ptr planner =
114  gp_loader_.createUniqueInstance(planner_types_[i]);
115  RCLCPP_INFO(
116  get_logger(), "Created global planner plugin %s of type %s",
117  planner_ids_[i].c_str(), planner_types_[i].c_str());
118  planner->configure(node, planner_ids_[i], tf_, costmap_ros_);
119  planners_.insert({planner_ids_[i], planner});
120  } catch (const std::exception & ex) {
121  RCLCPP_FATAL(
122  get_logger(), "Failed to create global planner. Exception: %s",
123  ex.what());
124  on_cleanup(state);
125  return nav2_util::CallbackReturn::FAILURE;
126  }
127  }
128 
129  for (size_t i = 0; i != planner_ids_.size(); i++) {
130  planner_ids_concat_ += planner_ids_[i] + std::string(" ");
131  }
132 
133  RCLCPP_INFO(
134  get_logger(),
135  "Planner Server has %s planners available.", planner_ids_concat_.c_str());
136 
137  double expected_planner_frequency;
138  get_parameter("expected_planner_frequency", expected_planner_frequency);
139  if (expected_planner_frequency > 0) {
140  max_planner_duration_ = 1 / expected_planner_frequency;
141  } else {
142  RCLCPP_WARN(
143  get_logger(),
144  "The expected planner frequency parameter is %.4f Hz. The value should to be greater"
145  " than 0.0 to turn on duration overrrun warning messages", expected_planner_frequency);
146  max_planner_duration_ = 0.0;
147  }
148 
149  // Initialize pubs & subs
150  plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan", 1);
151 
152  double action_server_result_timeout;
153  get_parameter("action_server_result_timeout", action_server_result_timeout);
154  rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
155  server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
156 
157  double costmap_update_timeout_dbl;
158  get_parameter("costmap_update_timeout", costmap_update_timeout_dbl);
159  costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
160 
161  // Create the action servers for path planning to a pose and through poses
162  action_server_pose_ = std::make_unique<ActionServerToPose>(
164  "compute_path_to_pose",
165  std::bind(&PlannerServer::computePlan, this),
166  nullptr,
167  std::chrono::milliseconds(500),
168  true, server_options);
169 
170  action_server_poses_ = std::make_unique<ActionServerThroughPoses>(
172  "compute_path_through_poses",
173  std::bind(&PlannerServer::computePlanThroughPoses, this),
174  nullptr,
175  std::chrono::milliseconds(500),
176  true, server_options);
177 
178  return nav2_util::CallbackReturn::SUCCESS;
179 }
180 
181 nav2_util::CallbackReturn
182 PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
183 {
184  RCLCPP_INFO(get_logger(), "Activating");
185 
186  plan_publisher_->on_activate();
187  action_server_pose_->activate();
188  action_server_poses_->activate();
189  const auto costmap_ros_state = costmap_ros_->activate();
190  if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
191  return nav2_util::CallbackReturn::FAILURE;
192  }
193 
194  PlannerMap::iterator it;
195  for (it = planners_.begin(); it != planners_.end(); ++it) {
196  it->second->activate();
197  }
198 
199  auto node = shared_from_this();
200 
201  is_path_valid_service_ = node->create_service<nav2_msgs::srv::IsPathValid>(
202  "is_path_valid",
203  std::bind(
205  std::placeholders::_1, std::placeholders::_2));
206 
207  // Add callback for dynamic parameters
208  dyn_params_handler_ = node->add_on_set_parameters_callback(
209  std::bind(&PlannerServer::dynamicParametersCallback, this, _1));
210 
211  // create bond connection
212  createBond();
213 
214  return nav2_util::CallbackReturn::SUCCESS;
215 }
216 
217 nav2_util::CallbackReturn
218 PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
219 {
220  RCLCPP_INFO(get_logger(), "Deactivating");
221 
222  action_server_pose_->deactivate();
223  action_server_poses_->deactivate();
224  plan_publisher_->on_deactivate();
225 
226  /*
227  * The costmap is also a lifecycle node, so it may have already fired on_deactivate
228  * via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
229  * in the order added, the preshutdown callbacks clearly don't per se, due to using an
230  * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
231  * ordering assumption: https://github.com/ros2/rclcpp/issues/2096
232  */
233  costmap_ros_->deactivate();
234 
235  PlannerMap::iterator it;
236  for (it = planners_.begin(); it != planners_.end(); ++it) {
237  it->second->deactivate();
238  }
239 
240  dyn_params_handler_.reset();
241 
242  // destroy bond connection
243  destroyBond();
244 
245  return nav2_util::CallbackReturn::SUCCESS;
246 }
247 
248 nav2_util::CallbackReturn
249 PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
250 {
251  RCLCPP_INFO(get_logger(), "Cleaning up");
252 
253  action_server_pose_.reset();
254  action_server_poses_.reset();
255  plan_publisher_.reset();
256  tf_.reset();
257 
258  costmap_ros_->cleanup();
259 
260  PlannerMap::iterator it;
261  for (it = planners_.begin(); it != planners_.end(); ++it) {
262  it->second->cleanup();
263  }
264 
265  planners_.clear();
266  costmap_thread_.reset();
267  costmap_ = nullptr;
268  return nav2_util::CallbackReturn::SUCCESS;
269 }
270 
271 nav2_util::CallbackReturn
272 PlannerServer::on_shutdown(const rclcpp_lifecycle::State &)
273 {
274  RCLCPP_INFO(get_logger(), "Shutting down");
275  return nav2_util::CallbackReturn::SUCCESS;
276 }
277 
278 template<typename T>
280  std::unique_ptr<nav2_util::SimpleActionServer<T>> & action_server)
281 {
282  if (action_server == nullptr || !action_server->is_server_active()) {
283  RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
284  return true;
285  }
286 
287  return false;
288 }
289 
291 {
292  // Don't compute a plan until costmap is valid (after clear costmap)
293  rclcpp::Rate r(100);
294  auto waiting_start = now();
295  while (!costmap_ros_->isCurrent()) {
296  if (now() - waiting_start > costmap_update_timeout_) {
297  throw nav2_core::PlannerTimedOut("Costmap timed out waiting for update");
298  }
299  r.sleep();
300  }
301 }
302 
303 template<typename T>
305  std::unique_ptr<nav2_util::SimpleActionServer<T>> & action_server)
306 {
307  if (action_server->is_cancel_requested()) {
308  RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action.");
309  action_server->terminate_all();
310  return true;
311  }
312 
313  return false;
314 }
315 
316 template<typename T>
318  std::unique_ptr<nav2_util::SimpleActionServer<T>> & action_server,
319  typename std::shared_ptr<const typename T::Goal> goal)
320 {
321  if (action_server->is_preempt_requested()) {
322  goal = action_server->accept_pending_goal();
323  }
324 }
325 
326 template<typename T>
328  typename std::shared_ptr<const typename T::Goal> goal,
329  geometry_msgs::msg::PoseStamped & start)
330 {
331  if (goal->use_start) {
332  start = goal->start;
333  } else if (!costmap_ros_->getRobotPose(start)) {
334  return false;
335  }
336 
337  return true;
338 }
339 
341  geometry_msgs::msg::PoseStamped & curr_start,
342  geometry_msgs::msg::PoseStamped & curr_goal)
343 {
344  if (!costmap_ros_->transformPoseToGlobalFrame(curr_start, curr_start) ||
345  !costmap_ros_->transformPoseToGlobalFrame(curr_goal, curr_goal))
346  {
347  return false;
348  }
349 
350  return true;
351 }
352 
353 template<typename T>
355  const geometry_msgs::msg::PoseStamped & goal,
356  const nav_msgs::msg::Path & path,
357  const std::string & planner_id)
358 {
359  if (path.poses.empty()) {
360  RCLCPP_WARN(
361  get_logger(), "Planning algorithm %s failed to generate a valid"
362  " path to (%.2f, %.2f)", planner_id.c_str(),
363  goal.pose.position.x, goal.pose.position.y);
364  return false;
365  }
366 
367  RCLCPP_DEBUG(
368  get_logger(),
369  "Found valid path of size %zu to (%.2f, %.2f)",
370  path.poses.size(), goal.pose.position.x,
371  goal.pose.position.y);
372 
373  return true;
374 }
375 
377 {
378  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
379 
380  auto start_time = this->now();
381 
382  // Initialize the ComputePathThroughPoses goal and result
383  auto goal = action_server_poses_->get_current_goal();
384  auto result = std::make_shared<ActionThroughPoses::Result>();
385  nav_msgs::msg::Path concat_path;
386 
387  geometry_msgs::msg::PoseStamped curr_start, curr_goal;
388 
389  try {
390  if (isServerInactive(action_server_poses_) || isCancelRequested(action_server_poses_)) {
391  return;
392  }
393 
394  waitForCostmap();
395 
396  getPreemptedGoalIfRequested(action_server_poses_, goal);
397 
398  if (goal->goals.empty()) {
399  throw nav2_core::NoViapointsGiven("No viapoints given");
400  }
401 
402  // Use start pose if provided otherwise use current robot pose
403  geometry_msgs::msg::PoseStamped start;
404  if (!getStartPose<ActionThroughPoses>(goal, start)) {
405  throw nav2_core::PlannerTFError("Unable to get start pose");
406  }
407 
408  auto cancel_checker = [this]() {
409  return action_server_poses_->is_cancel_requested();
410  };
411 
412  // Get consecutive paths through these points
413  for (unsigned int i = 0; i != goal->goals.size(); i++) {
414  // Get starting point
415  if (i == 0) {
416  curr_start = start;
417  } else {
418  // pick the end of the last planning task as the start for the next one
419  // to allow for path tolerance deviations
420  curr_start = concat_path.poses.back();
421  curr_start.header = concat_path.header;
422  }
423  curr_goal = goal->goals[i];
424 
425  // Transform them into the global frame
426  if (!transformPosesToGlobalFrame(curr_start, curr_goal)) {
427  throw nav2_core::PlannerTFError("Unable to transform poses to global frame");
428  }
429 
430  // Get plan from start -> goal
431  nav_msgs::msg::Path curr_path = getPlan(
432  curr_start, curr_goal, goal->planner_id,
433  cancel_checker);
434 
435  if (!validatePath<ActionThroughPoses>(curr_goal, curr_path, goal->planner_id)) {
436  throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
437  }
438 
439  // Concatenate paths together
440  concat_path.poses.insert(
441  concat_path.poses.end(), curr_path.poses.begin(), curr_path.poses.end());
442  concat_path.header = curr_path.header;
443  }
444 
445  // Publish the plan for visualization purposes
446  result->path = concat_path;
447  publishPlan(result->path);
448 
449  auto cycle_duration = this->now() - start_time;
450  result->planning_time = cycle_duration;
451 
452  if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
453  RCLCPP_WARN(
454  get_logger(),
455  "Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
456  1 / max_planner_duration_, 1 / cycle_duration.seconds());
457  }
458 
459  action_server_poses_->succeeded_current(result);
460  } catch (nav2_core::InvalidPlanner & ex) {
461  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
462  result->error_code = ActionThroughPosesResult::INVALID_PLANNER;
463  action_server_poses_->terminate_current(result);
464  } catch (nav2_core::StartOccupied & ex) {
465  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
466  result->error_code = ActionThroughPosesResult::START_OCCUPIED;
467  action_server_poses_->terminate_current(result);
468  } catch (nav2_core::GoalOccupied & ex) {
469  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
470  result->error_code = ActionThroughPosesResult::GOAL_OCCUPIED;
471  action_server_poses_->terminate_current(result);
472  } catch (nav2_core::NoValidPathCouldBeFound & ex) {
473  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
474  result->error_code = ActionThroughPosesResult::NO_VALID_PATH;
475  action_server_poses_->terminate_current(result);
476  } catch (nav2_core::PlannerTimedOut & ex) {
477  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
478  result->error_code = ActionThroughPosesResult::TIMEOUT;
479  action_server_poses_->terminate_current(result);
480  } catch (nav2_core::StartOutsideMapBounds & ex) {
481  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
482  result->error_code = ActionThroughPosesResult::START_OUTSIDE_MAP;
483  action_server_poses_->terminate_current(result);
484  } catch (nav2_core::GoalOutsideMapBounds & ex) {
485  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
486  result->error_code = ActionThroughPosesResult::GOAL_OUTSIDE_MAP;
487  action_server_poses_->terminate_current(result);
488  } catch (nav2_core::PlannerTFError & ex) {
489  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
490  result->error_code = ActionThroughPosesResult::TF_ERROR;
491  action_server_poses_->terminate_current(result);
492  } catch (nav2_core::NoViapointsGiven & ex) {
493  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
494  result->error_code = ActionThroughPosesResult::NO_VIAPOINTS_GIVEN;
495  action_server_poses_->terminate_current(result);
496  } catch (nav2_core::PlannerCancelled &) {
497  RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action.");
498  action_server_poses_->terminate_all();
499  } catch (std::exception & ex) {
500  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
501  result->error_code = ActionThroughPosesResult::UNKNOWN;
502  action_server_poses_->terminate_current(result);
503  }
504 }
505 
506 void
508 {
509  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
510 
511  auto start_time = this->now();
512 
513  // Initialize the ComputePathToPose goal and result
514  auto goal = action_server_pose_->get_current_goal();
515  auto result = std::make_shared<ActionToPose::Result>();
516 
517  geometry_msgs::msg::PoseStamped start;
518 
519  try {
520  if (isServerInactive(action_server_pose_) || isCancelRequested(action_server_pose_)) {
521  return;
522  }
523 
524  waitForCostmap();
525 
526  getPreemptedGoalIfRequested(action_server_pose_, goal);
527 
528  // Use start pose if provided otherwise use current robot pose
529  if (!getStartPose<ActionToPose>(goal, start)) {
530  throw nav2_core::PlannerTFError("Unable to get start pose");
531  }
532 
533  // Transform them into the global frame
534  geometry_msgs::msg::PoseStamped goal_pose = goal->goal;
535  if (!transformPosesToGlobalFrame(start, goal_pose)) {
536  throw nav2_core::PlannerTFError("Unable to transform poses to global frame");
537  }
538 
539  auto cancel_checker = [this]() {
540  return action_server_pose_->is_cancel_requested();
541  };
542 
543  result->path = getPlan(start, goal_pose, goal->planner_id, cancel_checker);
544 
545  if (!validatePath<ActionThroughPoses>(goal_pose, result->path, goal->planner_id)) {
546  throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
547  }
548 
549  // Publish the plan for visualization purposes
550  publishPlan(result->path);
551 
552  auto cycle_duration = this->now() - start_time;
553  result->planning_time = cycle_duration;
554 
555  if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
556  RCLCPP_WARN(
557  get_logger(),
558  "Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
559  1 / max_planner_duration_, 1 / cycle_duration.seconds());
560  }
561  action_server_pose_->succeeded_current(result);
562  } catch (nav2_core::InvalidPlanner & ex) {
563  exceptionWarning(start, goal->goal, goal->planner_id, ex);
564  result->error_code = ActionToPoseResult::INVALID_PLANNER;
565  action_server_pose_->terminate_current(result);
566  } catch (nav2_core::StartOccupied & ex) {
567  exceptionWarning(start, goal->goal, goal->planner_id, ex);
568  result->error_code = ActionToPoseResult::START_OCCUPIED;
569  action_server_pose_->terminate_current(result);
570  } catch (nav2_core::GoalOccupied & ex) {
571  exceptionWarning(start, goal->goal, goal->planner_id, ex);
572  result->error_code = ActionToPoseResult::GOAL_OCCUPIED;
573  action_server_pose_->terminate_current(result);
574  } catch (nav2_core::NoValidPathCouldBeFound & ex) {
575  exceptionWarning(start, goal->goal, goal->planner_id, ex);
576  result->error_code = ActionToPoseResult::NO_VALID_PATH;
577  action_server_pose_->terminate_current(result);
578  } catch (nav2_core::PlannerTimedOut & ex) {
579  exceptionWarning(start, goal->goal, goal->planner_id, ex);
580  result->error_code = ActionToPoseResult::TIMEOUT;
581  action_server_pose_->terminate_current(result);
582  } catch (nav2_core::StartOutsideMapBounds & ex) {
583  exceptionWarning(start, goal->goal, goal->planner_id, ex);
584  result->error_code = ActionToPoseResult::START_OUTSIDE_MAP;
585  action_server_pose_->terminate_current(result);
586  } catch (nav2_core::GoalOutsideMapBounds & ex) {
587  exceptionWarning(start, goal->goal, goal->planner_id, ex);
588  result->error_code = ActionToPoseResult::GOAL_OUTSIDE_MAP;
589  action_server_pose_->terminate_current(result);
590  } catch (nav2_core::PlannerTFError & ex) {
591  exceptionWarning(start, goal->goal, goal->planner_id, ex);
592  result->error_code = ActionToPoseResult::TF_ERROR;
593  action_server_pose_->terminate_current(result);
594  } catch (nav2_core::PlannerCancelled &) {
595  RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action.");
596  action_server_pose_->terminate_all();
597  } catch (std::exception & ex) {
598  exceptionWarning(start, goal->goal, goal->planner_id, ex);
599  result->error_code = ActionToPoseResult::UNKNOWN;
600  action_server_pose_->terminate_current(result);
601  }
602 }
603 
604 nav_msgs::msg::Path
606  const geometry_msgs::msg::PoseStamped & start,
607  const geometry_msgs::msg::PoseStamped & goal,
608  const std::string & planner_id,
609  std::function<bool()> cancel_checker)
610 {
611  RCLCPP_DEBUG(
612  get_logger(), "Attempting to a find path from (%.2f, %.2f) to "
613  "(%.2f, %.2f).", start.pose.position.x, start.pose.position.y,
614  goal.pose.position.x, goal.pose.position.y);
615 
616  if (planners_.find(planner_id) != planners_.end()) {
617  return planners_[planner_id]->createPlan(start, goal, cancel_checker);
618  } else {
619  if (planners_.size() == 1 && planner_id.empty()) {
620  RCLCPP_WARN_ONCE(
621  get_logger(), "No planners specified in action call. "
622  "Server will use only plugin %s in server."
623  " This warning will appear once.", planner_ids_concat_.c_str());
624  return planners_[planners_.begin()->first]->createPlan(start, goal, cancel_checker);
625  } else {
626  RCLCPP_ERROR(
627  get_logger(), "planner %s is not a valid planner. "
628  "Planner names are: %s", planner_id.c_str(),
629  planner_ids_concat_.c_str());
630  throw nav2_core::InvalidPlanner("Planner id " + planner_id + " is invalid");
631  }
632  }
633 
634  return nav_msgs::msg::Path();
635 }
636 
637 void
638 PlannerServer::publishPlan(const nav_msgs::msg::Path & path)
639 {
640  auto msg = std::make_unique<nav_msgs::msg::Path>(path);
641  if (plan_publisher_->is_activated() && plan_publisher_->get_subscription_count() > 0) {
642  plan_publisher_->publish(std::move(msg));
643  }
644 }
645 
647  const std::shared_ptr<nav2_msgs::srv::IsPathValid::Request> request,
648  std::shared_ptr<nav2_msgs::srv::IsPathValid::Response> response)
649 {
650  response->is_valid = true;
651 
652  if (request->path.poses.empty()) {
653  response->is_valid = false;
654  return;
655  }
656 
657  geometry_msgs::msg::PoseStamped current_pose;
658  unsigned int closest_point_index = 0;
659  if (costmap_ros_->getRobotPose(current_pose)) {
660  float current_distance = std::numeric_limits<float>::max();
661  float closest_distance = current_distance;
662  geometry_msgs::msg::Point current_point = current_pose.pose.position;
663  for (unsigned int i = 0; i < request->path.poses.size(); ++i) {
664  geometry_msgs::msg::Point path_point = request->path.poses[i].pose.position;
665 
666  current_distance = nav2_util::geometry_utils::euclidean_distance(
667  current_point,
668  path_point);
669 
670  if (current_distance < closest_distance) {
671  closest_point_index = i;
672  closest_distance = current_distance;
673  }
674  }
675 
681  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
682  unsigned int mx = 0;
683  unsigned int my = 0;
684 
685  bool use_radius = costmap_ros_->getUseRadius();
686 
687  unsigned int cost = nav2_costmap_2d::FREE_SPACE;
688  for (unsigned int i = closest_point_index; i < request->path.poses.size(); ++i) {
689  auto & position = request->path.poses[i].pose.position;
690  if (use_radius) {
691  if (costmap_->worldToMap(position.x, position.y, mx, my)) {
692  cost = costmap_->getCost(mx, my);
693  } else {
694  cost = nav2_costmap_2d::LETHAL_OBSTACLE;
695  }
696  } else {
697  nav2_costmap_2d::Footprint footprint = costmap_ros_->getRobotFootprint();
698  auto theta = tf2::getYaw(request->path.poses[i].pose.orientation);
699  cost = static_cast<unsigned int>(collision_checker_->footprintCostAtPose(
700  position.x, position.y, theta, footprint));
701  }
702 
703  if (use_radius &&
704  (cost == nav2_costmap_2d::LETHAL_OBSTACLE ||
705  cost == nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE))
706  {
707  response->is_valid = false;
708  break;
709  } else if (cost == nav2_costmap_2d::LETHAL_OBSTACLE) {
710  response->is_valid = false;
711  break;
712  }
713  }
714  }
715 }
716 
717 rcl_interfaces::msg::SetParametersResult
718 PlannerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
719 {
720  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
721  rcl_interfaces::msg::SetParametersResult result;
722  for (auto parameter : parameters) {
723  const auto & type = parameter.get_type();
724  const auto & name = parameter.get_name();
725 
726  if (type == ParameterType::PARAMETER_DOUBLE) {
727  if (name == "expected_planner_frequency") {
728  if (parameter.as_double() > 0) {
729  max_planner_duration_ = 1 / parameter.as_double();
730  } else {
731  RCLCPP_WARN(
732  get_logger(),
733  "The expected planner frequency parameter is %.4f Hz. The value should to be greater"
734  " than 0.0 to turn on duration overrrun warning messages", parameter.as_double());
735  max_planner_duration_ = 0.0;
736  }
737  }
738  }
739  }
740 
741  result.successful = true;
742  return result;
743 }
744 
745 void PlannerServer::exceptionWarning(
746  const geometry_msgs::msg::PoseStamped & start,
747  const geometry_msgs::msg::PoseStamped & goal,
748  const std::string & planner_id,
749  const std::exception & ex)
750 {
751  RCLCPP_WARN(
752  get_logger(), "%s plugin failed to plan from (%.2f, %.2f) to (%0.2f, %.2f): \"%s\"",
753  planner_id.c_str(),
754  start.pose.position.x, start.pose.position.y,
755  goal.pose.position.x, goal.pose.position.y,
756  ex.what());
757 }
758 
759 } // namespace nav2_planner
760 
761 #include "rclcpp_components/register_node_macro.hpp"
762 
763 // Register the component with class_loader.
764 // This acts as a sort of entry point, allowing the component to be discoverable when its library
765 // is being loaded into a running process.
766 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_planner::PlannerServer)
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:285
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:514
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:519
An action server implements the behavior tree's ComputePathToPose interface and hosts various plugins...
void publishPlan(const nav_msgs::msg::Path &path)
Publish a path for visualization purposes.
void computePlan()
The action server callback which calls planner to get the path ComputePathToPose.
void getPreemptedGoalIfRequested(std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server, typename std::shared_ptr< const typename T::Goal > goal)
Check if an action server has a preemption request and replaces the goal with the new preemption goal...
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
void waitForCostmap()
Wait for costmap to be valid with updated sensor data or repopulate after a clearing recovery....
bool getStartPose(typename std::shared_ptr< const typename T::Goal > goal, geometry_msgs::msg::PoseStamped &start)
Get the starting pose from costmap or message, if valid.
~PlannerServer()
A destructor for nav2_planner::PlannerServer.
bool isServerInactive(std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server)
Check if an action server is valid / active.
nav_msgs::msg::Path getPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, const std::string &planner_id, std::function< bool()> cancel_checker)
Method to get plan from the desired plugin.
void isPathValid(const std::shared_ptr< nav2_msgs::srv::IsPathValid::Request > request, std::shared_ptr< nav2_msgs::srv::IsPathValid::Response > response)
The service callback to determine if the path is still valid.
void computePlanThroughPoses()
The action server callback which calls planner to get the path ComputePathThroughPoses.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
bool isCancelRequested(std::unique_ptr< nav2_util::SimpleActionServer< T >> &action_server)
Check if an action server has a cancellation request pending.
bool validatePath(const geometry_msgs::msg::PoseStamped &curr_goal, const nav_msgs::msg::Path &path, const std::string &planner_id)
Validate that the path contains a meaningful path.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables and initializes planner.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate member variables.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
bool transformPosesToGlobalFrame(geometry_msgs::msg::PoseStamped &curr_start, geometry_msgs::msg::PoseStamped &curr_goal)
Transform start and goal poses into the costmap global frame for path planning plugins to utilize.
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.
An action server wrapper to make applications simpler using Actions.