Nav2 Navigation Stack - rolling  main
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::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::declare_parameter_if_not_declared(
43  this, std::string("waypoint_task_executor_plugin"),
44  rclcpp::ParameterValue(std::string("wait_at_waypoint")));
45  nav2::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::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 
66  callback_group_ = create_callback_group(
67  rclcpp::CallbackGroupType::MutuallyExclusive,
68  false);
69  callback_group_executor_.add_callback_group(callback_group_, get_node_base_interface());
70 
71  nav_to_pose_client_ = create_action_client<ClientT>(
72  "navigate_to_pose", callback_group_);
73 
74  xyz_action_server_ = create_action_server<ActionT>(
75  "follow_waypoints", std::bind(
77  this), nullptr, std::chrono::milliseconds(
78  500), false);
79 
80  from_ll_to_map_client_ = node->create_client<robot_localization::srv::FromLL>(
81  "/fromLL",
82  true /*creates and spins an internal executor*/);
83 
84  gps_action_server_ = create_action_server<ActionTGPS>(
85  "follow_gps_waypoints",
86  std::bind(
88  this), nullptr, std::chrono::milliseconds(
89  500), false);
90 
91  try {
92  waypoint_task_executor_type_ = nav2::get_plugin_type_param(
93  this,
94  waypoint_task_executor_id_);
95  waypoint_task_executor_ = waypoint_task_executor_loader_.createUniqueInstance(
96  waypoint_task_executor_type_);
97  RCLCPP_INFO(
98  get_logger(), "Created waypoint_task_executor : %s of type %s",
99  waypoint_task_executor_id_.c_str(), waypoint_task_executor_type_.c_str());
100  waypoint_task_executor_->initialize(node, waypoint_task_executor_id_);
101  } catch (const std::exception & e) {
102  RCLCPP_FATAL(
103  get_logger(),
104  "Failed to create waypoint_task_executor. Exception: %s", e.what());
105  on_cleanup(state);
106  }
107 
108  return nav2::CallbackReturn::SUCCESS;
109 }
110 
111 nav2::CallbackReturn
112 WaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/)
113 {
114  RCLCPP_INFO(get_logger(), "Activating");
115 
116  xyz_action_server_->activate();
117  gps_action_server_->activate();
118 
119  auto node = shared_from_this();
120  // Add callback for dynamic parameters
121  dyn_params_handler_ = node->add_on_set_parameters_callback(
122  std::bind(&WaypointFollower::dynamicParametersCallback, this, _1));
123 
124  // create bond connection
125  createBond();
126 
127  return nav2::CallbackReturn::SUCCESS;
128 }
129 
130 nav2::CallbackReturn
131 WaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
132 {
133  RCLCPP_INFO(get_logger(), "Deactivating");
134 
135  xyz_action_server_->deactivate();
136  gps_action_server_->deactivate();
137  remove_on_set_parameters_callback(dyn_params_handler_.get());
138  dyn_params_handler_.reset();
139  // destroy bond connection
140  destroyBond();
141 
142  return nav2::CallbackReturn::SUCCESS;
143 }
144 
145 nav2::CallbackReturn
146 WaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
147 {
148  RCLCPP_INFO(get_logger(), "Cleaning up");
149 
150  xyz_action_server_.reset();
151  nav_to_pose_client_.reset();
152  gps_action_server_.reset();
153  from_ll_to_map_client_.reset();
154 
155  return nav2::CallbackReturn::SUCCESS;
156 }
157 
158 nav2::CallbackReturn
159 WaypointFollower::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
160 {
161  RCLCPP_INFO(get_logger(), "Shutting down");
162  return nav2::CallbackReturn::SUCCESS;
163 }
164 
165 template<typename T>
166 std::vector<geometry_msgs::msg::PoseStamped> WaypointFollower::getLatestGoalPoses(
167  const T & action_server)
168 {
169  std::vector<geometry_msgs::msg::PoseStamped> poses;
170  const auto current_goal = action_server->get_current_goal();
171 
172  if (!current_goal) {
173  RCLCPP_ERROR(get_logger(), "No current action goal found!");
174  return poses;
175  }
176 
177  // compile time static check to decide which block of code to be built
178  if constexpr (std::is_same<T, ActionServer::SharedPtr>::value) {
179  // If normal waypoint following callback was called, we build here
180  poses = current_goal->poses;
181  } else {
182  // If GPS waypoint following callback was called, we build here
184  current_goal->gps_poses);
185  }
186  return poses;
187 }
188 
189 template<typename T, typename V, typename Z>
191  const T & action_server,
192  const V & feedback,
193  const Z & result)
194 {
195  auto goal = action_server->get_current_goal();
196 
197  // handling loops
198  unsigned int current_loop_no = 0;
199  auto no_of_loops = goal->number_of_loops;
200 
201  std::vector<geometry_msgs::msg::PoseStamped> poses;
202  poses = getLatestGoalPoses<T>(action_server);
203 
204  if (!action_server || !action_server->is_server_active()) {
205  RCLCPP_DEBUG(get_logger(), "Action server inactive. Stopping.");
206  return;
207  }
208 
209  RCLCPP_INFO(
210  get_logger(), "Received follow waypoint request with %i waypoints.",
211  static_cast<int>(poses.size()));
212 
213  if (poses.empty()) {
214  result->error_code =
215  nav2_msgs::action::FollowWaypoints::Result::NO_VALID_WAYPOINTS;
216  result->error_msg =
217  "Empty vector of waypoints passed to waypoint following "
218  "action potentially due to conversation failure or empty request.";
219  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
220  action_server->terminate_current(result);
221  return;
222  }
223 
224  rclcpp::WallRate r(loop_rate_);
225 
226  // get the goal index, by default, the first in the list of waypoints given.
227  uint32_t goal_index = goal->goal_index;
228  bool new_goal = true;
229 
230  while (rclcpp::ok()) {
231  // Check if asked to stop processing action
232  if (action_server->is_cancel_requested()) {
233  auto cancel_future = nav_to_pose_client_->async_cancel_all_goals();
234  callback_group_executor_.spin_until_future_complete(cancel_future);
235  // for result callback processing
236  callback_group_executor_.spin_some();
237  action_server->terminate_all();
238  return;
239  }
240 
241  // Check if asked to process another action
242  if (action_server->is_preempt_requested()) {
243  RCLCPP_INFO(get_logger(), "Preempting the goal pose.");
244  goal = action_server->accept_pending_goal();
245  poses = getLatestGoalPoses<T>(action_server);
246  if (poses.empty()) {
247  result->error_code =
248  nav2_msgs::action::FollowWaypoints::Result::NO_VALID_WAYPOINTS;
249  result->error_msg =
250  "Empty vector of Waypoints passed to waypoint following logic. "
251  "Nothing to execute, returning with failure!";
252  RCLCPP_ERROR(get_logger(), result->error_msg.c_str());
253  action_server->terminate_current(result);
254  return;
255  }
256  goal_index = 0;
257  new_goal = true;
258  }
259 
260  // Check if we need to send a new goal
261  if (new_goal) {
262  new_goal = false;
263  ClientT::Goal client_goal;
264  client_goal.pose = poses[goal_index];
265  client_goal.pose.header.stamp = this->now();
266 
267  auto send_goal_options = nav2::ActionClient<ClientT>::SendGoalOptions();
268  send_goal_options.result_callback = std::bind(
270  std::placeholders::_1);
271  send_goal_options.goal_response_callback = std::bind(
273  this, std::placeholders::_1);
274 
275  future_goal_handle_ =
276  nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);
277  current_goal_status_.status = ActionStatus::PROCESSING;
278  }
279 
280  feedback->current_waypoint = goal_index;
281  action_server->publish_feedback(feedback);
282 
283  if (
284  current_goal_status_.status == ActionStatus::FAILED ||
285  current_goal_status_.status == ActionStatus::UNKNOWN)
286  {
287  nav2_msgs::msg::WaypointStatus missedWaypoint;
288  missedWaypoint.waypoint_status = nav2_msgs::msg::WaypointStatus::FAILED;
289  missedWaypoint.waypoint_index = goal_index;
290  missedWaypoint.waypoint_pose = poses[goal_index];
291  missedWaypoint.error_code = current_goal_status_.error_code;
292  missedWaypoint.error_msg = current_goal_status_.error_msg;
293  result->missed_waypoints.push_back(missedWaypoint);
294 
295  if (stop_on_failure_) {
296  result->error_code =
297  nav2_msgs::action::FollowWaypoints::Result::STOP_ON_MISSED_WAYPOINT;
298  result->error_msg =
299  "Failed to process waypoint " + std::to_string(goal_index) +
300  " in waypoint list and stop on failure is enabled."
301  " Terminating action.";
302  RCLCPP_WARN(get_logger(), result->error_msg.c_str());
303  action_server->terminate_current(result);
304  current_goal_status_.error_code = 0;
305  current_goal_status_.error_msg = "";
306  return;
307  } else {
308  RCLCPP_INFO(
309  get_logger(), "Failed to process waypoint %i,"
310  " moving to next.", goal_index);
311  }
312  } else if (current_goal_status_.status == ActionStatus::SUCCEEDED) {
313  RCLCPP_INFO(
314  get_logger(), "Succeeded processing waypoint %i, processing waypoint task execution",
315  goal_index);
316  bool is_task_executed = waypoint_task_executor_->processAtWaypoint(
317  poses[goal_index], goal_index);
318  RCLCPP_INFO(
319  get_logger(), "Task execution at waypoint %i %s", goal_index,
320  is_task_executed ? "succeeded" : "failed!");
321 
322  if (!is_task_executed) {
323  nav2_msgs::msg::WaypointStatus missedWaypoint;
324  missedWaypoint.waypoint_status = nav2_msgs::msg::WaypointStatus::FAILED;
325  missedWaypoint.waypoint_index = goal_index;
326  missedWaypoint.waypoint_pose = poses[goal_index];
327  missedWaypoint.error_code =
328  nav2_msgs::action::FollowWaypoints::Result::TASK_EXECUTOR_FAILED;
329  missedWaypoint.error_msg = "Task execution failed";
330  result->missed_waypoints.push_back(missedWaypoint);
331  }
332  // if task execution was failed and stop_on_failure_ is on , terminate action
333  if (!is_task_executed && stop_on_failure_) {
334  result->error_code =
335  nav2_msgs::action::FollowWaypoints::Result::TASK_EXECUTOR_FAILED;
336  result->error_msg =
337  "Failed to execute task at waypoint " + std::to_string(goal_index) +
338  " stop on failure is enabled. Terminating action.";
339  RCLCPP_WARN(get_logger(), result->error_msg.c_str());
340  action_server->terminate_current(result);
341  current_goal_status_.error_code = 0;
342  current_goal_status_.error_msg = "";
343  return;
344  } else {
345  RCLCPP_INFO(
346  get_logger(), "Handled task execution on waypoint %i,"
347  " moving to next.", goal_index);
348  }
349  }
350 
351  if (current_goal_status_.status != ActionStatus::PROCESSING) {
352  // Update server state
353  goal_index++;
354  new_goal = true;
355  if (goal_index >= poses.size()) {
356  if (current_loop_no == no_of_loops) {
357  RCLCPP_INFO(
358  get_logger(), "Completed all %zu waypoints requested.",
359  poses.size());
360  action_server->succeeded_current(result);
361  current_goal_status_.error_code = 0;
362  current_goal_status_.error_msg = "";
363  return;
364  }
365  RCLCPP_INFO(
366  get_logger(), "Starting a new loop, current loop count is %i",
367  current_loop_no);
368  goal_index = 0;
369  current_loop_no++;
370  }
371  }
372 
373  callback_group_executor_.spin_some();
374  r.sleep();
375  }
376 }
377 
379 {
380  auto feedback = std::make_shared<ActionT::Feedback>();
381  auto result = std::make_shared<ActionT::Result>();
382 
383  followWaypointsHandler<typename ActionServer::SharedPtr,
384  ActionT::Feedback::SharedPtr,
385  ActionT::Result::SharedPtr>(
386  xyz_action_server_,
387  feedback, result);
388 }
389 
391 {
392  auto feedback = std::make_shared<ActionTGPS::Feedback>();
393  auto result = std::make_shared<ActionTGPS::Result>();
394 
395  followWaypointsHandler<typename ActionServerGPS::SharedPtr,
396  ActionTGPS::Feedback::SharedPtr,
397  ActionTGPS::Result::SharedPtr>(
398  gps_action_server_,
399  feedback, result);
400 }
401 
402 void
404  const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result)
405 {
406  if (result.goal_id != future_goal_handle_.get()->get_goal_id()) {
407  RCLCPP_DEBUG(
408  get_logger(),
409  "Goal IDs do not match for the current goal handle and received result."
410  "Ignoring likely due to receiving result for an old goal.");
411  return;
412  }
413 
414  switch (result.code) {
415  case rclcpp_action::ResultCode::SUCCEEDED:
416  current_goal_status_.status = ActionStatus::SUCCEEDED;
417  return;
418  case rclcpp_action::ResultCode::ABORTED:
419  current_goal_status_.status = ActionStatus::FAILED;
420  current_goal_status_.error_code = result.result->error_code;
421  current_goal_status_.error_msg = result.result->error_msg;
422  return;
423  case rclcpp_action::ResultCode::CANCELED:
424  current_goal_status_.status = ActionStatus::FAILED;
425  return;
426  default:
427  current_goal_status_.status = ActionStatus::UNKNOWN;
428  current_goal_status_.error_code = nav2_msgs::action::FollowWaypoints::Result::UNKNOWN;
429  current_goal_status_.error_msg = "Received an UNKNOWN result code from navigation action!";
430  RCLCPP_ERROR(get_logger(), current_goal_status_.error_msg.c_str());
431  return;
432  }
433 }
434 
435 void
437  const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal)
438 {
439  if (!goal) {
440  current_goal_status_.status = ActionStatus::FAILED;
441  current_goal_status_.error_code = nav2_msgs::action::FollowWaypoints::Result::UNKNOWN;
442  current_goal_status_.error_msg =
443  "navigate_to_pose action client failed to send goal to server.";
444  RCLCPP_ERROR(get_logger(), current_goal_status_.error_msg.c_str());
445  }
446 }
447 
448 rcl_interfaces::msg::SetParametersResult
449 WaypointFollower::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
450 {
451  // No locking required as action server is running on same single threaded executor
452  rcl_interfaces::msg::SetParametersResult result;
453 
454  for (auto parameter : parameters) {
455  const auto & param_type = parameter.get_type();
456  const auto & param_name = parameter.get_name();
457  if (param_name.find('.') != std::string::npos) {
458  continue;
459  }
460 
461  if (param_type == ParameterType::PARAMETER_INTEGER) {
462  if (param_name == "loop_rate") {
463  loop_rate_ = parameter.as_int();
464  }
465  } else if (param_type == ParameterType::PARAMETER_BOOL) {
466  if (param_name == "stop_on_failure") {
467  stop_on_failure_ = parameter.as_bool();
468  }
469  }
470  }
471 
472  result.successful = true;
473  return result;
474 }
475 
476 std::vector<geometry_msgs::msg::PoseStamped>
478  const std::vector<geographic_msgs::msg::GeoPose> & gps_poses)
479 {
480  RCLCPP_INFO(
481  this->get_logger(), "Converting GPS waypoints to %s Frame..",
482  global_frame_id_.c_str());
483 
484  std::vector<geometry_msgs::msg::PoseStamped> poses_in_map_frame_vector;
485  int waypoint_index = 0;
486  for (auto && curr_geopose : gps_poses) {
487  auto request = std::make_shared<robot_localization::srv::FromLL::Request>();
488  auto response = std::make_shared<robot_localization::srv::FromLL::Response>();
489  request->ll_point.latitude = curr_geopose.position.latitude;
490  request->ll_point.longitude = curr_geopose.position.longitude;
491  request->ll_point.altitude = curr_geopose.position.altitude;
492 
493  from_ll_to_map_client_->wait_for_service((std::chrono::seconds(1)));
494  if (!from_ll_to_map_client_->invoke(request, response)) {
495  RCLCPP_ERROR(
496  this->get_logger(),
497  "fromLL service of robot_localization could not convert %i th GPS waypoint to"
498  "%s frame, going to skip this point!"
499  "Make sure you have run navsat_transform_node of robot_localization",
500  waypoint_index, global_frame_id_.c_str());
501  if (stop_on_failure_) {
502  RCLCPP_ERROR(
503  this->get_logger(),
504  "Conversion of %i th GPS waypoint to"
505  "%s frame failed and stop_on_failure is set to true"
506  "Not going to execute any of waypoints, exiting with failure!",
507  waypoint_index, global_frame_id_.c_str());
508  return std::vector<geometry_msgs::msg::PoseStamped>();
509  }
510  continue;
511  } else {
512  geometry_msgs::msg::PoseStamped curr_pose_map_frame;
513  curr_pose_map_frame.header.frame_id = global_frame_id_;
514  curr_pose_map_frame.header.stamp = this->now();
515  curr_pose_map_frame.pose.position = response->map_point;
516  curr_pose_map_frame.pose.orientation = curr_geopose.orientation;
517  poses_in_map_frame_vector.push_back(curr_pose_map_frame);
518  }
519  waypoint_index++;
520  }
521  RCLCPP_INFO(
522  this->get_logger(),
523  "Converted all %i GPS waypoint to %s frame",
524  static_cast<int>(poses_in_map_frame_vector.size()), global_frame_id_.c_str());
525  return poses_in_map_frame_vector;
526 }
527 
528 } // namespace nav2_waypoint_follower
529 
530 #include "rclcpp_components/register_node_macro.hpp"
531 
532 // Register the component with class_loader.
533 // This acts as a sort of entry point, allowing the component to be discoverable when its library
534 // is being loaded into a running process.
535 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_waypoint_follower::WaypointFollower)
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.
ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1), const std::chrono::nanoseconds wait_for_service_timeout=std::chrono::seconds(10))
Invoke the service and block until completed or timed out.
bool wait_for_service(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::max())
Block until a service is available or timeout.
An action server that uses behavior tree for navigating a robot to its goal position.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates action server.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
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::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets member variables.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures member variables.
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...
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates action server.