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);
39 nav2_util::declare_parameter_if_not_declared(
40 this, std::string(
"waypoint_task_executor_plugin"),
41 rclcpp::ParameterValue(std::string(
"wait_at_waypoint")));
42 nav2_util::declare_parameter_if_not_declared(
43 this, std::string(
"wait_at_waypoint.plugin"),
44 rclcpp::ParameterValue(std::string(
"nav2_waypoint_follower::WaitAtWaypoint")));
51 nav2_util::CallbackReturn
54 RCLCPP_INFO(get_logger(),
"Configuring");
58 stop_on_failure_ = get_parameter(
"stop_on_failure").as_bool();
59 loop_rate_ = get_parameter(
"loop_rate").as_int();
60 waypoint_task_executor_id_ = get_parameter(
"waypoint_task_executor_plugin").as_string();
62 callback_group_ = create_callback_group(
63 rclcpp::CallbackGroupType::MutuallyExclusive,
65 callback_group_executor_.add_callback_group(callback_group_, get_node_base_interface());
67 nav_to_pose_client_ = rclcpp_action::create_client<ClientT>(
68 get_node_base_interface(),
69 get_node_graph_interface(),
70 get_node_logging_interface(),
71 get_node_waitables_interface(),
72 "navigate_to_pose", callback_group_);
74 action_server_ = std::make_unique<ActionServer>(
75 get_node_base_interface(),
76 get_node_clock_interface(),
77 get_node_logging_interface(),
78 get_node_waitables_interface(),
82 waypoint_task_executor_type_ = nav2_util::get_plugin_type_param(
84 waypoint_task_executor_id_);
85 waypoint_task_executor_ = waypoint_task_executor_loader_.createUniqueInstance(
86 waypoint_task_executor_type_);
88 get_logger(),
"Created waypoint_task_executor : %s of type %s",
89 waypoint_task_executor_id_.c_str(), waypoint_task_executor_type_.c_str());
90 waypoint_task_executor_->initialize(node, waypoint_task_executor_id_);
91 }
catch (
const pluginlib::PluginlibException & ex) {
94 "Failed to create waypoint_task_executor. Exception: %s", ex.what());
97 return nav2_util::CallbackReturn::SUCCESS;
100 nav2_util::CallbackReturn
103 RCLCPP_INFO(get_logger(),
"Activating");
105 action_server_->activate();
109 dyn_params_handler_ = node->add_on_set_parameters_callback(
115 return nav2_util::CallbackReturn::SUCCESS;
118 nav2_util::CallbackReturn
121 RCLCPP_INFO(get_logger(),
"Deactivating");
123 action_server_->deactivate();
124 dyn_params_handler_.reset();
129 return nav2_util::CallbackReturn::SUCCESS;
132 nav2_util::CallbackReturn
135 RCLCPP_INFO(get_logger(),
"Cleaning up");
137 action_server_.reset();
138 nav_to_pose_client_.reset();
140 return nav2_util::CallbackReturn::SUCCESS;
143 nav2_util::CallbackReturn
146 RCLCPP_INFO(get_logger(),
"Shutting down");
147 return nav2_util::CallbackReturn::SUCCESS;
153 auto goal = action_server_->get_current_goal();
154 auto feedback = std::make_shared<ActionT::Feedback>();
155 auto result = std::make_shared<ActionT::Result>();
158 if (!action_server_ || !action_server_->is_server_active()) {
159 RCLCPP_DEBUG(get_logger(),
"Action server inactive. Stopping.");
164 get_logger(),
"Received follow waypoint request with %i waypoints.",
165 static_cast<int>(goal->poses.size()));
167 if (goal->poses.size() == 0) {
168 action_server_->succeeded_current(result);
172 rclcpp::WallRate r(loop_rate_);
173 uint32_t goal_index = 0;
174 bool new_goal =
true;
176 while (rclcpp::ok()) {
178 if (action_server_->is_cancel_requested()) {
179 auto cancel_future = nav_to_pose_client_->async_cancel_all_goals();
180 callback_group_executor_.spin_until_future_complete(cancel_future);
182 callback_group_executor_.spin_some();
183 action_server_->terminate_all();
188 if (action_server_->is_preempt_requested()) {
189 RCLCPP_INFO(get_logger(),
"Preempting the goal pose.");
190 goal = action_server_->accept_pending_goal();
198 ClientT::Goal client_goal;
199 client_goal.pose = goal->poses[goal_index];
201 auto send_goal_options = rclcpp_action::Client<ClientT>::SendGoalOptions();
202 send_goal_options.result_callback =
204 send_goal_options.goal_response_callback =
206 future_goal_handle_ =
207 nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);
208 current_goal_status_ = ActionStatus::PROCESSING;
211 feedback->current_waypoint = goal_index;
212 action_server_->publish_feedback(feedback);
214 if (current_goal_status_ == ActionStatus::FAILED) {
215 failed_ids_.push_back(goal_index);
217 if (stop_on_failure_) {
219 get_logger(),
"Failed to process waypoint %i in waypoint "
220 "list and stop on failure is enabled."
221 " Terminating action.", goal_index);
222 result->missed_waypoints = failed_ids_;
223 action_server_->terminate_current(result);
228 get_logger(),
"Failed to process waypoint %i,"
229 " moving to next.", goal_index);
231 }
else if (current_goal_status_ == ActionStatus::SUCCEEDED) {
233 get_logger(),
"Succeeded processing waypoint %i, processing waypoint task execution",
235 bool is_task_executed = waypoint_task_executor_->processAtWaypoint(
236 goal->poses[goal_index], goal_index);
238 get_logger(),
"Task execution at waypoint %i %s", goal_index,
239 is_task_executed ?
"succeeded" :
"failed!");
241 if (!is_task_executed && stop_on_failure_) {
242 failed_ids_.push_back(goal_index);
244 get_logger(),
"Failed to execute task at waypoint %i "
245 " stop on failure is enabled."
246 " Terminating action.", goal_index);
247 result->missed_waypoints = failed_ids_;
248 action_server_->terminate_current(result);
253 get_logger(),
"Handled task execution on waypoint %i,"
254 " moving to next.", goal_index);
258 if (current_goal_status_ != ActionStatus::PROCESSING &&
259 current_goal_status_ != ActionStatus::UNKNOWN)
264 if (goal_index >= goal->poses.size()) {
266 get_logger(),
"Completed all %zu waypoints requested.",
268 result->missed_waypoints = failed_ids_;
269 action_server_->succeeded_current(result);
274 RCLCPP_INFO_EXPRESSION(
276 (
static_cast<int>(now().seconds()) % 30 == 0),
277 "Processing waypoint %i...", goal_index);
280 callback_group_executor_.spin_some();
287 const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result)
289 if (result.goal_id != future_goal_handle_.get()->get_goal_id()) {
292 "Goal IDs do not match for the current goal handle and received result."
293 "Ignoring likely due to receiving result for an old goal.");
297 switch (result.code) {
298 case rclcpp_action::ResultCode::SUCCEEDED:
299 current_goal_status_ = ActionStatus::SUCCEEDED;
301 case rclcpp_action::ResultCode::ABORTED:
302 current_goal_status_ = ActionStatus::FAILED;
304 case rclcpp_action::ResultCode::CANCELED:
305 current_goal_status_ = ActionStatus::FAILED;
308 current_goal_status_ = ActionStatus::UNKNOWN;
315 const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal)
320 "navigate_to_pose action client failed to send goal to server.");
321 current_goal_status_ = ActionStatus::FAILED;
325 rcl_interfaces::msg::SetParametersResult
329 rcl_interfaces::msg::SetParametersResult result;
331 for (
auto parameter : parameters) {
332 const auto & type = parameter.get_type();
333 const auto & name = parameter.get_name();
335 if (type == ParameterType::PARAMETER_INTEGER) {
336 if (name ==
"loop_rate") {
337 loop_rate_ = parameter.as_int();
339 }
else if (type == ParameterType::PARAMETER_BOOL) {
340 if (name ==
"stop_on_failure") {
341 stop_on_failure_ = parameter.as_bool();
346 result.successful =
true;
352 #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.
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 followWaypoints()
Action server callbacks.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.