15 #include "nav2_waypoint_follower/waypoint_follower.hpp"
24 namespace nav2_waypoint_follower
27 using rcl_interfaces::msg::ParameterType;
28 using std::placeholders::_1;
31 : nav2_util::LifecycleNode(
"waypoint_follower",
"", options),
32 waypoint_task_executor_loader_(
"nav2_waypoint_follower",
33 "nav2_core::WaypointTaskExecutor")
35 RCLCPP_INFO(get_logger(),
"Creating");
37 declare_parameter(
"stop_on_failure",
true);
38 declare_parameter(
"loop_rate", 20);
40 declare_parameter(
"action_server_result_timeout", 900.0);
42 declare_parameter(
"global_frame_id",
"map");
44 nav2_util::declare_parameter_if_not_declared(
45 this, std::string(
"waypoint_task_executor_plugin"),
46 rclcpp::ParameterValue(std::string(
"wait_at_waypoint")));
47 nav2_util::declare_parameter_if_not_declared(
48 this, std::string(
"wait_at_waypoint.plugin"),
49 rclcpp::ParameterValue(std::string(
"nav2_waypoint_follower::WaitAtWaypoint")));
56 nav2_util::CallbackReturn
59 RCLCPP_INFO(get_logger(),
"Configuring");
63 stop_on_failure_ = get_parameter(
"stop_on_failure").as_bool();
64 loop_rate_ = get_parameter(
"loop_rate").as_int();
65 waypoint_task_executor_id_ = get_parameter(
"waypoint_task_executor_plugin").as_string();
66 global_frame_id_ = get_parameter(
"global_frame_id").as_string();
67 global_frame_id_ = nav2_util::strip_leading_slash(global_frame_id_);
69 callback_group_ = create_callback_group(
70 rclcpp::CallbackGroupType::MutuallyExclusive,
72 callback_group_executor_.add_callback_group(callback_group_, get_node_base_interface());
74 nav_to_pose_client_ = rclcpp_action::create_client<ClientT>(
75 get_node_base_interface(),
76 get_node_graph_interface(),
77 get_node_logging_interface(),
78 get_node_waitables_interface(),
79 "navigate_to_pose", callback_group_);
81 double action_server_result_timeout = get_parameter(
"action_server_result_timeout").as_double();
82 rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
83 server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
85 xyz_action_server_ = std::make_unique<ActionServer>(
86 get_node_base_interface(),
87 get_node_clock_interface(),
88 get_node_logging_interface(),
89 get_node_waitables_interface(),
90 "follow_waypoints", std::bind(
92 this),
nullptr, std::chrono::milliseconds(
93 500),
false, server_options);
95 from_ll_to_map_client_ = std::make_unique<
97 std::shared_ptr<nav2_util::LifecycleNode>>>(
101 gps_action_server_ = std::make_unique<ActionServerGPS>(
102 get_node_base_interface(),
103 get_node_clock_interface(),
104 get_node_logging_interface(),
105 get_node_waitables_interface(),
106 "follow_gps_waypoints",
109 this),
nullptr, std::chrono::milliseconds(
110 500),
false, server_options);
113 waypoint_task_executor_type_ = nav2_util::get_plugin_type_param(
115 waypoint_task_executor_id_);
116 waypoint_task_executor_ = waypoint_task_executor_loader_.createUniqueInstance(
117 waypoint_task_executor_type_);
119 get_logger(),
"Created waypoint_task_executor : %s of type %s",
120 waypoint_task_executor_id_.c_str(), waypoint_task_executor_type_.c_str());
121 waypoint_task_executor_->initialize(node, waypoint_task_executor_id_);
122 }
catch (
const std::exception & e) {
125 "Failed to create waypoint_task_executor. Exception: %s", e.what());
129 return nav2_util::CallbackReturn::SUCCESS;
132 nav2_util::CallbackReturn
135 RCLCPP_INFO(get_logger(),
"Activating");
137 xyz_action_server_->activate();
138 gps_action_server_->activate();
142 dyn_params_handler_ = node->add_on_set_parameters_callback(
148 return nav2_util::CallbackReturn::SUCCESS;
151 nav2_util::CallbackReturn
154 RCLCPP_INFO(get_logger(),
"Deactivating");
156 xyz_action_server_->deactivate();
157 gps_action_server_->deactivate();
158 remove_on_set_parameters_callback(dyn_params_handler_.get());
159 dyn_params_handler_.reset();
163 return nav2_util::CallbackReturn::SUCCESS;
166 nav2_util::CallbackReturn
169 RCLCPP_INFO(get_logger(),
"Cleaning up");
171 xyz_action_server_.reset();
172 nav_to_pose_client_.reset();
173 gps_action_server_.reset();
174 from_ll_to_map_client_.reset();
176 return nav2_util::CallbackReturn::SUCCESS;
179 nav2_util::CallbackReturn
182 RCLCPP_INFO(get_logger(),
"Shutting down");
183 return nav2_util::CallbackReturn::SUCCESS;
188 const T & action_server)
190 std::vector<geometry_msgs::msg::PoseStamped> poses;
191 const auto current_goal = action_server->get_current_goal();
194 RCLCPP_ERROR(get_logger(),
"No current action goal found!");
199 if constexpr (std::is_same<T, std::unique_ptr<ActionServer>>::value) {
201 poses = current_goal->poses;
205 current_goal->gps_poses);
210 template<
typename T,
typename V,
typename Z>
212 const T & action_server,
216 auto goal = action_server->get_current_goal();
219 unsigned int current_loop_no = 0;
220 auto no_of_loops = goal->number_of_loops;
222 std::vector<geometry_msgs::msg::PoseStamped> poses;
223 poses = getLatestGoalPoses<T>(action_server);
225 if (!action_server || !action_server->is_server_active()) {
226 RCLCPP_DEBUG(get_logger(),
"Action server inactive. Stopping.");
231 get_logger(),
"Received follow waypoint request with %i waypoints.",
232 static_cast<int>(poses.size()));
237 "Empty vector of waypoints passed to waypoint following "
238 "action potentially due to conversation failure or empty request."
240 action_server->terminate_current(result);
244 rclcpp::WallRate r(loop_rate_);
247 uint32_t goal_index = goal->goal_index;
248 bool new_goal =
true;
250 while (rclcpp::ok()) {
252 if (action_server->is_cancel_requested()) {
253 auto cancel_future = nav_to_pose_client_->async_cancel_all_goals();
254 callback_group_executor_.spin_until_future_complete(cancel_future);
256 callback_group_executor_.spin_some();
257 action_server->terminate_all();
262 if (action_server->is_preempt_requested()) {
263 RCLCPP_INFO(get_logger(),
"Preempting the goal pose.");
264 goal = action_server->accept_pending_goal();
265 poses = getLatestGoalPoses<T>(action_server);
269 "Empty vector of Waypoints passed to waypoint following logic. "
270 "Nothing to execute, returning with failure!");
271 action_server->terminate_current(result);
281 ClientT::Goal client_goal;
282 client_goal.pose = poses[goal_index];
283 client_goal.pose.header.stamp = this->now();
285 auto send_goal_options = rclcpp_action::Client<ClientT>::SendGoalOptions();
286 send_goal_options.result_callback = std::bind(
288 std::placeholders::_1);
289 send_goal_options.goal_response_callback = std::bind(
291 this, std::placeholders::_1);
293 future_goal_handle_ =
294 nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);
295 current_goal_status_.status = ActionStatus::PROCESSING;
298 feedback->current_waypoint = goal_index;
299 action_server->publish_feedback(feedback);
302 current_goal_status_.status == ActionStatus::FAILED ||
303 current_goal_status_.status == ActionStatus::UNKNOWN)
305 nav2_msgs::msg::MissedWaypoint missedWaypoint;
306 missedWaypoint.index = goal_index;
307 missedWaypoint.goal = poses[goal_index];
308 missedWaypoint.error_code = current_goal_status_.error_code;
309 result->missed_waypoints.push_back(missedWaypoint);
311 if (stop_on_failure_) {
313 get_logger(),
"Failed to process waypoint %i in waypoint "
314 "list and stop on failure is enabled."
315 " Terminating action.", goal_index);
316 action_server->terminate_current(result);
317 current_goal_status_.error_code = 0;
321 get_logger(),
"Failed to process waypoint %i,"
322 " moving to next.", goal_index);
324 }
else if (current_goal_status_.status == ActionStatus::SUCCEEDED) {
326 get_logger(),
"Succeeded processing waypoint %i, processing waypoint task execution",
328 bool is_task_executed = waypoint_task_executor_->processAtWaypoint(
329 poses[goal_index], goal_index);
331 get_logger(),
"Task execution at waypoint %i %s", goal_index,
332 is_task_executed ?
"succeeded" :
"failed!");
334 if (!is_task_executed) {
335 nav2_msgs::msg::MissedWaypoint missedWaypoint;
336 missedWaypoint.index = goal_index;
337 missedWaypoint.goal = poses[goal_index];
338 missedWaypoint.error_code =
339 nav2_msgs::action::FollowWaypoints::Result::TASK_EXECUTOR_FAILED;
340 result->missed_waypoints.push_back(missedWaypoint);
343 if (!is_task_executed && stop_on_failure_) {
345 get_logger(),
"Failed to execute task at waypoint %i "
346 " stop on failure is enabled."
347 " Terminating action.", goal_index);
349 action_server->terminate_current(result);
350 current_goal_status_.error_code = 0;
354 get_logger(),
"Handled task execution on waypoint %i,"
355 " moving to next.", goal_index);
359 if (current_goal_status_.status != ActionStatus::PROCESSING) {
363 if (goal_index >= poses.size()) {
364 if (current_loop_no == no_of_loops) {
366 get_logger(),
"Completed all %zu waypoints requested.",
368 action_server->succeeded_current(result);
369 current_goal_status_.error_code = 0;
373 get_logger(),
"Starting a new loop, current loop count is %i",
380 callback_group_executor_.spin_some();
387 auto feedback = std::make_shared<ActionT::Feedback>();
388 auto result = std::make_shared<ActionT::Result>();
390 followWaypointsHandler<std::unique_ptr<ActionServer>,
391 ActionT::Feedback::SharedPtr,
392 ActionT::Result::SharedPtr>(
399 auto feedback = std::make_shared<ActionTGPS::Feedback>();
400 auto result = std::make_shared<ActionTGPS::Result>();
402 followWaypointsHandler<std::unique_ptr<ActionServerGPS>,
403 ActionTGPS::Feedback::SharedPtr,
404 ActionTGPS::Result::SharedPtr>(
411 const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result)
413 if (result.goal_id != future_goal_handle_.get()->get_goal_id()) {
416 "Goal IDs do not match for the current goal handle and received result."
417 "Ignoring likely due to receiving result for an old goal.");
421 switch (result.code) {
422 case rclcpp_action::ResultCode::SUCCEEDED:
423 current_goal_status_.status = ActionStatus::SUCCEEDED;
425 case rclcpp_action::ResultCode::ABORTED:
426 current_goal_status_.status = ActionStatus::FAILED;
427 current_goal_status_.error_code = result.result->error_code;
429 case rclcpp_action::ResultCode::CANCELED:
430 current_goal_status_.status = ActionStatus::FAILED;
433 RCLCPP_ERROR(get_logger(),
"Received an UNKNOWN result code from navigation action!");
434 current_goal_status_.status = ActionStatus::UNKNOWN;
441 const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal)
446 "navigate_to_pose action client failed to send goal to server.");
447 current_goal_status_.status = ActionStatus::FAILED;
451 rcl_interfaces::msg::SetParametersResult
455 rcl_interfaces::msg::SetParametersResult result;
457 for (
auto parameter : parameters) {
458 const auto & type = parameter.get_type();
459 const auto & name = parameter.get_name();
461 if (type == ParameterType::PARAMETER_INTEGER) {
462 if (name ==
"loop_rate") {
463 loop_rate_ = parameter.as_int();
465 }
else if (type == ParameterType::PARAMETER_BOOL) {
466 if (name ==
"stop_on_failure") {
467 stop_on_failure_ = parameter.as_bool();
472 result.successful =
true;
476 std::vector<geometry_msgs::msg::PoseStamped>
478 const std::vector<geographic_msgs::msg::GeoPose> & gps_poses)
481 this->get_logger(),
"Converting GPS waypoints to %s Frame..",
482 global_frame_id_.c_str());
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;
493 from_ll_to_map_client_->wait_for_service((std::chrono::seconds(1)));
494 if (!from_ll_to_map_client_->invoke(request, response)) {
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_) {
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>();
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);
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;
530 #include "rclcpp_components/register_node_macro.hpp"
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 for invoke() and block-style calling.
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...