Nav2 Navigation Stack - rolling  main
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_ros_common/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::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(), options);
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::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::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::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::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");
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_ = create_action_server<ActionToPose>(
156  "compute_path_to_pose",
157  std::bind(&PlannerServer::computePlan, this),
158  nullptr,
159  std::chrono::milliseconds(500),
160  true);
161 
162  action_server_poses_ = create_action_server<ActionThroughPoses>(
163  "compute_path_through_poses",
164  std::bind(&PlannerServer::computePlanThroughPoses, this),
165  nullptr,
166  std::chrono::milliseconds(500),
167  true);
168 
169  return nav2::CallbackReturn::SUCCESS;
170 }
171 
172 nav2::CallbackReturn
173 PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
174 {
175  RCLCPP_INFO(get_logger(), "Activating");
176 
177  plan_publisher_->on_activate();
178  action_server_pose_->activate();
179  action_server_poses_->activate();
180  const auto costmap_ros_state = costmap_ros_->activate();
181  if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
182  return nav2::CallbackReturn::FAILURE;
183  }
184 
185  PlannerMap::iterator it;
186  for (it = planners_.begin(); it != planners_.end(); ++it) {
187  it->second->activate();
188  }
189 
190  is_path_valid_service_ = create_service<nav2_msgs::srv::IsPathValid>(
191  "is_path_valid",
192  std::bind(&PlannerServer::isPathValid, this, std::placeholders::_1, std::placeholders::_2,
193  std::placeholders::_3));
194 
195  // Add callback for dynamic parameters
196  dyn_params_handler_ = add_on_set_parameters_callback(
197  std::bind(&PlannerServer::dynamicParametersCallback, this, _1));
198 
199  // create bond connection
200  createBond();
201 
202  return nav2::CallbackReturn::SUCCESS;
203 }
204 
205 nav2::CallbackReturn
206 PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
207 {
208  RCLCPP_INFO(get_logger(), "Deactivating");
209 
210  action_server_pose_->deactivate();
211  action_server_poses_->deactivate();
212  plan_publisher_->on_deactivate();
213 
214  /*
215  * The costmap is also a lifecycle node, so it may have already fired on_deactivate
216  * via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
217  * in the order added, the preshutdown callbacks clearly don't per se, due to using an
218  * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
219  * ordering assumption: https://github.com/ros2/rclcpp/issues/2096
220  */
221  costmap_ros_->deactivate();
222 
223  PlannerMap::iterator it;
224  for (it = planners_.begin(); it != planners_.end(); ++it) {
225  it->second->deactivate();
226  }
227 
228  dyn_params_handler_.reset();
229 
230  // destroy bond connection
231  destroyBond();
232 
233  return nav2::CallbackReturn::SUCCESS;
234 }
235 
236 nav2::CallbackReturn
237 PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
238 {
239  RCLCPP_INFO(get_logger(), "Cleaning up");
240 
241  is_path_valid_service_.reset();
242  action_server_pose_.reset();
243  action_server_poses_.reset();
244  plan_publisher_.reset();
245  tf_.reset();
246 
247  costmap_ros_->cleanup();
248 
249  PlannerMap::iterator it;
250  for (it = planners_.begin(); it != planners_.end(); ++it) {
251  it->second->cleanup();
252  }
253 
254  planners_.clear();
255  costmap_thread_.reset();
256  costmap_ = nullptr;
257  return nav2::CallbackReturn::SUCCESS;
258 }
259 
260 nav2::CallbackReturn
261 PlannerServer::on_shutdown(const rclcpp_lifecycle::State &)
262 {
263  RCLCPP_INFO(get_logger(), "Shutting down");
264  return nav2::CallbackReturn::SUCCESS;
265 }
266 
267 template<typename T>
269  typename nav2::SimpleActionServer<T>::SharedPtr & action_server)
270 {
271  if (action_server == nullptr || !action_server->is_server_active()) {
272  RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
273  return true;
274  }
275 
276  return false;
277 }
278 
280 {
281  // Don't compute a plan until costmap is valid (after clear costmap)
282  rclcpp::Rate r(100);
283  auto waiting_start = now();
284  while (!costmap_ros_->isCurrent()) {
285  if (now() - waiting_start > costmap_update_timeout_) {
286  throw nav2_core::PlannerTimedOut("Costmap timed out waiting for update");
287  }
288  r.sleep();
289  }
290 }
291 
292 template<typename T>
294  typename nav2::SimpleActionServer<T>::SharedPtr & action_server)
295 {
296  if (action_server->is_cancel_requested()) {
297  RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action.");
298  action_server->terminate_all();
299  return true;
300  }
301 
302  return false;
303 }
304 
305 template<typename T>
307  typename nav2::SimpleActionServer<T>::SharedPtr & action_server,
308  typename std::shared_ptr<const typename T::Goal> goal)
309 {
310  if (action_server->is_preempt_requested()) {
311  goal = action_server->accept_pending_goal();
312  }
313 }
314 
315 template<typename T>
317  typename std::shared_ptr<const typename T::Goal> goal,
318  geometry_msgs::msg::PoseStamped & start)
319 {
320  if (goal->use_start) {
321  start = goal->start;
322  } else if (!costmap_ros_->getRobotPose(start)) {
323  return false;
324  }
325 
326  return true;
327 }
328 
330  geometry_msgs::msg::PoseStamped & curr_start,
331  geometry_msgs::msg::PoseStamped & curr_goal)
332 {
333  if (!costmap_ros_->transformPoseToGlobalFrame(curr_start, curr_start) ||
334  !costmap_ros_->transformPoseToGlobalFrame(curr_goal, curr_goal))
335  {
336  return false;
337  }
338 
339  return true;
340 }
341 
342 template<typename T>
344  const geometry_msgs::msg::PoseStamped & goal,
345  const nav_msgs::msg::Path & path,
346  const std::string & planner_id)
347 {
348  if (path.poses.empty()) {
349  RCLCPP_WARN(
350  get_logger(), "Planning algorithm %s failed to generate a valid"
351  " path to (%.2f, %.2f)", planner_id.c_str(),
352  goal.pose.position.x, goal.pose.position.y);
353  return false;
354  }
355 
356  RCLCPP_DEBUG(
357  get_logger(),
358  "Found valid path of size %zu to (%.2f, %.2f)",
359  path.poses.size(), goal.pose.position.x,
360  goal.pose.position.y);
361 
362  return true;
363 }
364 
366 {
367  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
368 
369  auto start_time = this->now();
370 
371  // Initialize the ComputePathThroughPoses goal and result
372  auto goal = action_server_poses_->get_current_goal();
373  auto result = std::make_shared<ActionThroughPoses::Result>();
374  nav_msgs::msg::Path concat_path;
375  RCLCPP_INFO(get_logger(), "Computing path through poses to goal.");
376 
377  geometry_msgs::msg::PoseStamped curr_start, curr_goal;
378 
379  try {
380  if (isServerInactive<ActionThroughPoses>(action_server_poses_) ||
381  isCancelRequested<ActionThroughPoses>(action_server_poses_))
382  {
383  return;
384  }
385 
386  waitForCostmap();
387 
388  getPreemptedGoalIfRequested<ActionThroughPoses>(action_server_poses_, goal);
389 
390  if (goal->goals.goals.empty()) {
391  throw nav2_core::NoViapointsGiven("No viapoints given");
392  }
393 
394  // Use start pose if provided otherwise use current robot pose
395  geometry_msgs::msg::PoseStamped start;
396  if (!getStartPose<ActionThroughPoses>(goal, start)) {
397  throw nav2_core::PlannerTFError("Unable to get start pose");
398  }
399 
400  auto cancel_checker = [this]() {
401  return action_server_poses_->is_cancel_requested();
402  };
403 
404  // Get consecutive paths through these points
405  for (unsigned int i = 0; i != goal->goals.goals.size(); i++) {
406  // Get starting point
407  if (i == 0) {
408  curr_start = start;
409  } else {
410  // pick the end of the last planning task as the start for the next one
411  // to allow for path tolerance deviations
412  curr_start = concat_path.poses.back();
413  curr_start.header = concat_path.header;
414  }
415  curr_goal = goal->goals.goals[i];
416 
417  // Transform them into the global frame
418  if (!transformPosesToGlobalFrame(curr_start, curr_goal)) {
419  throw nav2_core::PlannerTFError("Unable to transform poses to global frame");
420  }
421 
422  // Get plan from start -> goal
423  nav_msgs::msg::Path curr_path = getPlan(
424  curr_start, curr_goal, goal->planner_id,
425  cancel_checker);
426 
427  if (!validatePath<ActionThroughPoses>(curr_goal, curr_path, goal->planner_id)) {
428  throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
429  }
430 
431  // Concatenate paths together
432  concat_path.poses.insert(
433  concat_path.poses.end(), curr_path.poses.begin(), curr_path.poses.end());
434  concat_path.header = curr_path.header;
435  }
436 
437  // Publish the plan for visualization purposes
438  result->path = concat_path;
439  publishPlan(result->path);
440 
441  auto cycle_duration = this->now() - start_time;
442  result->planning_time = cycle_duration;
443 
444  if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
445  RCLCPP_WARN(
446  get_logger(),
447  "Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
448  1 / max_planner_duration_, 1 / cycle_duration.seconds());
449  }
450 
451  action_server_poses_->succeeded_current(result);
452  } catch (nav2_core::InvalidPlanner & ex) {
453  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
454  result->error_code = ActionThroughPosesResult::INVALID_PLANNER;
455  action_server_poses_->terminate_current(result);
456  } catch (nav2_core::StartOccupied & ex) {
457  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
458  result->error_code = ActionThroughPosesResult::START_OCCUPIED;
459  action_server_poses_->terminate_current(result);
460  } catch (nav2_core::GoalOccupied & ex) {
461  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
462  result->error_code = ActionThroughPosesResult::GOAL_OCCUPIED;
463  action_server_poses_->terminate_current(result);
464  } catch (nav2_core::NoValidPathCouldBeFound & ex) {
465  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
466  result->error_code = ActionThroughPosesResult::NO_VALID_PATH;
467  action_server_poses_->terminate_current(result);
468  } catch (nav2_core::PlannerTimedOut & ex) {
469  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
470  result->error_code = ActionThroughPosesResult::TIMEOUT;
471  action_server_poses_->terminate_current(result);
472  } catch (nav2_core::StartOutsideMapBounds & ex) {
473  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
474  result->error_code = ActionThroughPosesResult::START_OUTSIDE_MAP;
475  action_server_poses_->terminate_current(result);
476  } catch (nav2_core::GoalOutsideMapBounds & ex) {
477  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
478  result->error_code = ActionThroughPosesResult::GOAL_OUTSIDE_MAP;
479  action_server_poses_->terminate_current(result);
480  } catch (nav2_core::PlannerTFError & ex) {
481  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
482  result->error_code = ActionThroughPosesResult::TF_ERROR;
483  action_server_poses_->terminate_current(result);
484  } catch (nav2_core::NoViapointsGiven & ex) {
485  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
486  result->error_code = ActionThroughPosesResult::NO_VIAPOINTS_GIVEN;
487  action_server_poses_->terminate_current(result);
488  } catch (nav2_core::PlannerCancelled &) {
489  result->error_msg = "Goal was canceled. Canceling planning action.";
490  RCLCPP_INFO(get_logger(), result->error_msg.c_str());
491  action_server_poses_->terminate_all();
492  } catch (std::exception & ex) {
493  exceptionWarning(curr_start, curr_goal, goal->planner_id, ex, result->error_msg);
494  result->error_code = ActionThroughPosesResult::UNKNOWN;
495  action_server_poses_->terminate_current(result);
496  }
497 }
498 
499 void
501 {
502  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
503 
504  auto start_time = this->now();
505 
506  // Initialize the ComputePathToPose goal and result
507  auto goal = action_server_pose_->get_current_goal();
508  auto result = std::make_shared<ActionToPose::Result>();
509  RCLCPP_INFO(get_logger(), "Computing path to goal.");
510 
511  geometry_msgs::msg::PoseStamped start;
512 
513  try {
514  if (isServerInactive<ActionToPose>(action_server_pose_) ||
515  isCancelRequested<ActionToPose>(action_server_pose_))
516  {
517  return;
518  }
519 
520  waitForCostmap();
521 
522  getPreemptedGoalIfRequested<ActionToPose>(action_server_pose_, goal);
523 
524  // Use start pose if provided otherwise use current robot pose
525  if (!getStartPose<ActionToPose>(goal, start)) {
526  throw nav2_core::PlannerTFError("Unable to get start pose");
527  }
528 
529  // Transform them into the global frame
530  geometry_msgs::msg::PoseStamped goal_pose = goal->goal;
531  if (!transformPosesToGlobalFrame(start, goal_pose)) {
532  throw nav2_core::PlannerTFError("Unable to transform poses to global frame");
533  }
534 
535  auto cancel_checker = [this]() {
536  return action_server_pose_->is_cancel_requested();
537  };
538 
539  result->path = getPlan(start, goal_pose, goal->planner_id, cancel_checker);
540 
541  if (!validatePath<ActionThroughPoses>(goal_pose, result->path, goal->planner_id)) {
542  throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
543  }
544 
545  // Publish the plan for visualization purposes
546  publishPlan(result->path);
547 
548  auto cycle_duration = this->now() - start_time;
549  result->planning_time = cycle_duration;
550 
551  if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
552  RCLCPP_WARN(
553  get_logger(),
554  "Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
555  1 / max_planner_duration_, 1 / cycle_duration.seconds());
556  }
557  action_server_pose_->succeeded_current(result);
558  } catch (nav2_core::InvalidPlanner & ex) {
559  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
560  result->error_code = ActionToPoseResult::INVALID_PLANNER;
561  action_server_pose_->terminate_current(result);
562  } catch (nav2_core::StartOccupied & ex) {
563  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
564  result->error_code = ActionToPoseResult::START_OCCUPIED;
565  action_server_pose_->terminate_current(result);
566  } catch (nav2_core::GoalOccupied & ex) {
567  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
568  result->error_code = ActionToPoseResult::GOAL_OCCUPIED;
569  action_server_pose_->terminate_current(result);
570  } catch (nav2_core::NoValidPathCouldBeFound & ex) {
571  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
572  result->error_code = ActionToPoseResult::NO_VALID_PATH;
573  action_server_pose_->terminate_current(result);
574  } catch (nav2_core::PlannerTimedOut & ex) {
575  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
576  result->error_code = ActionToPoseResult::TIMEOUT;
577  action_server_pose_->terminate_current(result);
578  } catch (nav2_core::StartOutsideMapBounds & ex) {
579  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
580  result->error_code = ActionToPoseResult::START_OUTSIDE_MAP;
581  action_server_pose_->terminate_current(result);
582  } catch (nav2_core::GoalOutsideMapBounds & ex) {
583  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
584  result->error_code = ActionToPoseResult::GOAL_OUTSIDE_MAP;
585  action_server_pose_->terminate_current(result);
586  } catch (nav2_core::PlannerTFError & ex) {
587  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
588  result->error_code = ActionToPoseResult::TF_ERROR;
589  action_server_pose_->terminate_current(result);
590  } catch (nav2_core::PlannerCancelled &) {
591  result->error_msg = "Goal was canceled. Canceling planning action.";
592  RCLCPP_INFO(get_logger(), result->error_msg.c_str());
593  action_server_pose_->terminate_all();
594  } catch (std::exception & ex) {
595  exceptionWarning(start, goal->goal, goal->planner_id, ex, result->error_msg);
596  result->error_code = ActionToPoseResult::UNKNOWN;
597  action_server_pose_->terminate_current(result);
598  }
599 }
600 
601 nav_msgs::msg::Path
603  const geometry_msgs::msg::PoseStamped & start,
604  const geometry_msgs::msg::PoseStamped & goal,
605  const std::string & planner_id,
606  std::function<bool()> cancel_checker)
607 {
608  RCLCPP_DEBUG(
609  get_logger(), "Attempting to a find path from (%.2f, %.2f) to "
610  "(%.2f, %.2f).", start.pose.position.x, start.pose.position.y,
611  goal.pose.position.x, goal.pose.position.y);
612 
613  if (planners_.find(planner_id) != planners_.end()) {
614  return planners_[planner_id]->createPlan(start, goal, cancel_checker);
615  } else {
616  if (planners_.size() == 1 && planner_id.empty()) {
617  RCLCPP_WARN_ONCE(
618  get_logger(), "No planners specified in action call. "
619  "Server will use only plugin %s in server."
620  " This warning will appear once.", planner_ids_concat_.c_str());
621  return planners_[planners_.begin()->first]->createPlan(start, goal, cancel_checker);
622  } else {
623  RCLCPP_ERROR(
624  get_logger(), "planner %s is not a valid planner. "
625  "Planner names are: %s", planner_id.c_str(),
626  planner_ids_concat_.c_str());
627  throw nav2_core::InvalidPlanner("Planner id " + planner_id + " is invalid");
628  }
629  }
630 
631  return nav_msgs::msg::Path();
632 }
633 
634 void
635 PlannerServer::publishPlan(const nav_msgs::msg::Path & path)
636 {
637  auto msg = std::make_unique<nav_msgs::msg::Path>(path);
638  if (plan_publisher_->is_activated() && plan_publisher_->get_subscription_count() > 0) {
639  plan_publisher_->publish(std::move(msg));
640  }
641 }
642 
644  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
645  const std::shared_ptr<nav2_msgs::srv::IsPathValid::Request> request,
646  std::shared_ptr<nav2_msgs::srv::IsPathValid::Response> response)
647 {
648  response->is_valid = true;
649 
650  if (request->path.poses.empty()) {
651  response->is_valid = false;
652  return;
653  }
654 
655  geometry_msgs::msg::PoseStamped current_pose;
656  unsigned int closest_point_index = 0;
657  if (costmap_ros_->getRobotPose(current_pose)) {
658  float current_distance = std::numeric_limits<float>::max();
659  float closest_distance = current_distance;
660  geometry_msgs::msg::Point current_point = current_pose.pose.position;
661  for (unsigned int i = 0; i < request->path.poses.size(); ++i) {
662  geometry_msgs::msg::Point path_point = request->path.poses[i].pose.position;
663 
664  current_distance = nav2_util::geometry_utils::euclidean_distance(
665  current_point,
666  path_point);
667 
668  if (current_distance < closest_distance) {
669  closest_point_index = i;
670  closest_distance = current_distance;
671  }
672  }
673 
679  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
680  unsigned int mx = 0;
681  unsigned int my = 0;
682 
683  bool use_radius = costmap_ros_->getUseRadius();
684 
685  unsigned int cost = nav2_costmap_2d::FREE_SPACE;
686  for (unsigned int i = closest_point_index; i < request->path.poses.size(); ++i) {
687  auto & position = request->path.poses[i].pose.position;
688  if (use_radius) {
689  if (costmap_->worldToMap(position.x, position.y, mx, my)) {
690  cost = costmap_->getCost(mx, my);
691  } else {
692  cost = nav2_costmap_2d::LETHAL_OBSTACLE;
693  }
694  } else {
695  nav2_costmap_2d::Footprint footprint = costmap_ros_->getRobotFootprint();
696  auto theta = tf2::getYaw(request->path.poses[i].pose.orientation);
697  cost = static_cast<unsigned int>(collision_checker_->footprintCostAtPose(
698  position.x, position.y, theta, footprint));
699  }
700 
701  if (cost == nav2_costmap_2d::NO_INFORMATION && request->consider_unknown_as_obstacle) {
702  cost = nav2_costmap_2d::LETHAL_OBSTACLE;
703  } else if (cost == nav2_costmap_2d::NO_INFORMATION) {
704  cost = nav2_costmap_2d::FREE_SPACE;
705  }
706 
707  if (use_radius &&
708  (cost >= request->max_cost || cost == nav2_costmap_2d::LETHAL_OBSTACLE ||
709  cost == nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE))
710  {
711  response->is_valid = false;
712  break;
713  } else if (cost == nav2_costmap_2d::LETHAL_OBSTACLE || cost >= request->max_cost) {
714  response->is_valid = false;
715  break;
716  }
717  }
718  }
719 }
720 
721 rcl_interfaces::msg::SetParametersResult
722 PlannerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
723 {
724  std::lock_guard<std::mutex> lock(dynamic_params_lock_);
725  rcl_interfaces::msg::SetParametersResult result;
726  for (auto parameter : parameters) {
727  const auto & param_type = parameter.get_type();
728  const auto & param_name = parameter.get_name();
729  if (param_name.find('.') != std::string::npos) {
730  continue;
731  }
732 
733  if (param_type == ParameterType::PARAMETER_DOUBLE) {
734  if (param_name == "expected_planner_frequency") {
735  if (parameter.as_double() > 0) {
736  max_planner_duration_ = 1 / parameter.as_double();
737  } else {
738  RCLCPP_WARN(
739  get_logger(),
740  "The expected planner frequency parameter is %.4f Hz. The value should to be greater"
741  " than 0.0 to turn on duration overrun warning messages", parameter.as_double());
742  max_planner_duration_ = 0.0;
743  }
744  }
745  }
746  }
747 
748  result.successful = true;
749  return result;
750 }
751 
752 void PlannerServer::exceptionWarning(
753  const geometry_msgs::msg::PoseStamped & start,
754  const geometry_msgs::msg::PoseStamped & goal,
755  const std::string & planner_id,
756  const std::exception & ex,
757  std::string & error_msg)
758 {
759  std::stringstream ss;
760  ss << std::fixed << std::setprecision(2)
761  << planner_id << "plugin failed to plan from ("
762  << start.pose.position.x << ", " << start.pose.position.y
763  << ") to ("
764  << goal.pose.position.x << ", " << goal.pose.position.y << ")"
765  << ": \"" << ex.what() << "\"";
766 
767  error_msg = ss.str();
768  RCLCPP_WARN(get_logger(), error_msg.c_str());
769 }
770 
771 } // namespace nav2_planner
772 
773 #include "rclcpp_components/register_node_macro.hpp"
774 
775 // Register the component with class_loader.
776 // This acts as a sort of entry point, allowing the component to be discoverable when its library
777 // is being loaded into a running process.
778 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_planner::PlannerServer)
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
bool is_cancel_requested() const
Whether or not a cancel command has come in.
void terminate_all(typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Terminate all pending and active actions.
bool is_preempt_requested() const
Whether the action server has been asked to be preempted with a new goal.
bool is_server_active()
Whether the action server is active or not.
const std::shared_ptr< const typename ActionT::Goal > accept_pending_goal()
Accept pending goals.
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...
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure member variables and initializes planner.
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.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate member variables.
bool isServerInactive(typename nav2::SimpleActionServer< T >::SharedPtr &action_server)
Check if an action server is valid / active.
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.
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.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
void computePlanThroughPoses()
The action server callback which calls planner to get the path ComputePathThroughPoses.
bool isCancelRequested(typename nav2::SimpleActionServer< T >::SharedPtr &action_server)
Check if an action server has a cancellation request pending.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Reset member variables.
void getPreemptedGoalIfRequested(typename nav2::SimpleActionServer< T >::SharedPtr &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...
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::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate 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.