Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
nav2_panel.cpp
1 // Copyright (c) 2019 Intel Corporation
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_rviz_plugins/nav2_panel.hpp"
16 
17 #include <QtConcurrent/QtConcurrent>
18 #include <QVBoxLayout>
19 
20 #include <memory>
21 #include <vector>
22 #include <utility>
23 #include <chrono>
24 #include <string>
25 
26 #include "nav2_rviz_plugins/goal_common.hpp"
27 #include "rviz_common/display_context.hpp"
28 #include "ament_index_cpp/get_package_share_directory.hpp"
29 
30 using namespace std::chrono_literals;
31 
32 namespace nav2_rviz_plugins
33 {
34 using nav2_util::geometry_utils::orientationAroundZAxis;
35 
36 // Define global GoalPoseUpdater so that the nav2 GoalTool plugin can access to update goal pose
37 GoalPoseUpdater GoalUpdater;
38 
39 Nav2Panel::Nav2Panel(QWidget * parent)
40 : Panel(parent),
41  server_timeout_(100)
42 {
43  // Create the control button and its tooltip
44 
45  start_reset_button_ = new QPushButton;
46  pause_resume_button_ = new QPushButton;
47  navigation_mode_button_ = new QPushButton;
48  navigation_status_indicator_ = new QLabel;
49  localization_status_indicator_ = new QLabel;
50  navigation_goal_status_indicator_ = new QLabel;
51  navigation_feedback_indicator_ = new QLabel;
52 
53  // Create the state machine used to present the proper control button states in the UI
54 
55  const char * startup_msg = "Configure and activate all nav2 lifecycle nodes";
56  const char * shutdown_msg = "Deactivate and cleanup all nav2 lifecycle nodes";
57  const char * cancel_msg = "Cancel navigation";
58  const char * pause_msg = "Deactivate all nav2 lifecycle nodes";
59  const char * resume_msg = "Activate all nav2 lifecycle nodes";
60  const char * single_goal_msg = "Change to waypoint / nav through poses style navigation";
61  const char * waypoint_goal_msg = "Start following waypoints";
62  const char * nft_goal_msg = "Start navigating through poses";
63  const char * cancel_waypoint_msg = "Cancel waypoint / viapoint accumulation mode";
64 
65  const QString navigation_active("<table><tr><td width=100><b>Navigation:</b></td>"
66  "<td><font color=green>active</color></td></tr></table>");
67  const QString navigation_inactive("<table><tr><td width=100><b>Navigation:</b></td>"
68  "<td>inactive</td></tr></table>");
69  const QString navigation_unknown("<table><tr><td width=100><b>Navigation:</b></td>"
70  "<td>unknown</td></tr></table>");
71  const QString localization_active("<table><tr><td width=100><b>Localization:</b></td>"
72  "<td><font color=green>active</color></td></tr></table>");
73  const QString localization_inactive("<table><tr><td width=100><b>Localization:</b></td>"
74  "<td>inactive</td></tr></table>");
75  const QString localization_unknown("<table><tr><td width=100><b>Localization:</b></td>"
76  "<td>unknown</td></tr></table>");
77 
78  navigation_status_indicator_->setText(navigation_unknown);
79  localization_status_indicator_->setText(localization_unknown);
80  navigation_goal_status_indicator_->setText(getGoalStatusLabel());
81  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
82  navigation_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
83  localization_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
84  navigation_goal_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
85  navigation_feedback_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
86 
87  pre_initial_ = new QState();
88  pre_initial_->setObjectName("pre_initial");
89  pre_initial_->assignProperty(start_reset_button_, "text", "Startup");
90  pre_initial_->assignProperty(start_reset_button_, "enabled", false);
91 
92  pre_initial_->assignProperty(pause_resume_button_, "text", "Pause");
93  pre_initial_->assignProperty(pause_resume_button_, "enabled", false);
94 
95  pre_initial_->assignProperty(
96  navigation_mode_button_, "text",
97  "Waypoint / Nav Through Poses Mode");
98  pre_initial_->assignProperty(navigation_mode_button_, "enabled", false);
99 
100  initial_ = new QState();
101  initial_->setObjectName("initial");
102  initial_->assignProperty(start_reset_button_, "text", "Startup");
103  initial_->assignProperty(start_reset_button_, "toolTip", startup_msg);
104  initial_->assignProperty(start_reset_button_, "enabled", true);
105 
106  initial_->assignProperty(pause_resume_button_, "text", "Pause");
107  initial_->assignProperty(pause_resume_button_, "enabled", false);
108 
109  initial_->assignProperty(navigation_mode_button_, "text", "Waypoint / Nav Through Poses Mode");
110  initial_->assignProperty(navigation_mode_button_, "enabled", false);
111 
112  // State entered when navigate_to_pose action is not active
113  idle_ = new QState();
114  idle_->setObjectName("idle");
115  idle_->assignProperty(start_reset_button_, "text", "Reset");
116  idle_->assignProperty(start_reset_button_, "toolTip", shutdown_msg);
117  idle_->assignProperty(start_reset_button_, "enabled", true);
118 
119  idle_->assignProperty(pause_resume_button_, "text", "Pause");
120  idle_->assignProperty(pause_resume_button_, "enabled", true);
121  idle_->assignProperty(pause_resume_button_, "toolTip", pause_msg);
122 
123  idle_->assignProperty(navigation_mode_button_, "text", "Waypoint / Nav Through Poses Mode");
124  idle_->assignProperty(navigation_mode_button_, "enabled", true);
125  idle_->assignProperty(navigation_mode_button_, "toolTip", single_goal_msg);
126 
127  // State entered when navigate_to_pose action is not active
128  accumulating_ = new QState();
129  accumulating_->setObjectName("accumulating");
130  accumulating_->assignProperty(start_reset_button_, "text", "Cancel Accumulation");
131  accumulating_->assignProperty(start_reset_button_, "toolTip", cancel_waypoint_msg);
132  accumulating_->assignProperty(start_reset_button_, "enabled", true);
133 
134  accumulating_->assignProperty(pause_resume_button_, "text", "Start Nav Through Poses");
135  accumulating_->assignProperty(pause_resume_button_, "enabled", true);
136  accumulating_->assignProperty(pause_resume_button_, "toolTip", nft_goal_msg);
137 
138  accumulating_->assignProperty(navigation_mode_button_, "text", "Start Waypoint Following");
139  accumulating_->assignProperty(navigation_mode_button_, "enabled", true);
140  accumulating_->assignProperty(navigation_mode_button_, "toolTip", waypoint_goal_msg);
141 
142  accumulated_wp_ = new QState();
143  accumulated_wp_->setObjectName("accumulated_wp");
144  accumulated_wp_->assignProperty(start_reset_button_, "text", "Cancel");
145  accumulated_wp_->assignProperty(start_reset_button_, "toolTip", cancel_msg);
146  accumulated_wp_->assignProperty(start_reset_button_, "enabled", true);
147 
148  accumulated_wp_->assignProperty(pause_resume_button_, "text", "Start Nav Through Poses");
149  accumulated_wp_->assignProperty(pause_resume_button_, "enabled", false);
150  accumulated_wp_->assignProperty(pause_resume_button_, "toolTip", nft_goal_msg);
151 
152  accumulated_wp_->assignProperty(navigation_mode_button_, "text", "Start Waypoint Following");
153  accumulated_wp_->assignProperty(navigation_mode_button_, "enabled", false);
154  accumulated_wp_->assignProperty(navigation_mode_button_, "toolTip", waypoint_goal_msg);
155 
156  accumulated_nav_through_poses_ = new QState();
157  accumulated_nav_through_poses_->setObjectName("accumulated_nav_through_poses");
158  accumulated_nav_through_poses_->assignProperty(start_reset_button_, "text", "Cancel");
159  accumulated_nav_through_poses_->assignProperty(start_reset_button_, "toolTip", cancel_msg);
160  accumulated_nav_through_poses_->assignProperty(start_reset_button_, "enabled", true);
161 
162  accumulated_nav_through_poses_->assignProperty(
163  pause_resume_button_, "text",
164  "Start Nav Through Poses");
165  accumulated_nav_through_poses_->assignProperty(pause_resume_button_, "enabled", false);
166  accumulated_nav_through_poses_->assignProperty(pause_resume_button_, "toolTip", nft_goal_msg);
167 
168  accumulated_nav_through_poses_->assignProperty(
169  navigation_mode_button_, "text",
170  "Start Waypoint Following");
171  accumulated_nav_through_poses_->assignProperty(navigation_mode_button_, "enabled", false);
172  accumulated_nav_through_poses_->assignProperty(
173  navigation_mode_button_, "toolTip",
174  waypoint_goal_msg);
175 
176  // State entered to cancel the navigate_to_pose action
177  canceled_ = new QState();
178  canceled_->setObjectName("canceled");
179 
180  // State entered to reset the nav2 lifecycle nodes
181  reset_ = new QState();
182  reset_->setObjectName("reset");
183 
184  // State entered while the navigate_to_pose action is active
185  running_ = new QState();
186  running_->setObjectName("running");
187  running_->assignProperty(start_reset_button_, "text", "Cancel");
188  running_->assignProperty(start_reset_button_, "toolTip", cancel_msg);
189 
190  running_->assignProperty(pause_resume_button_, "text", "Pause");
191  running_->assignProperty(pause_resume_button_, "enabled", false);
192 
193  running_->assignProperty(navigation_mode_button_, "text", "Waypoint mode");
194  running_->assignProperty(navigation_mode_button_, "enabled", false);
195 
196  // State entered when pause is requested
197  paused_ = new QState();
198  paused_->setObjectName("pausing");
199  paused_->assignProperty(start_reset_button_, "text", "Reset");
200  paused_->assignProperty(start_reset_button_, "toolTip", shutdown_msg);
201 
202  paused_->assignProperty(pause_resume_button_, "text", "Resume");
203  paused_->assignProperty(pause_resume_button_, "toolTip", resume_msg);
204  paused_->assignProperty(pause_resume_button_, "enabled", true);
205 
206  paused_->assignProperty(navigation_mode_button_, "text", "Start navigation");
207  paused_->assignProperty(navigation_mode_button_, "toolTip", resume_msg);
208  paused_->assignProperty(navigation_mode_button_, "enabled", true);
209 
210  // State entered to resume the nav2 lifecycle nodes
211  resumed_ = new QState();
212  resumed_->setObjectName("resuming");
213 
214  QObject::connect(initial_, SIGNAL(exited()), this, SLOT(onStartup()));
215  QObject::connect(canceled_, SIGNAL(exited()), this, SLOT(onCancel()));
216  QObject::connect(reset_, SIGNAL(exited()), this, SLOT(onShutdown()));
217  QObject::connect(paused_, SIGNAL(entered()), this, SLOT(onPause()));
218  QObject::connect(resumed_, SIGNAL(exited()), this, SLOT(onResume()));
219  QObject::connect(accumulating_, SIGNAL(entered()), this, SLOT(onAccumulating()));
220  QObject::connect(accumulated_wp_, SIGNAL(entered()), this, SLOT(onAccumulatedWp()));
221  QObject::connect(
222  accumulated_nav_through_poses_, SIGNAL(entered()), this,
223  SLOT(onAccumulatedNTP()));
224 
225  // Start/Reset button click transitions
226  initial_->addTransition(start_reset_button_, SIGNAL(clicked()), idle_);
227  idle_->addTransition(start_reset_button_, SIGNAL(clicked()), reset_);
228  running_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
229  paused_->addTransition(start_reset_button_, SIGNAL(clicked()), reset_);
230  idle_->addTransition(navigation_mode_button_, SIGNAL(clicked()), accumulating_);
231  accumulating_->addTransition(navigation_mode_button_, SIGNAL(clicked()), accumulated_wp_);
232  accumulating_->addTransition(
233  pause_resume_button_, SIGNAL(
234  clicked()), accumulated_nav_through_poses_);
235  accumulating_->addTransition(start_reset_button_, SIGNAL(clicked()), idle_);
236  accumulated_wp_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
237  accumulated_nav_through_poses_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
238 
239  // Internal state transitions
240  canceled_->addTransition(canceled_, SIGNAL(entered()), idle_);
241  reset_->addTransition(reset_, SIGNAL(entered()), initial_);
242  resumed_->addTransition(resumed_, SIGNAL(entered()), idle_);
243 
244  // Pause/Resume button click transitions
245  idle_->addTransition(pause_resume_button_, SIGNAL(clicked()), paused_);
246  paused_->addTransition(pause_resume_button_, SIGNAL(clicked()), resumed_);
247 
248  // ROSAction Transitions: So when actions are updated remotely (failing, succeeding, etc)
249  // the state of the application will also update. This means that if in the processing
250  // states and then goes inactive, move back to the idle state. Vise versa as well.
251  ROSActionQTransition * idleTransition = new ROSActionQTransition(QActionState::INACTIVE);
252  idleTransition->setTargetState(running_);
253  idle_->addTransition(idleTransition);
254 
255  ROSActionQTransition * runningTransition = new ROSActionQTransition(QActionState::ACTIVE);
256  runningTransition->setTargetState(idle_);
257  running_->addTransition(runningTransition);
258 
259  ROSActionQTransition * idleAccumulatedWpTransition =
260  new ROSActionQTransition(QActionState::INACTIVE);
261  idleAccumulatedWpTransition->setTargetState(accumulated_wp_);
262  idle_->addTransition(idleAccumulatedWpTransition);
263 
264  ROSActionQTransition * accumulatedWpTransition = new ROSActionQTransition(QActionState::ACTIVE);
265  accumulatedWpTransition->setTargetState(idle_);
266  accumulated_wp_->addTransition(accumulatedWpTransition);
267 
268  ROSActionQTransition * idleAccumulatedNTPTransition =
269  new ROSActionQTransition(QActionState::INACTIVE);
270  idleAccumulatedNTPTransition->setTargetState(accumulated_nav_through_poses_);
271  idle_->addTransition(idleAccumulatedNTPTransition);
272 
273  ROSActionQTransition * accumulatedNTPTransition = new ROSActionQTransition(QActionState::ACTIVE);
274  accumulatedNTPTransition->setTargetState(idle_);
275  accumulated_nav_through_poses_->addTransition(accumulatedNTPTransition);
276 
277  auto options = rclcpp::NodeOptions().arguments(
278  {"--ros-args", "--remap", "__node:=rviz_navigation_dialog_action_client", "--"});
279  client_node_ = std::make_shared<rclcpp::Node>("_", options);
280 
281  client_nav_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
282  "lifecycle_manager_navigation", client_node_);
283  client_loc_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
284  "lifecycle_manager_localization", client_node_);
285  initial_thread_ = new InitialThread(client_nav_, client_loc_);
286  connect(initial_thread_, &InitialThread::finished, initial_thread_, &QObject::deleteLater);
287 
288  QSignalTransition * activeSignal = new QSignalTransition(
289  initial_thread_,
290  &InitialThread::navigationActive);
291  activeSignal->setTargetState(idle_);
292  pre_initial_->addTransition(activeSignal);
293 
294  QSignalTransition * inactiveSignal = new QSignalTransition(
295  initial_thread_,
296  &InitialThread::navigationInactive);
297  inactiveSignal->setTargetState(initial_);
298  pre_initial_->addTransition(inactiveSignal);
299 
300  QObject::connect(
301  initial_thread_, &InitialThread::navigationActive,
302  [this, navigation_active] {
303  navigation_status_indicator_->setText(navigation_active);
304  });
305  QObject::connect(
306  initial_thread_, &InitialThread::navigationInactive,
307  [this, navigation_inactive] {
308  navigation_status_indicator_->setText(navigation_inactive);
309  navigation_goal_status_indicator_->setText(getGoalStatusLabel());
310  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
311  });
312  QObject::connect(
313  initial_thread_, &InitialThread::localizationActive,
314  [this, localization_active] {
315  localization_status_indicator_->setText(localization_active);
316  });
317  QObject::connect(
318  initial_thread_, &InitialThread::localizationInactive,
319  [this, localization_inactive] {
320  localization_status_indicator_->setText(localization_inactive);
321  });
322 
323  state_machine_.addState(pre_initial_);
324  state_machine_.addState(initial_);
325  state_machine_.addState(idle_);
326  state_machine_.addState(running_);
327  state_machine_.addState(canceled_);
328  state_machine_.addState(reset_);
329  state_machine_.addState(paused_);
330  state_machine_.addState(resumed_);
331  state_machine_.addState(accumulating_);
332  state_machine_.addState(accumulated_wp_);
333  state_machine_.addState(accumulated_nav_through_poses_);
334 
335  state_machine_.setInitialState(pre_initial_);
336 
337  // delay starting initial thread until state machine has started or a race occurs
338  QObject::connect(&state_machine_, SIGNAL(started()), this, SLOT(startThread()));
339  state_machine_.start();
340 
341  // Lay out the items in the panel
342  QVBoxLayout * main_layout = new QVBoxLayout;
343  main_layout->addWidget(navigation_status_indicator_);
344  main_layout->addWidget(localization_status_indicator_);
345  main_layout->addWidget(navigation_goal_status_indicator_);
346  main_layout->addWidget(navigation_feedback_indicator_);
347  main_layout->addWidget(pause_resume_button_);
348  main_layout->addWidget(start_reset_button_);
349  main_layout->addWidget(navigation_mode_button_);
350 
351  main_layout->setContentsMargins(10, 10, 10, 10);
352  setLayout(main_layout);
353 
354  navigation_action_client_ =
355  rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
356  client_node_,
357  "navigate_to_pose");
358  waypoint_follower_action_client_ =
359  rclcpp_action::create_client<nav2_msgs::action::FollowWaypoints>(
360  client_node_,
361  "follow_waypoints");
362  nav_through_poses_action_client_ =
363  rclcpp_action::create_client<nav2_msgs::action::NavigateThroughPoses>(
364  client_node_,
365  "navigate_through_poses");
366  navigation_goal_ = nav2_msgs::action::NavigateToPose::Goal();
367  waypoint_follower_goal_ = nav2_msgs::action::FollowWaypoints::Goal();
368  nav_through_poses_goal_ = nav2_msgs::action::NavigateThroughPoses::Goal();
369 
370  wp_navigation_markers_pub_ =
371  client_node_->create_publisher<visualization_msgs::msg::MarkerArray>(
372  "waypoints",
373  rclcpp::QoS(1).transient_local());
374 
375  QObject::connect(
376  &GoalUpdater, SIGNAL(updateGoal(double,double,double,QString)), // NOLINT
377  this, SLOT(onNewGoal(double,double,double,QString))); // NOLINT
378 }
379 
380 Nav2Panel::~Nav2Panel()
381 {
382 }
383 
384 void
385 Nav2Panel::onInitialize()
386 {
387  auto node = getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();
388 
389  // create action feedback subscribers
390  navigation_feedback_sub_ =
391  node->create_subscription<nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage>(
392  "navigate_to_pose/_action/feedback",
393  rclcpp::SystemDefaultsQoS(),
394  [this](const nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage::SharedPtr msg) {
395  navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel(msg->feedback));
396  });
397  nav_through_poses_feedback_sub_ =
398  node->create_subscription<nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage>(
399  "navigate_through_poses/_action/feedback",
400  rclcpp::SystemDefaultsQoS(),
401  [this](const nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage::SharedPtr msg) {
402  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel(msg->feedback));
403  });
404 
405  // create action goal status subscribers
406  navigation_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
407  "navigate_to_pose/_action/status",
408  rclcpp::SystemDefaultsQoS(),
409  [this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
410  navigation_goal_status_indicator_->setText(
411  getGoalStatusLabel(msg->status_list.back().status));
412  if (msg->status_list.back().status != action_msgs::msg::GoalStatus::STATUS_EXECUTING) {
413  navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel());
414  }
415  });
416  nav_through_poses_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
417  "navigate_through_poses/_action/status",
418  rclcpp::SystemDefaultsQoS(),
419  [this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
420  navigation_goal_status_indicator_->setText(
421  getGoalStatusLabel(msg->status_list.back().status));
422  if (msg->status_list.back().status != action_msgs::msg::GoalStatus::STATUS_EXECUTING) {
423  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
424  }
425  });
426 }
427 
428 void
429 Nav2Panel::startThread()
430 {
431  // start initial thread now that state machine is started
432  initial_thread_->start();
433 }
434 
435 void
436 Nav2Panel::onPause()
437 {
438  QFuture<void> futureNav =
439  QtConcurrent::run(
440  std::bind(
442  client_nav_.get(), std::placeholders::_1), server_timeout_);
443  QFuture<void> futureLoc =
444  QtConcurrent::run(
445  std::bind(
447  client_loc_.get(), std::placeholders::_1), server_timeout_);
448 }
449 
450 void
451 Nav2Panel::onResume()
452 {
453  QFuture<void> futureNav =
454  QtConcurrent::run(
455  std::bind(
457  client_nav_.get(), std::placeholders::_1), server_timeout_);
458  QFuture<void> futureLoc =
459  QtConcurrent::run(
460  std::bind(
462  client_loc_.get(), std::placeholders::_1), server_timeout_);
463 }
464 
465 void
466 Nav2Panel::onStartup()
467 {
468  QFuture<void> futureNav =
469  QtConcurrent::run(
470  std::bind(
472  client_nav_.get(), std::placeholders::_1), server_timeout_);
473  QFuture<void> futureLoc =
474  QtConcurrent::run(
475  std::bind(
477  client_loc_.get(), std::placeholders::_1), server_timeout_);
478 }
479 
480 void
481 Nav2Panel::onShutdown()
482 {
483  QFuture<void> futureNav =
484  QtConcurrent::run(
485  std::bind(
487  client_nav_.get(), std::placeholders::_1), server_timeout_);
488  QFuture<void> futureLoc =
489  QtConcurrent::run(
490  std::bind(
492  client_loc_.get(), std::placeholders::_1), server_timeout_);
493  timer_.stop();
494 }
495 
496 void
497 Nav2Panel::onCancel()
498 {
499  QFuture<void> future =
500  QtConcurrent::run(
501  std::bind(
502  &Nav2Panel::onCancelButtonPressed,
503  this));
504 }
505 
506 void
507 Nav2Panel::onNewGoal(double x, double y, double theta, QString frame)
508 {
509  auto pose = geometry_msgs::msg::PoseStamped();
510 
511  pose.header.stamp = rclcpp::Clock().now();
512  pose.header.frame_id = frame.toStdString();
513  pose.pose.position.x = x;
514  pose.pose.position.y = y;
515  pose.pose.position.z = 0.0;
516  pose.pose.orientation = orientationAroundZAxis(theta);
517 
518  if (state_machine_.configuration().contains(accumulating_)) {
519  acummulated_poses_.push_back(pose);
520  } else {
521  std::cout << "Start navigation" << std::endl;
522  startNavigation(pose);
523  }
524 
525  updateWpNavigationMarkers();
526 }
527 
528 void
529 Nav2Panel::onCancelButtonPressed()
530 {
531  if (navigation_goal_handle_) {
532  auto future_cancel = navigation_action_client_->async_cancel_goal(navigation_goal_handle_);
533 
534  if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
535  rclcpp::FutureReturnCode::SUCCESS)
536  {
537  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel goal");
538  } else {
539  navigation_goal_handle_.reset();
540  }
541  }
542 
543  if (waypoint_follower_goal_handle_) {
544  auto future_cancel =
545  waypoint_follower_action_client_->async_cancel_goal(waypoint_follower_goal_handle_);
546 
547  if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
548  rclcpp::FutureReturnCode::SUCCESS)
549  {
550  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel waypoint follower");
551  } else {
552  waypoint_follower_goal_handle_.reset();
553  }
554  }
555 
556  if (nav_through_poses_goal_handle_) {
557  auto future_cancel =
558  nav_through_poses_action_client_->async_cancel_goal(nav_through_poses_goal_handle_);
559 
560  if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
561  rclcpp::FutureReturnCode::SUCCESS)
562  {
563  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel nav through pose action");
564  } else {
565  nav_through_poses_goal_handle_.reset();
566  }
567  }
568 
569 
570  timer_.stop();
571 }
572 
573 void
574 Nav2Panel::onAccumulatedWp()
575 {
576  std::cout << "Start waypoint" << std::endl;
577  startWaypointFollowing(acummulated_poses_);
578  acummulated_poses_.clear();
579 }
580 
581 void
582 Nav2Panel::onAccumulatedNTP()
583 {
584  std::cout << "Start navigate through poses" << std::endl;
585  startNavThroughPoses(acummulated_poses_);
586  acummulated_poses_.clear();
587 }
588 
589 void
590 Nav2Panel::onAccumulating()
591 {
592  acummulated_poses_.clear();
593 }
594 
595 void
596 Nav2Panel::timerEvent(QTimerEvent * event)
597 {
598  if (state_machine_.configuration().contains(accumulated_wp_)) {
599  if (event->timerId() == timer_.timerId()) {
600  if (!waypoint_follower_goal_handle_) {
601  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
602  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
603  return;
604  }
605 
606  rclcpp::spin_some(client_node_);
607  auto status = waypoint_follower_goal_handle_->get_status();
608 
609  // Check if the goal is still executing
610  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
611  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
612  {
613  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
614  } else {
615  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
616  timer_.stop();
617  }
618  }
619  } else if (state_machine_.configuration().contains(accumulated_nav_through_poses_)) {
620  if (event->timerId() == timer_.timerId()) {
621  if (!nav_through_poses_goal_handle_) {
622  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
623  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
624  return;
625  }
626 
627  rclcpp::spin_some(client_node_);
628  auto status = nav_through_poses_goal_handle_->get_status();
629 
630  // Check if the goal is still executing
631  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
632  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
633  {
634  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
635  } else {
636  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
637  timer_.stop();
638  }
639  }
640  } else {
641  if (event->timerId() == timer_.timerId()) {
642  if (!navigation_goal_handle_) {
643  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
644  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
645  return;
646  }
647 
648  rclcpp::spin_some(client_node_);
649  auto status = navigation_goal_handle_->get_status();
650 
651  // Check if the goal is still executing
652  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
653  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
654  {
655  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
656  } else {
657  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
658  timer_.stop();
659  }
660  }
661  }
662 }
663 
664 void
665 Nav2Panel::startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses)
666 {
667  auto is_action_server_ready =
668  waypoint_follower_action_client_->wait_for_action_server(std::chrono::seconds(5));
669  if (!is_action_server_ready) {
670  RCLCPP_ERROR(
671  client_node_->get_logger(), "follow_waypoints action server is not available."
672  " Is the initial pose set?");
673  return;
674  }
675 
676  // Send the goal poses
677  waypoint_follower_goal_.poses = poses;
678 
679  RCLCPP_DEBUG(
680  client_node_->get_logger(), "Sending a path of %zu waypoints:",
681  waypoint_follower_goal_.poses.size());
682  for (auto waypoint : waypoint_follower_goal_.poses) {
683  RCLCPP_DEBUG(
684  client_node_->get_logger(),
685  "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
686  }
687 
688  // Enable result awareness by providing an empty lambda function
689  auto send_goal_options =
690  rclcpp_action::Client<nav2_msgs::action::FollowWaypoints>::SendGoalOptions();
691  send_goal_options.result_callback = [this](auto) {
692  waypoint_follower_goal_handle_.reset();
693  };
694 
695  auto future_goal_handle =
696  waypoint_follower_action_client_->async_send_goal(waypoint_follower_goal_, send_goal_options);
697  if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
698  rclcpp::FutureReturnCode::SUCCESS)
699  {
700  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
701  return;
702  }
703 
704  // Get the goal handle and save so that we can check on completion in the timer callback
705  waypoint_follower_goal_handle_ = future_goal_handle.get();
706  if (!waypoint_follower_goal_handle_) {
707  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
708  return;
709  }
710 
711  timer_.start(200, this);
712 }
713 
714 void
715 Nav2Panel::startNavThroughPoses(std::vector<geometry_msgs::msg::PoseStamped> poses)
716 {
717  auto is_action_server_ready =
718  nav_through_poses_action_client_->wait_for_action_server(std::chrono::seconds(5));
719  if (!is_action_server_ready) {
720  RCLCPP_ERROR(
721  client_node_->get_logger(), "navigate_through_poses action server is not available."
722  " Is the initial pose set?");
723  return;
724  }
725 
726  nav_through_poses_goal_.poses = poses;
727  RCLCPP_INFO(
728  client_node_->get_logger(),
729  "NavigateThroughPoses will be called using the BT Navigator's default behavior tree.");
730 
731  RCLCPP_DEBUG(
732  client_node_->get_logger(), "Sending a path of %zu waypoints:",
733  nav_through_poses_goal_.poses.size());
734  for (auto waypoint : nav_through_poses_goal_.poses) {
735  RCLCPP_DEBUG(
736  client_node_->get_logger(),
737  "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
738  }
739 
740  // Enable result awareness by providing an empty lambda function
741  auto send_goal_options =
742  rclcpp_action::Client<nav2_msgs::action::NavigateThroughPoses>::SendGoalOptions();
743  send_goal_options.result_callback = [this](auto) {
744  nav_through_poses_goal_handle_.reset();
745  };
746 
747  auto future_goal_handle =
748  nav_through_poses_action_client_->async_send_goal(nav_through_poses_goal_, send_goal_options);
749  if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
750  rclcpp::FutureReturnCode::SUCCESS)
751  {
752  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
753  return;
754  }
755 
756  // Get the goal handle and save so that we can check on completion in the timer callback
757  nav_through_poses_goal_handle_ = future_goal_handle.get();
758  if (!nav_through_poses_goal_handle_) {
759  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
760  return;
761  }
762 
763  timer_.start(200, this);
764 }
765 
766 void
767 Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose)
768 {
769  auto is_action_server_ready =
770  navigation_action_client_->wait_for_action_server(std::chrono::seconds(5));
771  if (!is_action_server_ready) {
772  RCLCPP_ERROR(
773  client_node_->get_logger(),
774  "navigate_to_pose action server is not available."
775  " Is the initial pose set?");
776  return;
777  }
778 
779  // Send the goal pose
780  navigation_goal_.pose = pose;
781 
782  RCLCPP_INFO(
783  client_node_->get_logger(),
784  "NavigateToPose will be called using the BT Navigator's default behavior tree.");
785 
786  // Enable result awareness by providing an empty lambda function
787  auto send_goal_options =
788  rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SendGoalOptions();
789  send_goal_options.result_callback = [this](auto) {
790  navigation_goal_handle_.reset();
791  };
792 
793  auto future_goal_handle =
794  navigation_action_client_->async_send_goal(navigation_goal_, send_goal_options);
795  if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
796  rclcpp::FutureReturnCode::SUCCESS)
797  {
798  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
799  return;
800  }
801 
802  // Get the goal handle and save so that we can check on completion in the timer callback
803  navigation_goal_handle_ = future_goal_handle.get();
804  if (!navigation_goal_handle_) {
805  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
806  return;
807  }
808 
809  timer_.start(200, this);
810 }
811 
812 void
813 Nav2Panel::save(rviz_common::Config config) const
814 {
815  Panel::save(config);
816 }
817 
818 void
819 Nav2Panel::load(const rviz_common::Config & config)
820 {
821  Panel::load(config);
822 }
823 
824 void
825 Nav2Panel::resetUniqueId()
826 {
827  unique_id = 0;
828 }
829 
830 int
831 Nav2Panel::getUniqueId()
832 {
833  int temp_id = unique_id;
834  unique_id += 1;
835  return temp_id;
836 }
837 
838 void
839 Nav2Panel::updateWpNavigationMarkers()
840 {
841  resetUniqueId();
842 
843  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
844 
845  for (size_t i = 0; i < acummulated_poses_.size(); i++) {
846  // Draw a green arrow at the waypoint pose
847  visualization_msgs::msg::Marker arrow_marker;
848  arrow_marker.header = acummulated_poses_[i].header;
849  arrow_marker.id = getUniqueId();
850  arrow_marker.type = visualization_msgs::msg::Marker::ARROW;
851  arrow_marker.action = visualization_msgs::msg::Marker::ADD;
852  arrow_marker.pose = acummulated_poses_[i].pose;
853  arrow_marker.scale.x = 0.3;
854  arrow_marker.scale.y = 0.05;
855  arrow_marker.scale.z = 0.02;
856  arrow_marker.color.r = 0;
857  arrow_marker.color.g = 255;
858  arrow_marker.color.b = 0;
859  arrow_marker.color.a = 1.0f;
860  arrow_marker.lifetime = rclcpp::Duration(0s);
861  arrow_marker.frame_locked = false;
862  marker_array->markers.push_back(arrow_marker);
863 
864  // Draw a red circle at the waypoint pose
865  visualization_msgs::msg::Marker circle_marker;
866  circle_marker.header = acummulated_poses_[i].header;
867  circle_marker.id = getUniqueId();
868  circle_marker.type = visualization_msgs::msg::Marker::SPHERE;
869  circle_marker.action = visualization_msgs::msg::Marker::ADD;
870  circle_marker.pose = acummulated_poses_[i].pose;
871  circle_marker.scale.x = 0.05;
872  circle_marker.scale.y = 0.05;
873  circle_marker.scale.z = 0.05;
874  circle_marker.color.r = 255;
875  circle_marker.color.g = 0;
876  circle_marker.color.b = 0;
877  circle_marker.color.a = 1.0f;
878  circle_marker.lifetime = rclcpp::Duration(0s);
879  circle_marker.frame_locked = false;
880  marker_array->markers.push_back(circle_marker);
881 
882  // Draw the waypoint number
883  visualization_msgs::msg::Marker marker_text;
884  marker_text.header = acummulated_poses_[i].header;
885  marker_text.id = getUniqueId();
886  marker_text.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
887  marker_text.action = visualization_msgs::msg::Marker::ADD;
888  marker_text.pose = acummulated_poses_[i].pose;
889  marker_text.pose.position.z += 0.2; // draw it on top of the waypoint
890  marker_text.scale.x = 0.07;
891  marker_text.scale.y = 0.07;
892  marker_text.scale.z = 0.07;
893  marker_text.color.r = 0;
894  marker_text.color.g = 255;
895  marker_text.color.b = 0;
896  marker_text.color.a = 1.0f;
897  marker_text.lifetime = rclcpp::Duration(0s);
898  marker_text.frame_locked = false;
899  marker_text.text = "wp_" + std::to_string(i + 1);
900  marker_array->markers.push_back(marker_text);
901  }
902 
903  if (marker_array->markers.empty()) {
904  visualization_msgs::msg::Marker clear_all_marker;
905  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
906  marker_array->markers.push_back(clear_all_marker);
907  }
908 
909  wp_navigation_markers_pub_->publish(std::move(marker_array));
910 }
911 
912 inline QString
913 Nav2Panel::getGoalStatusLabel(int8_t status)
914 {
915  std::string status_str;
916  switch (status) {
917  case action_msgs::msg::GoalStatus::STATUS_EXECUTING:
918  status_str = "<font color=green>active</color>";
919  break;
920 
921  case action_msgs::msg::GoalStatus::STATUS_SUCCEEDED:
922  status_str = "<font color=green>reached</color>";
923  break;
924 
925  case action_msgs::msg::GoalStatus::STATUS_CANCELED:
926  status_str = "<font color=orange>canceled</color>";
927  break;
928 
929  case action_msgs::msg::GoalStatus::STATUS_ABORTED:
930  status_str = "<font color=red>aborted</color>";
931  break;
932 
933  case action_msgs::msg::GoalStatus::STATUS_UNKNOWN:
934  status_str = "unknown";
935  break;
936 
937  default:
938  status_str = "inactive";
939  break;
940  }
941  return QString(
942  std::string(
943  "<table><tr><td width=100><b>Feedback:</b></td><td>" +
944  status_str + "</td></tr></table>").c_str());
945 }
946 
947 inline QString
948 Nav2Panel::getNavToPoseFeedbackLabel(nav2_msgs::action::NavigateToPose::Feedback msg)
949 {
950  return QString(std::string("<table>" + toLabel(msg) + "</table>").c_str());
951 }
952 
953 inline QString
954 Nav2Panel::getNavThroughPosesFeedbackLabel(nav2_msgs::action::NavigateThroughPoses::Feedback msg)
955 {
956  return QString(
957  std::string(
958  "<table><tr><td width=150>Poses remaining:</td><td>" +
959  std::to_string(msg.number_of_poses_remaining) +
960  "</td></tr>" + toLabel(msg) + "</table>").c_str());
961 }
962 
963 template<typename T>
964 inline std::string Nav2Panel::toLabel(T & msg)
965 {
966  return std::string(
967  "<tr><td width=150>ETA:</td><td>" +
968  toString(rclcpp::Duration(msg.estimated_time_remaining).seconds(), 0) + " s"
969  "</td></tr><tr><td width=150>Distance remaining:</td><td>" +
970  toString(msg.distance_remaining, 2) + " m"
971  "</td></tr><tr><td width=150>Time taken:</td><td>" +
972  toString(rclcpp::Duration(msg.navigation_time).seconds(), 0) + " s"
973  "</td></tr><tr><td width=150>Recoveries:</td><td>" +
974  std::to_string(msg.number_of_recoveries) +
975  "</td></tr>");
976 }
977 
978 inline std::string
979 Nav2Panel::toString(double val, int precision)
980 {
981  std::ostringstream out;
982  out.precision(precision);
983  out << std::fixed << val;
984  return out.str();
985 }
986 
987 } // namespace nav2_rviz_plugins
988 
989 #include <pluginlib/class_list_macros.hpp> // NOLINT
990 PLUGINLIB_EXPORT_CLASS(nav2_rviz_plugins::Nav2Panel, rviz_common::Panel)
bool pause(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make pause service call.
bool reset(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make reset service call.
bool startup(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make start up service call.
bool resume(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make resume service call.
Panel to interface to the nav2 stack.
Definition: nav2_panel.hpp:47