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