Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
waypoint_follower.cpp
1 // Copyright (c) 2019 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_waypoint_follower/waypoint_follower.hpp"
16 
17 #include <fstream>
18 #include <memory>
19 #include <streambuf>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
24 namespace nav2_waypoint_follower
25 {
26 
27 using rcl_interfaces::msg::ParameterType;
28 using std::placeholders::_1;
29 
30 WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options)
31 : nav2_util::LifecycleNode("waypoint_follower", "", options),
32  waypoint_task_executor_loader_("nav2_waypoint_follower",
33  "nav2_core::WaypointTaskExecutor")
34 {
35  RCLCPP_INFO(get_logger(), "Creating");
36 
37  declare_parameter("stop_on_failure", true);
38  declare_parameter("loop_rate", 20);
39 
40  declare_parameter("global_frame_id", "map");
41 
42  nav2_util::declare_parameter_if_not_declared(
43  this, std::string("waypoint_task_executor_plugin"),
44  rclcpp::ParameterValue(std::string("wait_at_waypoint")));
45  nav2_util::declare_parameter_if_not_declared(
46  this, std::string("wait_at_waypoint.plugin"),
47  rclcpp::ParameterValue(std::string("nav2_waypoint_follower::WaitAtWaypoint")));
48 }
49 
51 {
52 }
53 
54 nav2_util::CallbackReturn
55 WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
56 {
57  RCLCPP_INFO(get_logger(), "Configuring");
58 
59  auto node = shared_from_this();
60 
61  stop_on_failure_ = get_parameter("stop_on_failure").as_bool();
62  loop_rate_ = get_parameter("loop_rate").as_int();
63  waypoint_task_executor_id_ = get_parameter("waypoint_task_executor_plugin").as_string();
64  global_frame_id_ = get_parameter("global_frame_id").as_string();
65  global_frame_id_ = nav2_util::strip_leading_slash(global_frame_id_);
66 
67  callback_group_ = create_callback_group(
68  rclcpp::CallbackGroupType::MutuallyExclusive,
69  false);
70  callback_group_executor_.add_callback_group(callback_group_, get_node_base_interface());
71 
72  nav_to_pose_client_ = rclcpp_action::create_client<ClientT>(
73  get_node_base_interface(),
74  get_node_graph_interface(),
75  get_node_logging_interface(),
76  get_node_waitables_interface(),
77  "navigate_to_pose", callback_group_);
78 
79  xyz_action_server_ = std::make_unique<ActionServer>(
80  get_node_base_interface(),
81  get_node_clock_interface(),
82  get_node_logging_interface(),
83  get_node_waitables_interface(),
84  "follow_waypoints", std::bind(
86  this), nullptr, std::chrono::milliseconds(
87  500), false);
88 
89  from_ll_to_map_client_ = std::make_unique<
90  nav2_util::ServiceClient<robot_localization::srv::FromLL,
91  std::shared_ptr<nav2_util::LifecycleNode>>>(
92  "/fromLL",
93  node,
94  true /*creates and spins an internal executor*/);
95 
96  gps_action_server_ = std::make_unique<ActionServerGPS>(
97  get_node_base_interface(),
98  get_node_clock_interface(),
99  get_node_logging_interface(),
100  get_node_waitables_interface(),
101  "follow_gps_waypoints",
102  std::bind(
104  this), nullptr, std::chrono::milliseconds(
105  500), false);
106 
107  try {
108  waypoint_task_executor_type_ = nav2_util::get_plugin_type_param(
109  this,
110  waypoint_task_executor_id_);
111  waypoint_task_executor_ = waypoint_task_executor_loader_.createUniqueInstance(
112  waypoint_task_executor_type_);
113  RCLCPP_INFO(
114  get_logger(), "Created waypoint_task_executor : %s of type %s",
115  waypoint_task_executor_id_.c_str(), waypoint_task_executor_type_.c_str());
116  waypoint_task_executor_->initialize(node, waypoint_task_executor_id_);
117  } catch (const std::exception & e) {
118  RCLCPP_FATAL(
119  get_logger(),
120  "Failed to create waypoint_task_executor. Exception: %s", e.what());
121  on_cleanup(state);
122  }
123 
124  return nav2_util::CallbackReturn::SUCCESS;
125 }
126 
127 nav2_util::CallbackReturn
128 WaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/)
129 {
130  RCLCPP_INFO(get_logger(), "Activating");
131 
132  xyz_action_server_->activate();
133  gps_action_server_->activate();
134 
135  auto node = shared_from_this();
136  // Add callback for dynamic parameters
137  dyn_params_handler_ = node->add_on_set_parameters_callback(
138  std::bind(&WaypointFollower::dynamicParametersCallback, this, _1));
139 
140  // create bond connection
141  createBond();
142 
143  return nav2_util::CallbackReturn::SUCCESS;
144 }
145 
146 nav2_util::CallbackReturn
147 WaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
148 {
149  RCLCPP_INFO(get_logger(), "Deactivating");
150 
151  xyz_action_server_->deactivate();
152  gps_action_server_->deactivate();
153  remove_on_set_parameters_callback(dyn_params_handler_.get());
154  dyn_params_handler_.reset();
155  // destroy bond connection
156  destroyBond();
157 
158  return nav2_util::CallbackReturn::SUCCESS;
159 }
160 
161 nav2_util::CallbackReturn
162 WaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
163 {
164  RCLCPP_INFO(get_logger(), "Cleaning up");
165 
166  xyz_action_server_.reset();
167  nav_to_pose_client_.reset();
168  gps_action_server_.reset();
169  from_ll_to_map_client_.reset();
170 
171  return nav2_util::CallbackReturn::SUCCESS;
172 }
173 
174 nav2_util::CallbackReturn
175 WaypointFollower::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
176 {
177  RCLCPP_INFO(get_logger(), "Shutting down");
178  return nav2_util::CallbackReturn::SUCCESS;
179 }
180 
181 template<typename T>
182 std::vector<geometry_msgs::msg::PoseStamped> WaypointFollower::getLatestGoalPoses(
183  const T & action_server)
184 {
185  std::vector<geometry_msgs::msg::PoseStamped> poses;
186  const auto current_goal = action_server->get_current_goal();
187 
188  if (!current_goal) {
189  RCLCPP_ERROR(get_logger(), "No current action goal found!");
190  return poses;
191  }
192 
193  // compile time static check to decide which block of code to be built
194  if constexpr (std::is_same<T, std::unique_ptr<ActionServer>>::value) {
195  // If normal waypoint following callback was called, we build here
196  poses = current_goal->poses;
197  } else {
198  // If GPS waypoint following callback was called, we build here
200  current_goal->gps_poses);
201  }
202  return poses;
203 }
204 
205 template<typename T, typename V, typename Z>
207  const T & action_server,
208  const V & feedback,
209  const Z & result)
210 {
211  auto goal = action_server->get_current_goal();
212 
213  // handling loops
214  unsigned int current_loop_no = 0;
215  auto no_of_loops = goal->number_of_loops;
216 
217  std::vector<geometry_msgs::msg::PoseStamped> poses;
218  poses = getLatestGoalPoses<T>(action_server);
219 
220  if (!action_server || !action_server->is_server_active()) {
221  RCLCPP_DEBUG(get_logger(), "Action server inactive. Stopping.");
222  return;
223  }
224 
225  RCLCPP_INFO(
226  get_logger(), "Received follow waypoint request with %i waypoints.",
227  static_cast<int>(poses.size()));
228 
229  if (poses.empty()) {
230  result->error_code =
231  nav2_msgs::action::FollowWaypoints::Result::NO_VALID_WAYPOINTS;
232  result->error_msg =
233  "Empty vector of waypoints passed to waypoint following "
234  "action potentially due to conversation failure or empty request.";
235  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
236  action_server->terminate_current(result);
237  return;
238  }
239 
240  rclcpp::WallRate r(loop_rate_);
241 
242  // get the goal index, by default, the first in the list of waypoints given.
243  uint32_t goal_index = goal->goal_index;
244  bool new_goal = true;
245 
246  while (rclcpp::ok()) {
247  // Check if asked to stop processing action
248  if (action_server->is_cancel_requested()) {
249  auto cancel_future = nav_to_pose_client_->async_cancel_all_goals();
250  callback_group_executor_.spin_until_future_complete(cancel_future);
251  // for result callback processing
252  callback_group_executor_.spin_some();
253  action_server->terminate_all();
254  return;
255  }
256 
257  // Check if asked to process another action
258  if (action_server->is_preempt_requested()) {
259  RCLCPP_INFO(get_logger(), "Preempting the goal pose.");
260  goal = action_server->accept_pending_goal();
261  poses = getLatestGoalPoses<T>(action_server);
262  if (poses.empty()) {
263  result->error_code =
264  nav2_msgs::action::FollowWaypoints::Result::NO_VALID_WAYPOINTS;
265  result->error_msg =
266  "Empty vector of Waypoints passed to waypoint following logic. "
267  "Nothing to execute, returning with failure!";
268  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
269  action_server->terminate_current(result);
270  return;
271  }
272  goal_index = 0;
273  new_goal = true;
274  }
275 
276  // Check if we need to send a new goal
277  if (new_goal) {
278  new_goal = false;
279  ClientT::Goal client_goal;
280  client_goal.pose = poses[goal_index];
281  client_goal.pose.header.stamp = this->now();
282 
283  auto send_goal_options = rclcpp_action::Client<ClientT>::SendGoalOptions();
284  send_goal_options.result_callback = std::bind(
286  std::placeholders::_1);
287  send_goal_options.goal_response_callback = std::bind(
289  this, std::placeholders::_1);
290 
291  future_goal_handle_ =
292  nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);
293  current_goal_status_.status = ActionStatus::PROCESSING;
294  }
295 
296  feedback->current_waypoint = goal_index;
297  action_server->publish_feedback(feedback);
298 
299  if (
300  current_goal_status_.status == ActionStatus::FAILED ||
301  current_goal_status_.status == ActionStatus::UNKNOWN)
302  {
303  nav2_msgs::msg::WaypointStatus missedWaypoint;
304  missedWaypoint.waypoint_status = nav2_msgs::msg::WaypointStatus::FAILED;
305  missedWaypoint.waypoint_index = goal_index;
306  missedWaypoint.waypoint_pose = poses[goal_index];
307  missedWaypoint.error_code = current_goal_status_.error_code;
308  missedWaypoint.error_msg = current_goal_status_.error_msg;
309  result->missed_waypoints.push_back(missedWaypoint);
310 
311  if (stop_on_failure_) {
312  result->error_code =
313  nav2_msgs::action::FollowWaypoints::Result::STOP_ON_MISSED_WAYPOINT;
314  result->error_msg =
315  "Failed to process waypoint " + std::to_string(goal_index) +
316  " in waypoint list and stop on failure is enabled."
317  " Terminating action.";
318  RCLCPP_WARN(get_logger(), result->error_msg.c_str());
319  action_server->terminate_current(result);
320  current_goal_status_.error_code = 0;
321  current_goal_status_.error_msg = "";
322  return;
323  } else {
324  RCLCPP_INFO(
325  get_logger(), "Failed to process waypoint %i,"
326  " moving to next.", goal_index);
327  }
328  } else if (current_goal_status_.status == ActionStatus::SUCCEEDED) {
329  RCLCPP_INFO(
330  get_logger(), "Succeeded processing waypoint %i, processing waypoint task execution",
331  goal_index);
332  bool is_task_executed = waypoint_task_executor_->processAtWaypoint(
333  poses[goal_index], goal_index);
334  RCLCPP_INFO(
335  get_logger(), "Task execution at waypoint %i %s", goal_index,
336  is_task_executed ? "succeeded" : "failed!");
337 
338  if (!is_task_executed) {
339  nav2_msgs::msg::WaypointStatus missedWaypoint;
340  missedWaypoint.waypoint_status = nav2_msgs::msg::WaypointStatus::FAILED;
341  missedWaypoint.waypoint_index = goal_index;
342  missedWaypoint.waypoint_pose = poses[goal_index];
343  missedWaypoint.error_code =
344  nav2_msgs::action::FollowWaypoints::Result::TASK_EXECUTOR_FAILED;
345  missedWaypoint.error_msg = "Task execution failed";
346  result->missed_waypoints.push_back(missedWaypoint);
347  }
348  // if task execution was failed and stop_on_failure_ is on , terminate action
349  if (!is_task_executed && stop_on_failure_) {
350  result->error_code =
351  nav2_msgs::action::FollowWaypoints::Result::TASK_EXECUTOR_FAILED;
352  result->error_msg =
353  "Failed to execute task at waypoint " + std::to_string(goal_index) +
354  " stop on failure is enabled. Terminating action.";
355  RCLCPP_WARN(get_logger(), result->error_msg.c_str());
356  action_server->terminate_current(result);
357  current_goal_status_.error_code = 0;
358  current_goal_status_.error_msg = "";
359  return;
360  } else {
361  RCLCPP_INFO(
362  get_logger(), "Handled task execution on waypoint %i,"
363  " moving to next.", goal_index);
364  }
365  }
366 
367  if (current_goal_status_.status != ActionStatus::PROCESSING) {
368  // Update server state
369  goal_index++;
370  new_goal = true;
371  if (goal_index >= poses.size()) {
372  if (current_loop_no == no_of_loops) {
373  RCLCPP_INFO(
374  get_logger(), "Completed all %zu waypoints requested.",
375  poses.size());
376  action_server->succeeded_current(result);
377  current_goal_status_.error_code = 0;
378  current_goal_status_.error_msg = "";
379  return;
380  }
381  RCLCPP_INFO(
382  get_logger(), "Starting a new loop, current loop count is %i",
383  current_loop_no);
384  goal_index = 0;
385  current_loop_no++;
386  }
387  }
388 
389  callback_group_executor_.spin_some();
390  r.sleep();
391  }
392 }
393 
395 {
396  auto feedback = std::make_shared<ActionT::Feedback>();
397  auto result = std::make_shared<ActionT::Result>();
398 
399  followWaypointsHandler<std::unique_ptr<ActionServer>,
400  ActionT::Feedback::SharedPtr,
401  ActionT::Result::SharedPtr>(
402  xyz_action_server_,
403  feedback, result);
404 }
405 
407 {
408  auto feedback = std::make_shared<ActionTGPS::Feedback>();
409  auto result = std::make_shared<ActionTGPS::Result>();
410 
411  followWaypointsHandler<std::unique_ptr<ActionServerGPS>,
412  ActionTGPS::Feedback::SharedPtr,
413  ActionTGPS::Result::SharedPtr>(
414  gps_action_server_,
415  feedback, result);
416 }
417 
418 void
420  const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result)
421 {
422  if (result.goal_id != future_goal_handle_.get()->get_goal_id()) {
423  RCLCPP_DEBUG(
424  get_logger(),
425  "Goal IDs do not match for the current goal handle and received result."
426  "Ignoring likely due to receiving result for an old goal.");
427  return;
428  }
429 
430  switch (result.code) {
431  case rclcpp_action::ResultCode::SUCCEEDED:
432  current_goal_status_.status = ActionStatus::SUCCEEDED;
433  return;
434  case rclcpp_action::ResultCode::ABORTED:
435  current_goal_status_.status = ActionStatus::FAILED;
436  current_goal_status_.error_code = result.result->error_code;
437  current_goal_status_.error_msg = result.result->error_msg;
438  return;
439  case rclcpp_action::ResultCode::CANCELED:
440  current_goal_status_.status = ActionStatus::FAILED;
441  return;
442  default:
443  current_goal_status_.status = ActionStatus::UNKNOWN;
444  current_goal_status_.error_code = nav2_msgs::action::FollowWaypoints::Result::UNKNOWN;
445  current_goal_status_.error_msg = "Received an UNKNOWN result code from navigation action!";
446  RCLCPP_ERROR(get_logger(), current_goal_status_.error_msg.c_str());
447  return;
448  }
449 }
450 
451 void
453  const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal)
454 {
455  if (!goal) {
456  current_goal_status_.status = ActionStatus::FAILED;
457  current_goal_status_.error_code = nav2_msgs::action::FollowWaypoints::Result::UNKNOWN;
458  current_goal_status_.error_msg =
459  "navigate_to_pose action client failed to send goal to server.";
460  RCLCPP_ERROR(get_logger(), current_goal_status_.error_msg.c_str());
461  }
462 }
463 
464 rcl_interfaces::msg::SetParametersResult
465 WaypointFollower::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
466 {
467  // No locking required as action server is running on same single threaded executor
468  rcl_interfaces::msg::SetParametersResult result;
469 
470  for (auto parameter : parameters) {
471  const auto & param_type = parameter.get_type();
472  const auto & param_name = parameter.get_name();
473  if (param_name.find('.') != std::string::npos) {
474  continue;
475  }
476 
477  if (param_type == ParameterType::PARAMETER_INTEGER) {
478  if (param_name == "loop_rate") {
479  loop_rate_ = parameter.as_int();
480  }
481  } else if (param_type == ParameterType::PARAMETER_BOOL) {
482  if (param_name == "stop_on_failure") {
483  stop_on_failure_ = parameter.as_bool();
484  }
485  }
486  }
487 
488  result.successful = true;
489  return result;
490 }
491 
492 std::vector<geometry_msgs::msg::PoseStamped>
494  const std::vector<geographic_msgs::msg::GeoPose> & gps_poses)
495 {
496  RCLCPP_INFO(
497  this->get_logger(), "Converting GPS waypoints to %s Frame..",
498  global_frame_id_.c_str());
499 
500  std::vector<geometry_msgs::msg::PoseStamped> poses_in_map_frame_vector;
501  int waypoint_index = 0;
502  for (auto && curr_geopose : gps_poses) {
503  auto request = std::make_shared<robot_localization::srv::FromLL::Request>();
504  auto response = std::make_shared<robot_localization::srv::FromLL::Response>();
505  request->ll_point.latitude = curr_geopose.position.latitude;
506  request->ll_point.longitude = curr_geopose.position.longitude;
507  request->ll_point.altitude = curr_geopose.position.altitude;
508 
509  from_ll_to_map_client_->wait_for_service((std::chrono::seconds(1)));
510  if (!from_ll_to_map_client_->invoke(request, response)) {
511  RCLCPP_ERROR(
512  this->get_logger(),
513  "fromLL service of robot_localization could not convert %i th GPS waypoint to"
514  "%s frame, going to skip this point!"
515  "Make sure you have run navsat_transform_node of robot_localization",
516  waypoint_index, global_frame_id_.c_str());
517  if (stop_on_failure_) {
518  RCLCPP_ERROR(
519  this->get_logger(),
520  "Conversion of %i th GPS waypoint to"
521  "%s frame failed and stop_on_failure is set to true"
522  "Not going to execute any of waypoints, exiting with failure!",
523  waypoint_index, global_frame_id_.c_str());
524  return std::vector<geometry_msgs::msg::PoseStamped>();
525  }
526  continue;
527  } else {
528  geometry_msgs::msg::PoseStamped curr_pose_map_frame;
529  curr_pose_map_frame.header.frame_id = global_frame_id_;
530  curr_pose_map_frame.header.stamp = this->now();
531  curr_pose_map_frame.pose.position = response->map_point;
532  curr_pose_map_frame.pose.orientation = curr_geopose.orientation;
533  poses_in_map_frame_vector.push_back(curr_pose_map_frame);
534  }
535  waypoint_index++;
536  }
537  RCLCPP_INFO(
538  this->get_logger(),
539  "Converted all %i GPS waypoint to %s frame",
540  static_cast<int>(poses_in_map_frame_vector.size()), global_frame_id_.c_str());
541  return poses_in_map_frame_vector;
542 }
543 
544 } // namespace nav2_waypoint_follower
545 
546 #include "rclcpp_components/register_node_macro.hpp"
547 
548 // Register the component with class_loader.
549 // This acts as a sort of entry point, allowing the component to be discoverable when its library
550 // is being loaded into a running process.
551 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_waypoint_follower::WaypointFollower)
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 client.
An action server that uses behavior tree for navigating a robot to its goal position.
void resultCallback(const rclcpp_action::ClientGoalHandle< ClientT >::WrappedResult &result)
Action client result callback.
~WaypointFollower()
A destructor for nav2_waypoint_follower::WaypointFollower class.
WaypointFollower(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_waypoint_follower::WaypointFollower class.
void goalResponseCallback(const rclcpp_action::ClientGoalHandle< ClientT >::SharedPtr &goal)
Action client goal response callback.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures member variables.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets member variables.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates action server.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates action server.
void followGPSWaypointsCallback()
send robot through each of GPS point , which are converted to map frame first then using a client to ...
std::vector< geometry_msgs::msg::PoseStamped > convertGPSPosesToMapPoses(const std::vector< geographic_msgs::msg::GeoPose > &gps_poses)
given some gps_poses, converts them to map frame using robot_localization's service fromLL....
void followWaypointsHandler(const T &action_server, const V &feedback, const Z &result)
Templated function to perform internal logic behind waypoint following, Both GPS and non GPS waypoint...
void followWaypointsCallback()
Action server callbacks.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
std::vector< geometry_msgs::msg::PoseStamped > getLatestGoalPoses(const T &action_server)
get the latest poses on the action server goal. If they are GPS poses, convert them to the global car...