Nav2 Navigation Stack - rolling  main
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 #include <QHBoxLayout>
20 #include <QTextEdit>
21 #include <QCheckBox>
22 
23 #include <ctype.h>
24 #include <memory>
25 #include <vector>
26 #include <utility>
27 #include <chrono>
28 #include <string>
29 
30 #include "nav2_rviz_plugins/goal_common.hpp"
31 #include "nav2_rviz_plugins/utils.hpp"
32 #include "rclcpp/rclcpp.hpp"
33 #include "rviz_common/display_context.hpp"
34 #include "rviz_common/load_resource.hpp"
35 #include "ament_index_cpp/get_package_share_directory.hpp"
36 #include "yaml-cpp/yaml.h"
37 #include "geometry_msgs/msg/pose.hpp"
38 
39 using namespace std::chrono_literals;
40 
41 namespace nav2_rviz_plugins
42 {
43 using nav2_util::geometry_utils::orientationAroundZAxis;
44 
45 // Define global GoalPoseUpdater so that the nav2 GoalTool plugin can access to update goal pose
46 GoalPoseUpdater GoalUpdater;
47 
48 Nav2Panel::Nav2Panel(QWidget * parent)
49 : Panel(parent),
50  server_timeout_(100)
51 {
52  // Create the control button and its tooltip
53 
54  start_reset_button_ = new QPushButton;
55  pause_resume_button_ = new QPushButton;
56  navigation_mode_button_ = new QPushButton;
57  save_waypoints_button_ = new QPushButton;
58  load_waypoints_button_ = new QPushButton;
59  pause_waypoint_button_ = new QPushButton;
60  navigation_status_indicator_ = new QLabel;
61  localization_status_indicator_ = new QLabel;
62  navigation_goal_status_indicator_ = new QLabel;
63  navigation_feedback_indicator_ = new QLabel;
64  waypoint_status_indicator_ = new QLabel;
65  number_of_loops_ = new QLabel;
66  nr_of_loops_ = new QLineEdit;
67  store_initial_pose_checkbox_ = new QCheckBox("Store initial_pose");
68 
69  // Create the state machine used to present the proper control button states in the UI
70 
71  const char * startup_msg = "Configure and activate all nav2 lifecycle nodes";
72  const char * shutdown_msg = "Deactivate and cleanup all nav2 lifecycle nodes";
73  const char * cancel_msg = "Cancel navigation";
74  const char * pause_msg = "Deactivate all nav2 lifecycle nodes";
75  const char * resume_msg = "Activate all nav2 lifecycle nodes";
76  const char * single_goal_msg = "Change to waypoint / nav through poses style navigation";
77  const char * waypoint_goal_msg = "Start following waypoints";
78  const char * nft_goal_msg = "Start navigating through poses";
79  const char * cancel_waypoint_msg = "Cancel waypoint / viapoint accumulation mode";
80 
81  const QString navigation_active("<table><tr><td width=150><b>Navigation:</b></td>"
82  "<td><font color=green>active</color></td></tr></table>");
83  const QString navigation_inactive("<table><tr><td width=150><b>Navigation:</b></td>"
84  "<td>inactive</td></tr></table>");
85  const QString navigation_unknown("<table><tr><td width=150><b>Navigation:</b></td>"
86  "<td>unknown</td></tr></table>");
87  const QString localization_active("<table><tr><td width=150><b>Localization:</b></td>"
88  "<td><font color=green>active</color></td></tr></table>");
89  const QString localization_inactive("<table><tr><td width=150><b>Localization:</b></td>"
90  "<td>inactive</td></tr></table>");
91  const QString localization_unknown("<table><tr><td width=150><b>Localization:</b></td>"
92  "<td>unknown</td></tr></table>");
93 
94  navigation_status_indicator_->setText(navigation_unknown);
95  localization_status_indicator_->setText(localization_unknown);
96  navigation_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel());
97  number_of_loops_->setText("Num of loops");
98  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
99  navigation_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
100  localization_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
101  navigation_goal_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
102  navigation_feedback_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
103  waypoint_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
104 
105  pre_initial_ = new QState();
106  pre_initial_->setObjectName("pre_initial");
107  pre_initial_->assignProperty(start_reset_button_, "text", "Startup");
108  pre_initial_->assignProperty(start_reset_button_, "enabled", false);
109 
110  pre_initial_->assignProperty(pause_resume_button_, "text", "Pause");
111  pre_initial_->assignProperty(pause_resume_button_, "enabled", false);
112 
113  pre_initial_->assignProperty(save_waypoints_button_, "text", "Save WPs");
114  pre_initial_->assignProperty(save_waypoints_button_, "enabled", false);
115 
116  pre_initial_->assignProperty(load_waypoints_button_, "text", "Load WPs");
117  pre_initial_->assignProperty(load_waypoints_button_, "enabled", false);
118 
119  pre_initial_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
120  pre_initial_->assignProperty(pause_waypoint_button_, "enabled", false);
121 
122  pre_initial_->assignProperty(nr_of_loops_, "text", "0");
123  pre_initial_->assignProperty(nr_of_loops_, "enabled", false);
124 
125  pre_initial_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
126 
127  pre_initial_->assignProperty(
128  navigation_mode_button_, "text",
129  "Waypoint / Nav Through Poses Mode");
130  pre_initial_->assignProperty(navigation_mode_button_, "enabled", false);
131 
132  initial_ = new QState();
133  initial_->setObjectName("initial");
134  initial_->assignProperty(start_reset_button_, "text", "Startup");
135  initial_->assignProperty(start_reset_button_, "toolTip", startup_msg);
136  initial_->assignProperty(start_reset_button_, "enabled", true);
137 
138  initial_->assignProperty(pause_resume_button_, "text", "Pause");
139  initial_->assignProperty(pause_resume_button_, "enabled", false);
140 
141  initial_->assignProperty(navigation_mode_button_, "text", "Waypoint / Nav Through Poses Mode");
142  initial_->assignProperty(navigation_mode_button_, "enabled", false);
143 
144  initial_->assignProperty(save_waypoints_button_, "text", "Save WPs");
145  initial_->assignProperty(save_waypoints_button_, "enabled", false);
146 
147  initial_->assignProperty(load_waypoints_button_, "text", "Load WPs");
148  initial_->assignProperty(load_waypoints_button_, "enabled", false);
149 
150  initial_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
151  initial_->assignProperty(pause_waypoint_button_, "enabled", false);
152 
153  initial_->assignProperty(nr_of_loops_, "text", "0");
154  initial_->assignProperty(nr_of_loops_, "enabled", false);
155 
156  initial_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
157 
158  // State entered when navigate_to_pose action is not active
159  idle_ = new QState();
160  idle_->setObjectName("idle");
161  idle_->assignProperty(start_reset_button_, "text", "Reset");
162  idle_->assignProperty(start_reset_button_, "toolTip", shutdown_msg);
163  idle_->assignProperty(start_reset_button_, "enabled", true);
164 
165  idle_->assignProperty(pause_resume_button_, "text", "Pause");
166  idle_->assignProperty(pause_resume_button_, "enabled", true);
167  idle_->assignProperty(pause_resume_button_, "toolTip", pause_msg);
168 
169  idle_->assignProperty(navigation_mode_button_, "text", "Waypoint / Nav Through Poses Mode");
170  idle_->assignProperty(navigation_mode_button_, "enabled", true);
171  idle_->assignProperty(navigation_mode_button_, "toolTip", single_goal_msg);
172 
173  idle_->assignProperty(save_waypoints_button_, "text", "Save WPs");
174  idle_->assignProperty(save_waypoints_button_, "enabled", false);
175 
176  idle_->assignProperty(load_waypoints_button_, "text", "Load WPs");
177  idle_->assignProperty(load_waypoints_button_, "enabled", false);
178 
179  idle_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
180  idle_->assignProperty(pause_waypoint_button_, "enabled", false);
181 
182  idle_->assignProperty(nr_of_loops_, "text", "0");
183  idle_->assignProperty(nr_of_loops_, "enabled", false);
184 
185  idle_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
186 
187  // State entered when navigate_to_pose action is not active
188  accumulating_ = new QState();
189  accumulating_->setObjectName("accumulating");
190  accumulating_->assignProperty(start_reset_button_, "text", "Cancel Accumulation");
191  accumulating_->assignProperty(start_reset_button_, "toolTip", cancel_waypoint_msg);
192  accumulating_->assignProperty(start_reset_button_, "enabled", true);
193 
194  accumulating_->assignProperty(pause_resume_button_, "text", "Start Nav Through Poses");
195  accumulating_->assignProperty(pause_resume_button_, "enabled", true);
196  accumulating_->assignProperty(pause_resume_button_, "toolTip", nft_goal_msg);
197 
198  accumulating_->assignProperty(navigation_mode_button_, "text", "Start Waypoint Following");
199  accumulating_->assignProperty(navigation_mode_button_, "enabled", true);
200  accumulating_->assignProperty(navigation_mode_button_, "toolTip", waypoint_goal_msg);
201 
202  accumulating_->assignProperty(save_waypoints_button_, "text", "Save WPs");
203  accumulating_->assignProperty(save_waypoints_button_, "enabled", true);
204 
205  accumulating_->assignProperty(load_waypoints_button_, "text", "Load WPs");
206  accumulating_->assignProperty(load_waypoints_button_, "enabled", true);
207 
208  accumulating_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
209  accumulating_->assignProperty(pause_waypoint_button_, "enabled", false);
210 
211  accumulating_->assignProperty(nr_of_loops_, "text", QString::fromStdString(loop_no_));
212  accumulating_->assignProperty(nr_of_loops_, "enabled", true);
213  accumulating_->assignProperty(store_initial_pose_checkbox_, "enabled", true);
214 
215  accumulated_wp_ = new QState();
216  accumulated_wp_->setObjectName("accumulated_wp");
217  accumulated_wp_->assignProperty(start_reset_button_, "text", "Cancel");
218  accumulated_wp_->assignProperty(start_reset_button_, "toolTip", cancel_msg);
219  accumulated_wp_->assignProperty(start_reset_button_, "enabled", true);
220 
221  accumulated_wp_->assignProperty(pause_resume_button_, "text", "Start Nav Through Poses");
222  accumulated_wp_->assignProperty(pause_resume_button_, "enabled", false);
223  accumulated_wp_->assignProperty(pause_resume_button_, "toolTip", nft_goal_msg);
224 
225  accumulated_wp_->assignProperty(navigation_mode_button_, "text", "Start Waypoint Following");
226  accumulated_wp_->assignProperty(navigation_mode_button_, "enabled", false);
227  accumulated_wp_->assignProperty(navigation_mode_button_, "toolTip", waypoint_goal_msg);
228 
229  accumulated_wp_->assignProperty(save_waypoints_button_, "text", "Save WPs");
230  accumulated_wp_->assignProperty(save_waypoints_button_, "enabled", false);
231 
232  accumulated_wp_->assignProperty(load_waypoints_button_, "text", "Load WPs");
233  accumulated_wp_->assignProperty(load_waypoints_button_, "enabled", false);
234 
235  accumulated_wp_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
236  accumulated_wp_->assignProperty(pause_waypoint_button_, "enabled", true);
237 
238  accumulated_wp_->assignProperty(nr_of_loops_, "enabled", false);
239  accumulated_wp_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
240 
241  accumulated_nav_through_poses_ = new QState();
242  accumulated_nav_through_poses_->setObjectName("accumulated_nav_through_poses");
243  accumulated_nav_through_poses_->assignProperty(start_reset_button_, "text", "Cancel");
244  accumulated_nav_through_poses_->assignProperty(start_reset_button_, "toolTip", cancel_msg);
245 
246  accumulated_nav_through_poses_->assignProperty(save_waypoints_button_, "text", "Save WPs");
247  accumulated_nav_through_poses_->assignProperty(save_waypoints_button_, "enabled", false);
248 
249  accumulated_nav_through_poses_->assignProperty(load_waypoints_button_, "text", "Load WPs");
250  accumulated_nav_through_poses_->assignProperty(load_waypoints_button_, "enabled", false);
251 
252  accumulated_nav_through_poses_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
253  accumulated_nav_through_poses_->assignProperty(pause_waypoint_button_, "enabled", false);
254 
255  accumulated_nav_through_poses_->assignProperty(nr_of_loops_, "enabled", false);
256 
257  accumulated_nav_through_poses_->assignProperty(start_reset_button_, "enabled", true);
258  accumulated_nav_through_poses_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
259 
260  accumulated_nav_through_poses_->assignProperty(
261  pause_resume_button_, "text",
262  "Start Nav Through Poses");
263  accumulated_nav_through_poses_->assignProperty(pause_resume_button_, "enabled", false);
264  accumulated_nav_through_poses_->assignProperty(pause_resume_button_, "toolTip", nft_goal_msg);
265 
266  accumulated_nav_through_poses_->assignProperty(
267  navigation_mode_button_, "text",
268  "Start Waypoint Following");
269  accumulated_nav_through_poses_->assignProperty(navigation_mode_button_, "enabled", false);
270  accumulated_nav_through_poses_->assignProperty(
271  navigation_mode_button_, "toolTip",
272  waypoint_goal_msg);
273 
274  accumulated_nav_through_poses_->assignProperty(
275  nr_of_loops_, "text",
276  QString::fromStdString(loop_no_));
277  accumulated_nav_through_poses_->assignProperty(nr_of_loops_, "enabled", false);
278  accumulated_nav_through_poses_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
279 
280  // State entered to cancel the navigate_to_pose action
281  canceled_ = new QState();
282  canceled_->setObjectName("canceled");
283 
284  // State entered to reset the nav2 lifecycle nodes
285  reset_ = new QState();
286  reset_->setObjectName("reset");
287  // State entered while the navigate_to_pose action is active
288  running_ = new QState();
289  running_->setObjectName("running");
290  running_->assignProperty(start_reset_button_, "text", "Cancel");
291  running_->assignProperty(start_reset_button_, "toolTip", cancel_msg);
292 
293  running_->assignProperty(pause_resume_button_, "text", "Pause");
294  running_->assignProperty(pause_resume_button_, "enabled", false);
295 
296  running_->assignProperty(navigation_mode_button_, "text", "Waypoint mode");
297  running_->assignProperty(navigation_mode_button_, "enabled", false);
298 
299  running_->assignProperty(save_waypoints_button_, "text", "Save WPs");
300  running_->assignProperty(save_waypoints_button_, "enabled", false);
301 
302  running_->assignProperty(load_waypoints_button_, "text", "Load WPs");
303  running_->assignProperty(load_waypoints_button_, "enabled", false);
304 
305  running_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
306  running_->assignProperty(pause_waypoint_button_, "enabled", false);
307 
308  running_->assignProperty(nr_of_loops_, "text", "0");
309  running_->assignProperty(nr_of_loops_, "enabled", false);
310 
311  running_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
312 
313  // State entered when pause is requested
314  paused_ = new QState();
315  paused_->setObjectName("pausing");
316  paused_->assignProperty(start_reset_button_, "text", "Reset");
317  paused_->assignProperty(start_reset_button_, "toolTip", shutdown_msg);
318 
319  paused_->assignProperty(pause_resume_button_, "text", "Resume");
320  paused_->assignProperty(pause_resume_button_, "toolTip", resume_msg);
321  paused_->assignProperty(pause_resume_button_, "enabled", true);
322 
323  paused_->assignProperty(navigation_mode_button_, "text", "");
324  paused_->assignProperty(navigation_mode_button_, "enabled", false);
325 
326  paused_->assignProperty(save_waypoints_button_, "text", "Save WPs");
327  paused_->assignProperty(save_waypoints_button_, "enabled", false);
328 
329  paused_->assignProperty(load_waypoints_button_, "text", "Load WPs");
330  paused_->assignProperty(load_waypoints_button_, "enabled", false);
331 
332  paused_->assignProperty(pause_waypoint_button_, "text", "Pause WP");
333  paused_->assignProperty(pause_waypoint_button_, "enabled", false);
334 
335  paused_->assignProperty(nr_of_loops_, "enabled", false);
336 
337  paused_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
338 
339  // State entered to resume the nav2 lifecycle nodes
340  resumed_ = new QState();
341  resumed_->setObjectName("resuming");
342 
343  // States entered to pause and Resume WPs
344  resumed_wp_ = new QState();
345  resumed_wp_->setObjectName("running");
346  resumed_wp_->assignProperty(start_reset_button_, "text", "Cancel");
347  resumed_wp_->assignProperty(start_reset_button_, "toolTip", cancel_msg);
348 
349  resumed_wp_->assignProperty(pause_resume_button_, "text", "Start Nav Through Poses");
350  resumed_wp_->assignProperty(pause_resume_button_, "enabled", false);
351 
352  resumed_wp_->assignProperty(navigation_mode_button_, "text", "Start Waypoint Following");
353  resumed_wp_->assignProperty(navigation_mode_button_, "enabled", false);
354 
355  resumed_wp_->assignProperty(save_waypoints_button_, "text", "Save WPs");
356  resumed_wp_->assignProperty(save_waypoints_button_, "enabled", true);
357 
358  resumed_wp_->assignProperty(load_waypoints_button_, "text", "Load WPs");
359  resumed_wp_->assignProperty(load_waypoints_button_, "enabled", false);
360 
361  resumed_wp_->assignProperty(pause_waypoint_button_, "text", "Resume WP");
362  resumed_wp_->assignProperty(pause_waypoint_button_, "enabled", true);
363 
364  resumed_wp_->assignProperty(nr_of_loops_, "enabled", false);
365  resumed_wp_->assignProperty(store_initial_pose_checkbox_, "enabled", false);
366 
367  QObject::connect(initial_, SIGNAL(exited()), this, SLOT(onStartup()));
368  QObject::connect(canceled_, SIGNAL(exited()), this, SLOT(onCancel()));
369  QObject::connect(reset_, SIGNAL(exited()), this, SLOT(onShutdown()));
370  QObject::connect(paused_, SIGNAL(entered()), this, SLOT(onPause()));
371  QObject::connect(resumed_, SIGNAL(exited()), this, SLOT(onResume()));
372  QObject::connect(accumulating_, SIGNAL(entered()), this, SLOT(onAccumulating()));
373  QObject::connect(accumulated_wp_, SIGNAL(entered()), this, SLOT(onAccumulatedWp()));
374  QObject::connect(resumed_wp_, SIGNAL(entered()), this, SLOT(onResumedWp()));
375  QObject::connect(
376  accumulated_nav_through_poses_, SIGNAL(entered()), this,
377  SLOT(onAccumulatedNTP()));
378  QObject::connect(
379  save_waypoints_button_,
380  &QPushButton::released,
381  this, &Nav2Panel::handleGoalSaver);
382  QObject::connect(
383  load_waypoints_button_,
384  &QPushButton::released,
385  this,
386  &Nav2Panel::handleGoalLoader);
387  QObject::connect(
388  nr_of_loops_,
389  &QLineEdit::editingFinished,
390  this,
391  &Nav2Panel::loophandler);
392  QObject::connect(
393  store_initial_pose_checkbox_,
394  &QCheckBox::stateChanged,
395  this,
396  &Nav2Panel::initialStateHandler);
397 
398  // Start/Reset button click transitions
399  initial_->addTransition(start_reset_button_, SIGNAL(clicked()), idle_);
400  idle_->addTransition(start_reset_button_, SIGNAL(clicked()), reset_);
401  running_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
402  paused_->addTransition(start_reset_button_, SIGNAL(clicked()), reset_);
403  idle_->addTransition(navigation_mode_button_, SIGNAL(clicked()), accumulating_);
404  accumulating_->addTransition(navigation_mode_button_, SIGNAL(clicked()), accumulated_wp_);
405  accumulating_->addTransition(
406  pause_resume_button_, SIGNAL(
407  clicked()), accumulated_nav_through_poses_);
408  accumulating_->addTransition(start_reset_button_, SIGNAL(clicked()), idle_);
409  accumulated_wp_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
410  accumulated_nav_through_poses_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
411 
412  // Internal state transitions
413  canceled_->addTransition(canceled_, SIGNAL(entered()), idle_);
414  reset_->addTransition(reset_, SIGNAL(entered()), initial_);
415  resumed_->addTransition(resumed_, SIGNAL(entered()), idle_);
416 
417  // Pause/Resume button click transitions
418  idle_->addTransition(pause_resume_button_, SIGNAL(clicked()), paused_);
419  paused_->addTransition(pause_resume_button_, SIGNAL(clicked()), resumed_);
420 
421  // Pause/Resume button waypoint transition
422  accumulated_wp_->addTransition(pause_waypoint_button_, SIGNAL(clicked()), resumed_wp_);
423  resumed_wp_->addTransition(pause_waypoint_button_, SIGNAL(clicked()), accumulated_wp_);
424  resumed_wp_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
425 
426  // ROSAction Transitions: So when actions are updated remotely (failing, succeeding, etc)
427  // the state of the application will also update. This means that if in the processing
428  // states and then goes inactive, move back to the idle state. Vice versa as well.
429  ROSActionQTransition * idleTransition = new ROSActionQTransition(QActionState::INACTIVE);
430  idleTransition->setTargetState(running_);
431  idle_->addTransition(idleTransition);
432 
433  ROSActionQTransition * runningTransition = new ROSActionQTransition(QActionState::ACTIVE);
434  runningTransition->setTargetState(idle_);
435  running_->addTransition(runningTransition);
436 
437  ROSActionQTransition * idleAccumulatedWpTransition =
438  new ROSActionQTransition(QActionState::INACTIVE);
439  idleAccumulatedWpTransition->setTargetState(accumulated_wp_);
440  idle_->addTransition(idleAccumulatedWpTransition);
441 
442  ROSActionQTransition * accumulatedWpTransition = new ROSActionQTransition(QActionState::ACTIVE);
443  accumulatedWpTransition->setTargetState(accumulating_);
444  accumulated_wp_->addTransition(accumulatedWpTransition);
445 
446  ROSActionQTransition * idleAccumulatedNTPTransition =
447  new ROSActionQTransition(QActionState::INACTIVE);
448  idleAccumulatedNTPTransition->setTargetState(accumulated_nav_through_poses_);
449  idle_->addTransition(idleAccumulatedNTPTransition);
450 
451  ROSActionQTransition * accumulatedNTPTransition = new ROSActionQTransition(QActionState::ACTIVE);
452  accumulatedNTPTransition->setTargetState(idle_);
453  accumulated_nav_through_poses_->addTransition(accumulatedNTPTransition);
454 
455  auto options = rclcpp::NodeOptions().arguments(
456  {"--ros-args", "--remap", "__node:=rviz_navigation_dialog_action_client", "--"});
457  client_node_ = std::make_shared<rclcpp::Node>("_", options);
458 
459  client_nav_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
460  "lifecycle_manager_navigation", client_node_);
461  client_loc_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
462  "lifecycle_manager_localization", client_node_);
463  initial_thread_ = new InitialThread(client_nav_, client_loc_);
464  connect(initial_thread_, &InitialThread::finished, initial_thread_, &QObject::deleteLater);
465 
466  QSignalTransition * activeSignal = new QSignalTransition(
467  initial_thread_,
468  &InitialThread::navigationActive);
469  activeSignal->setTargetState(idle_);
470  pre_initial_->addTransition(activeSignal);
471  QSignalTransition * inactiveSignal = new QSignalTransition(
472  initial_thread_,
473  &InitialThread::navigationInactive);
474  inactiveSignal->setTargetState(initial_);
475  pre_initial_->addTransition(inactiveSignal);
476 
477  QObject::connect(
478  initial_thread_, &InitialThread::navigationActive,
479  [this, navigation_active] {
480  navigation_status_indicator_->setText(navigation_active);
481  });
482  QObject::connect(
483  initial_thread_, &InitialThread::navigationInactive,
484  [this, navigation_inactive] {
485  navigation_status_indicator_->setText(navigation_inactive);
486  navigation_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel());
487  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
488  });
489  QObject::connect(
490  initial_thread_, &InitialThread::localizationActive,
491  [this, localization_active] {
492  localization_status_indicator_->setText(localization_active);
493  });
494  QObject::connect(
495  initial_thread_, &InitialThread::localizationInactive,
496  [this, localization_inactive] {
497  localization_status_indicator_->setText(localization_inactive);
498  });
499 
500  state_machine_.addState(pre_initial_);
501  state_machine_.addState(initial_);
502  state_machine_.addState(idle_);
503  state_machine_.addState(running_);
504  state_machine_.addState(canceled_);
505  state_machine_.addState(reset_);
506  state_machine_.addState(paused_);
507  state_machine_.addState(resumed_);
508  state_machine_.addState(accumulating_);
509  state_machine_.addState(accumulated_wp_);
510  state_machine_.addState(accumulated_nav_through_poses_);
511  state_machine_.addState(resumed_wp_);
512 
513  state_machine_.setInitialState(pre_initial_);
514 
515  // delay starting initial thread until state machine has started or a race occurs
516  QObject::connect(&state_machine_, SIGNAL(started()), this, SLOT(startThread()));
517  state_machine_.start();
518 
519  // Lay out the items in the panel
520  QVBoxLayout * main_layout = new QVBoxLayout;
521  QHBoxLayout * side_layout = new QHBoxLayout;
522  QVBoxLayout * status_layout = new QVBoxLayout;
523  QHBoxLayout * logo_layout = new QHBoxLayout;
524  QVBoxLayout * group_box_layout = new QVBoxLayout;
525 
526  QGroupBox * groupBox = new QGroupBox(tr("Tools for WP-Following"));
527  imgDisplayLabel_ = new QLabel("");
528  imgDisplayLabel_->setPixmap(
529  rviz_common::loadPixmap("package://nav2_rviz_plugins/icons/classes/nav2_logo_small.png"));
530 
531  status_layout->addWidget(navigation_status_indicator_);
532  status_layout->addWidget(localization_status_indicator_);
533  status_layout->addWidget(navigation_goal_status_indicator_);
534 
535  logo_layout->addWidget(imgDisplayLabel_, 5, Qt::AlignRight);
536 
537  side_layout->addLayout(status_layout);
538  side_layout->addLayout(logo_layout);
539 
540  main_layout->addLayout(side_layout);
541  main_layout->addWidget(navigation_feedback_indicator_);
542  main_layout->addWidget(waypoint_status_indicator_);
543  main_layout->addWidget(pause_resume_button_);
544  main_layout->addWidget(start_reset_button_);
545  main_layout->addWidget(navigation_mode_button_);
546 
547  QHBoxLayout * group_box_l1_layout = new QHBoxLayout;
548  QHBoxLayout * group_box_l2_layout = new QHBoxLayout;
549 
550  group_box_l1_layout->addWidget(save_waypoints_button_);
551  group_box_l1_layout->addWidget(load_waypoints_button_);
552  group_box_l1_layout->addWidget(pause_waypoint_button_);
553 
554  group_box_l2_layout->addWidget(number_of_loops_);
555  group_box_l2_layout->addWidget(nr_of_loops_);
556  group_box_l2_layout->addWidget(store_initial_pose_checkbox_);
557 
558  group_box_layout->addLayout(group_box_l1_layout);
559  group_box_layout->addLayout(group_box_l2_layout);
560 
561  groupBox->setLayout(group_box_layout);
562 
563  main_layout->addWidget(groupBox);
564  main_layout->setContentsMargins(10, 10, 10, 10);
565  setLayout(main_layout);
566 
567  navigation_action_client_ =
568  rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
569  client_node_,
570  "navigate_to_pose");
571  waypoint_follower_action_client_ =
572  rclcpp_action::create_client<nav2_msgs::action::FollowWaypoints>(
573  client_node_,
574  "follow_waypoints");
575  nav_through_poses_action_client_ =
576  rclcpp_action::create_client<nav2_msgs::action::NavigateThroughPoses>(
577  client_node_,
578  "navigate_through_poses");
579 
580  // Setting up tf for initial pose
581  tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(client_node_->get_clock());
582  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
583  client_node_->get_node_base_interface(),
584  client_node_->get_node_timers_interface());
585  tf2_buffer_->setCreateTimerInterface(timer_interface);
586  transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);
587 
588  navigation_goal_ = nav2_msgs::action::NavigateToPose::Goal();
589  waypoint_follower_goal_ = nav2_msgs::action::FollowWaypoints::Goal();
590  nav_through_poses_goal_ = nav2_msgs::action::NavigateThroughPoses::Goal();
591 
592  wp_navigation_markers_pub_ =
593  client_node_->create_publisher<visualization_msgs::msg::MarkerArray>(
594  "waypoints",
595  rclcpp::QoS(1).transient_local());
596 
597  QObject::connect(
598  &GoalUpdater, SIGNAL(updateGoal(double,double,double,QString)), // NOLINT
599  this, SLOT(onNewGoal(double,double,double,QString))); // NOLINT
600 }
601 
602 Nav2Panel::~Nav2Panel()
603 {
604 }
605 
606 void Nav2Panel::initialStateHandler()
607 {
608  if (store_initial_pose_checkbox_->isChecked()) {
609  store_initial_pose_ = true;
610 
611  } else {
612  store_initial_pose_ = false;
613  }
614 }
615 
616 bool Nav2Panel::isLoopValueValid(std::string & loop_value)
617 {
618  // Check for just empty space
619  if (loop_value.empty()) {
620  std::cout << "Loop value cannot be set to empty, setting to 0" << std::endl;
621  loop_value = "0";
622  nr_of_loops_->setText("0");
623  return true;
624  }
625 
626  // Check for any chars or spaces in the string
627  for (char & c : loop_value) {
628  if (isalpha(c) || isspace(c) || ispunct(c)) {
629  waypoint_status_indicator_->setText(
630  "<b> Note: </b> Set a valid value for the loop");
631  std::cout << "Set a valid value for the loop, check for alphabets and spaces" << std::endl;
632  navigation_mode_button_->setEnabled(false);
633  return false;
634  }
635  }
636 
637  try {
638  stoi(loop_value);
639  } catch (std::invalid_argument const & ex) {
640  // Handling special symbols
641  waypoint_status_indicator_->setText("<b> Note: </b> Set a valid value for the loop");
642  navigation_mode_button_->setEnabled(false);
643  return false;
644  } catch (std::out_of_range const & ex) {
645  // Handling out of range values
646  waypoint_status_indicator_->setText(
647  "<b> Note: </b> Loop value out of range, setting max possible value"
648  );
649  loop_value = std::to_string(std::numeric_limits<int>::max());
650  nr_of_loops_->setText(QString::fromStdString(loop_value));
651  }
652  return true;
653 }
654 
655 void Nav2Panel::loophandler()
656 {
657  loop_no_ = nr_of_loops_->displayText().toStdString();
658 
659  // Sanity check for the loop value
660  if (!isLoopValueValid(loop_no_)) {
661  return;
662  }
663 
664  // Enabling the start_waypoint_follow button, if disabled.
665  navigation_mode_button_->setEnabled(true);
666 
667  // Disabling nav_through_poses button
668  if (!loop_no_.empty() && stoi(loop_no_) > 0) {
669  pause_resume_button_->setEnabled(false);
670  } else {
671  pause_resume_button_->setEnabled(true);
672  }
673 }
674 
675 void Nav2Panel::handleGoalLoader()
676 {
677  acummulated_poses_ = nav_msgs::msg::Goals();
678 
679  std::cout << "Loading Waypoints!" << std::endl;
680 
681  QString file = QFileDialog::getOpenFileName(
682  this,
683  tr("Open File"), "",
684  tr("yaml(*.yaml);;All Files (*)"));
685 
686  YAML::Node available_waypoints;
687 
688  try {
689  available_waypoints = YAML::LoadFile(file.toStdString());
690  } catch (const std::exception & ex) {
691  std::cout << ex.what() << ", please select a valid file" << std::endl;
692  updateWpNavigationMarkers();
693  return;
694  }
695 
696  const YAML::Node & waypoint_iter = available_waypoints["waypoints"];
697  for (YAML::const_iterator it = waypoint_iter.begin(); it != waypoint_iter.end(); ++it) {
698  auto waypoint = waypoint_iter[it->first.as<std::string>()];
699  auto pose = waypoint["pose"].as<std::vector<double>>();
700  auto orientation = waypoint["orientation"].as<std::vector<double>>();
701  acummulated_poses_.goals.push_back(convert_to_msg(pose, orientation));
702  }
703 
704  // Publishing Waypoint Navigation marker after loading wp's
705  updateWpNavigationMarkers();
706 }
707 
708 geometry_msgs::msg::PoseStamped Nav2Panel::convert_to_msg(
709  std::vector<double> pose,
710  std::vector<double> orientation)
711 {
712  auto msg = geometry_msgs::msg::PoseStamped();
713 
714  msg.header.frame_id = "map";
715  // msg.header.stamp = client_node_->now(); // client node doesn't respect sim time yet
716 
717  msg.pose.position.x = pose[0];
718  msg.pose.position.y = pose[1];
719  msg.pose.position.z = pose[2];
720 
721  msg.pose.orientation.w = orientation[0];
722  msg.pose.orientation.x = orientation[1];
723  msg.pose.orientation.y = orientation[2];
724  msg.pose.orientation.z = orientation[3];
725 
726  return msg;
727 }
728 
729 void Nav2Panel::handleGoalSaver()
730 {
731 // Check if the waypoints are accumulated
732 
733  if (acummulated_poses_.goals.empty()) {
734  std::cout << "No accumulated Points to Save!" << std::endl;
735  return;
736  } else {
737  std::cout << "Saving Waypoints!" << std::endl;
738  }
739 
740  YAML::Emitter out;
741  out << YAML::BeginMap;
742  out << YAML::Key << "waypoints";
743  out << YAML::BeginMap;
744 
745  // Save WPs to data structure
746  for (unsigned int i = 0; i < acummulated_poses_.goals.size(); ++i) {
747  out << YAML::Key << "waypoint" + std::to_string(i);
748  out << YAML::BeginMap;
749  out << YAML::Key << "pose";
750  std::vector<double> pose =
751  {acummulated_poses_.goals[i].pose.position.x, acummulated_poses_.goals[i].pose.position.y,
752  acummulated_poses_.goals[i].pose.position.z};
753  out << YAML::Value << pose;
754  out << YAML::Key << "orientation";
755  std::vector<double> orientation =
756  {acummulated_poses_.goals[i].pose.orientation.w, acummulated_poses_.goals[i].pose.orientation.x,
757  acummulated_poses_.goals[i].pose.orientation.y,
758  acummulated_poses_.goals[i].pose.orientation.z};
759  out << YAML::Value << orientation;
760  out << YAML::EndMap;
761  }
762 
763  // open dialog to save it in a file
764  QString file = QFileDialog::getSaveFileName(
765  this,
766  tr("Open File"), "",
767  tr("yaml(*.yaml);;All Files (*)"));
768 
769  if (!file.toStdString().empty()) {
770  std::ofstream fout(file.toStdString() + ".yaml");
771  fout << out.c_str();
772  std::cout << "Saving waypoints succeeded" << std::endl;
773  } else {
774  std::cout << "Saving waypoints aborted" << std::endl;
775  }
776 }
777 
778 void
779 Nav2Panel::onInitialize()
780 {
781  node_ptr_ = getDisplayContext()->getRosNodeAbstraction().lock();
782  if (node_ptr_ == nullptr) {
783  // The node no longer exists, so just don't initialize
784  RCLCPP_ERROR(
785  rclcpp::get_logger("nav2_panel"),
786  "Underlying ROS node no longer exists, initialization failed");
787  return;
788  }
789  rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
790 
791  // declaring parameter to get the base frame
792  node->declare_parameter("base_frame", rclcpp::ParameterValue(std::string("base_footprint")));
793  node->get_parameter("base_frame", base_frame_);
794 
795  // create action feedback subscribers
796  navigation_feedback_sub_ =
797  node->create_subscription<nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage>(
798  "navigate_to_pose/_action/feedback",
799  rclcpp::SystemDefaultsQoS(),
800  [this](const nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage::SharedPtr msg) {
801  if (stoi(nr_of_loops_->displayText().toStdString()) > 0) {
802  if (goal_index_ == 0 && !loop_counter_stop_) {
803  loop_count_++;
804  loop_counter_stop_ = true;
805  }
806  if (goal_index_ != 0) {
807  loop_counter_stop_ = false;
808  }
809  navigation_feedback_indicator_->setText(
810  getNavToPoseFeedbackLabel(msg->feedback) + QString(
811  std::string(
812  "</td></tr><tr><td width=150>Waypoint:</td><td>" +
813  toString(goal_index_ + 1)).c_str()) + QString(
814  std::string(
815  "</td></tr><tr><td width=150>Loop:</td><td>" +
816  toString(loop_count_)).c_str()));
817  } else {
818  navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel(msg->feedback));
819  }
820  });
821  nav_through_poses_feedback_sub_ =
822  node->create_subscription<nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage>(
823  "navigate_through_poses/_action/feedback",
824  rclcpp::SystemDefaultsQoS(),
825  [this](const nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage::SharedPtr msg) {
826  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel(msg->feedback));
827  });
828 
829  // create action goal status subscribers
830  navigation_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
831  "navigate_to_pose/_action/status",
832  rclcpp::SystemDefaultsQoS(),
833  [this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
834  navigation_goal_status_indicator_->setText(
835  nav2_rviz_plugins::getGoalStatusLabel("Feedback", msg->status_list.back().status));
836  // Clearing all the stored values once reaching the final goal
837  if (
838  loop_count_ == stoi(nr_of_loops_->displayText().toStdString()) &&
839  goal_index_ == static_cast<int>(store_poses_.goals.size()) - 1 &&
840  msg->status_list.back().status == action_msgs::msg::GoalStatus::STATUS_SUCCEEDED)
841  {
842  store_poses_ = nav_msgs::msg::Goals();
843  waypoint_status_indicator_->clear();
844  loop_no_ = "0";
845  loop_count_ = 0;
846  navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel());
847  }
848  });
849  nav_through_poses_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
850  "navigate_through_poses/_action/status",
851  rclcpp::SystemDefaultsQoS(),
852  [this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
853  navigation_goal_status_indicator_->setText(
854  nav2_rviz_plugins::getGoalStatusLabel("Feedback", msg->status_list.back().status));
855  if (msg->status_list.back().status != action_msgs::msg::GoalStatus::STATUS_EXECUTING) {
856  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
857  }
858  });
859 }
860 
861 void
862 Nav2Panel::startThread()
863 {
864  // start initial thread now that state machine is started
865  initial_thread_->start();
866 }
867 
868 void
869 Nav2Panel::onPause()
870 {
871  QFuture<void> futureNav =
872  QtConcurrent::run(
873  std::bind(
875  client_nav_.get(), std::placeholders::_1), server_timeout_);
876  QFuture<void> futureLoc =
877  QtConcurrent::run(
878  std::bind(
880  client_loc_.get(), std::placeholders::_1), server_timeout_);
881 }
882 
883 void
884 Nav2Panel::onResume()
885 {
886  QFuture<void> futureNav =
887  QtConcurrent::run(
888  std::bind(
890  client_nav_.get(), std::placeholders::_1), server_timeout_);
891  QFuture<void> futureLoc =
892  QtConcurrent::run(
893  std::bind(
895  client_loc_.get(), std::placeholders::_1), server_timeout_);
896 }
897 
898 void
899 Nav2Panel::onStartup()
900 {
901  QFuture<void> futureNav =
902  QtConcurrent::run(
903  std::bind(
905  client_nav_.get(), std::placeholders::_1), server_timeout_);
906  QFuture<void> futureLoc =
907  QtConcurrent::run(
908  std::bind(
910  client_loc_.get(), std::placeholders::_1), server_timeout_);
911 }
912 
913 void
914 Nav2Panel::onShutdown()
915 {
916  QFuture<void> futureNav =
917  QtConcurrent::run(
918  std::bind(
920  client_nav_.get(), std::placeholders::_1), server_timeout_);
921  QFuture<void> futureLoc =
922  QtConcurrent::run(
923  std::bind(
925  client_loc_.get(), std::placeholders::_1), server_timeout_);
926  timer_.stop();
927 }
928 
929 void
930 Nav2Panel::onCancel()
931 {
932  QFuture<void> future =
933  QtConcurrent::run(
934  std::bind(
935  &Nav2Panel::onCancelButtonPressed,
936  this));
937  waypoint_status_indicator_->clear();
938  store_poses_ = nav_msgs::msg::Goals();
939  acummulated_poses_ = nav_msgs::msg::Goals();
940 }
941 
942 void Nav2Panel::onResumedWp()
943 {
944  QFuture<void> future =
945  QtConcurrent::run(
946  std::bind(
947  &Nav2Panel::onCancelButtonPressed,
948  this));
949  acummulated_poses_ = store_poses_;
950  loop_no_ = std::to_string(
951  stoi(nr_of_loops_->displayText().toStdString()) -
952  loop_count_);
953  waypoint_status_indicator_->setText(
954  QString(std::string("<b> Note: </b> Navigation is paused.").c_str()));
955 }
956 
957 void
958 Nav2Panel::onNewGoal(double x, double y, double theta, QString frame)
959 {
960  auto pose = geometry_msgs::msg::PoseStamped();
961 
962  // pose.header.stamp = client_node_->now(); // client node doesn't respect sim time yet
963  pose.header.frame_id = frame.toStdString();
964  pose.pose.position.x = x;
965  pose.pose.position.y = y;
966  pose.pose.position.z = 0.0;
967  pose.pose.orientation = orientationAroundZAxis(theta);
968 
969  if (store_poses_.goals.empty()) {
970  if (state_machine_.configuration().contains(accumulating_)) {
971  waypoint_status_indicator_->clear();
972  acummulated_poses_.goals.push_back(pose);
973  } else {
974  acummulated_poses_ = nav_msgs::msg::Goals();
975  updateWpNavigationMarkers();
976  std::cout << "Start navigation" << std::endl;
977  startNavigation(pose);
978  }
979  } else {
980  waypoint_status_indicator_->setText(
981  QString(std::string("<b> Note: </b> Cannot set goal in pause state").c_str()));
982  }
983  updateWpNavigationMarkers();
984 }
985 
986 void
987 Nav2Panel::onCancelButtonPressed()
988 {
989  if (navigation_goal_handle_) {
990  auto future_cancel = navigation_action_client_->async_cancel_goal(navigation_goal_handle_);
991 
992  if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
993  rclcpp::FutureReturnCode::SUCCESS)
994  {
995  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel goal");
996  } else {
997  navigation_goal_handle_.reset();
998  }
999  }
1000 
1001  if (waypoint_follower_goal_handle_) {
1002  auto future_cancel =
1003  waypoint_follower_action_client_->async_cancel_goal(waypoint_follower_goal_handle_);
1004 
1005  if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
1006  rclcpp::FutureReturnCode::SUCCESS)
1007  {
1008  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel waypoint follower");
1009  } else {
1010  waypoint_follower_goal_handle_.reset();
1011  }
1012  }
1013 
1014  if (nav_through_poses_goal_handle_) {
1015  auto future_cancel =
1016  nav_through_poses_action_client_->async_cancel_goal(nav_through_poses_goal_handle_);
1017 
1018  if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
1019  rclcpp::FutureReturnCode::SUCCESS)
1020  {
1021  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel nav through pose action");
1022  } else {
1023  nav_through_poses_goal_handle_.reset();
1024  }
1025  }
1026 
1027  timer_.stop();
1028 }
1029 
1030 void
1031 Nav2Panel::onAccumulatedWp()
1032 {
1033  if (acummulated_poses_.goals.empty()) {
1034  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1035  waypoint_status_indicator_->setText(
1036  "<b> Note: </b> Uh oh! Someone forgot to select the waypoints");
1037  return;
1038  }
1039 
1040  // Sanity check for the loop value
1041  if (!isLoopValueValid(loop_no_)) {
1042  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1043  return;
1044  }
1045 
1046  // Remove any warning status at this point
1047  waypoint_status_indicator_->clear();
1048 
1049  // Disable navigation modes
1050  navigation_mode_button_->setEnabled(false);
1051  pause_resume_button_->setEnabled(false);
1052 
1055  if (store_poses_.goals.empty()) {
1056  std::cout << "Start waypoint" << std::endl;
1057 
1058  // Setting the final loop value on the text box for sanity
1059  nr_of_loops_->setText(QString::fromStdString(loop_no_));
1060 
1061  // Variable to store initial pose
1062  geometry_msgs::msg::TransformStamped init_transform;
1063 
1064  // Looking up transform to get initial pose
1065  if (store_initial_pose_) {
1066  try {
1067  init_transform = tf2_buffer_->lookupTransform(
1068  acummulated_poses_.goals[0].header.frame_id, base_frame_,
1069  tf2::TimePointZero);
1070  } catch (const tf2::TransformException & ex) {
1071  RCLCPP_INFO(
1072  client_node_->get_logger(), "Could not transform %s to %s: %s",
1073  acummulated_poses_.goals[0].header.frame_id.c_str(), base_frame_.c_str(), ex.what());
1074  return;
1075  }
1076 
1077  // Converting TransformStamped to PoseStamped
1078  geometry_msgs::msg::PoseStamped initial_pose;
1079  initial_pose.header = init_transform.header;
1080  initial_pose.pose.position.x = init_transform.transform.translation.x;
1081  initial_pose.pose.position.y = init_transform.transform.translation.y;
1082  initial_pose.pose.position.z = init_transform.transform.translation.z;
1083  initial_pose.pose.orientation.x = init_transform.transform.rotation.x;
1084  initial_pose.pose.orientation.y = init_transform.transform.rotation.y;
1085  initial_pose.pose.orientation.z = init_transform.transform.rotation.z;
1086  initial_pose.pose.orientation.w = init_transform.transform.rotation.w;
1087 
1088  // inserting the acummulated pose
1089  acummulated_poses_.goals.insert(acummulated_poses_.goals.begin(), initial_pose);
1090  updateWpNavigationMarkers();
1091  initial_pose_stored_ = true;
1092  if (loop_count_ == 0) {
1093  goal_index_ = 1;
1094  }
1095  } else if (!store_initial_pose_ && initial_pose_stored_) {
1096  acummulated_poses_.goals.erase(
1097  acummulated_poses_.goals.begin(),
1098  acummulated_poses_.goals.begin());
1099  }
1100  } else {
1101  std::cout << "Resuming waypoint" << std::endl;
1102  }
1103 
1104  startWaypointFollowing(acummulated_poses_.goals);
1105  store_poses_ = acummulated_poses_;
1106  acummulated_poses_ = nav_msgs::msg::Goals();
1107 }
1108 
1109 void
1110 Nav2Panel::onAccumulatedNTP()
1111 {
1112  std::cout << "Start navigate through poses" << std::endl;
1113  startNavThroughPoses(acummulated_poses_);
1114 }
1115 
1116 void
1117 Nav2Panel::onAccumulating()
1118 {
1119  acummulated_poses_ = nav_msgs::msg::Goals();
1120  store_poses_ = nav_msgs::msg::Goals();
1121  loop_count_ = 0;
1122  loop_no_ = "0";
1123  initial_pose_stored_ = false;
1124  loop_counter_stop_ = true;
1125  goal_index_ = 0;
1126  updateWpNavigationMarkers();
1127 }
1128 
1129 void
1130 Nav2Panel::timerEvent(QTimerEvent * event)
1131 {
1132  if (state_machine_.configuration().contains(accumulated_wp_)) {
1133  if (event->timerId() == timer_.timerId()) {
1134  if (!waypoint_follower_goal_handle_) {
1135  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
1136  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1137  return;
1138  }
1139 
1140  rclcpp::spin_some(client_node_);
1141  auto status = waypoint_follower_goal_handle_->get_status();
1142 
1143  // Check if the goal is still executing
1144  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1145  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1146  {
1147  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
1148  } else {
1149  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1150  timer_.stop();
1151  }
1152  }
1153  } else if (state_machine_.configuration().contains(accumulated_nav_through_poses_)) {
1154  if (event->timerId() == timer_.timerId()) {
1155  if (!nav_through_poses_goal_handle_) {
1156  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
1157  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1158  return;
1159  }
1160 
1161  rclcpp::spin_some(client_node_);
1162  auto status = nav_through_poses_goal_handle_->get_status();
1163 
1164  // Check if the goal is still executing
1165  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1166  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1167  {
1168  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
1169  } else {
1170  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1171  timer_.stop();
1172  }
1173  }
1174  } else {
1175  if (event->timerId() == timer_.timerId()) {
1176  if (!navigation_goal_handle_) {
1177  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
1178  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1179  return;
1180  }
1181 
1182  rclcpp::spin_some(client_node_);
1183  auto status = navigation_goal_handle_->get_status();
1184 
1185  // Check if the goal is still executing
1186  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1187  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1188  {
1189  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
1190  } else {
1191  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1192  timer_.stop();
1193  }
1194  }
1195  }
1196 }
1197 
1198 void
1199 Nav2Panel::startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses)
1200 {
1201  auto is_action_server_ready =
1202  waypoint_follower_action_client_->wait_for_action_server(std::chrono::seconds(5));
1203  if (!is_action_server_ready) {
1204  RCLCPP_ERROR(
1205  client_node_->get_logger(), "follow_waypoints action server is not available."
1206  " Is the initial pose set?");
1207  return;
1208  }
1209 
1210  // Send the goal poses
1211  waypoint_follower_goal_.poses = poses;
1212  waypoint_follower_goal_.goal_index = goal_index_;
1213  waypoint_follower_goal_.number_of_loops = stoi(loop_no_);
1214 
1215  RCLCPP_DEBUG(
1216  client_node_->get_logger(), "Sending a path of %zu waypoints:",
1217  waypoint_follower_goal_.poses.size());
1218  for (auto waypoint : waypoint_follower_goal_.poses) {
1219  RCLCPP_DEBUG(
1220  client_node_->get_logger(),
1221  "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
1222  }
1223 
1224  // Enable result awareness by providing an empty lambda function
1225  auto send_goal_options =
1226  nav2::ActionClient<nav2_msgs::action::FollowWaypoints>::SendGoalOptions();
1227  send_goal_options.result_callback = [this](auto) {
1228  waypoint_follower_goal_handle_.reset();
1229  };
1230 
1231  send_goal_options.feedback_callback = [this](
1232  WaypointFollowerGoalHandle::SharedPtr /*goal_handle*/,
1233  const std::shared_ptr<const nav2_msgs::action::FollowWaypoints::Feedback> feedback) {
1234  goal_index_ = feedback->current_waypoint;
1235  };
1236 
1237  auto future_goal_handle =
1238  waypoint_follower_action_client_->async_send_goal(waypoint_follower_goal_, send_goal_options);
1239  if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
1240  rclcpp::FutureReturnCode::SUCCESS)
1241  {
1242  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
1243  return;
1244  }
1245 
1246  // Get the goal handle and save so that we can check on completion in the timer callback
1247  waypoint_follower_goal_handle_ = future_goal_handle.get();
1248  if (!waypoint_follower_goal_handle_) {
1249  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
1250  return;
1251  }
1252 
1253  timer_.start(200, this);
1254 }
1255 
1256 void
1257 Nav2Panel::startNavThroughPoses(nav_msgs::msg::Goals poses)
1258 {
1259  auto is_action_server_ready =
1260  nav_through_poses_action_client_->wait_for_action_server(std::chrono::seconds(5));
1261  if (!is_action_server_ready) {
1262  RCLCPP_ERROR(
1263  client_node_->get_logger(), "navigate_through_poses action server is not available."
1264  " Is the initial pose set?");
1265  return;
1266  }
1267 
1268  nav_through_poses_goal_.poses = poses;
1269  RCLCPP_INFO(
1270  client_node_->get_logger(),
1271  "NavigateThroughPoses will be called using the BT Navigator's default behavior tree.");
1272 
1273  RCLCPP_DEBUG(
1274  client_node_->get_logger(), "Sending a path of %zu waypoints:",
1275  nav_through_poses_goal_.poses.goals.size());
1276  for (auto waypoint : nav_through_poses_goal_.poses.goals) {
1277  RCLCPP_DEBUG(
1278  client_node_->get_logger(),
1279  "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
1280  }
1281 
1282  // Enable result awareness by providing an empty lambda function
1283  auto send_goal_options =
1284  nav2::ActionClient<nav2_msgs::action::NavigateThroughPoses>::SendGoalOptions();
1285  send_goal_options.result_callback = [this](auto) {
1286  nav_through_poses_goal_handle_.reset();
1287  };
1288 
1289  auto future_goal_handle =
1290  nav_through_poses_action_client_->async_send_goal(nav_through_poses_goal_, send_goal_options);
1291  if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
1292  rclcpp::FutureReturnCode::SUCCESS)
1293  {
1294  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
1295  return;
1296  }
1297 
1298  // Get the goal handle and save so that we can check on completion in the timer callback
1299  nav_through_poses_goal_handle_ = future_goal_handle.get();
1300  if (!nav_through_poses_goal_handle_) {
1301  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
1302  return;
1303  }
1304 
1305  timer_.start(200, this);
1306 }
1307 
1308 void
1309 Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose)
1310 {
1311  auto is_action_server_ready =
1312  navigation_action_client_->wait_for_action_server(std::chrono::seconds(5));
1313  if (!is_action_server_ready) {
1314  RCLCPP_ERROR(
1315  client_node_->get_logger(),
1316  "navigate_to_pose action server is not available."
1317  " Is the initial pose set?");
1318  return;
1319  }
1320 
1321  // Send the goal pose
1322  navigation_goal_.pose = pose;
1323 
1324  RCLCPP_INFO(
1325  client_node_->get_logger(),
1326  "NavigateToPose will be called using the BT Navigator's default behavior tree.");
1327 
1328  // Enable result awareness by providing an empty lambda function
1329  auto send_goal_options =
1330  nav2::ActionClient<nav2_msgs::action::NavigateToPose>::SendGoalOptions();
1331  send_goal_options.result_callback = [this](auto) {
1332  navigation_goal_handle_.reset();
1333  };
1334 
1335  auto future_goal_handle =
1336  navigation_action_client_->async_send_goal(navigation_goal_, send_goal_options);
1337  if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
1338  rclcpp::FutureReturnCode::SUCCESS)
1339  {
1340  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
1341  return;
1342  }
1343 
1344  // Get the goal handle and save so that we can check on completion in the timer callback
1345  navigation_goal_handle_ = future_goal_handle.get();
1346  if (!navigation_goal_handle_) {
1347  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
1348  return;
1349  }
1350 
1351  timer_.start(200, this);
1352 }
1353 
1354 void
1355 Nav2Panel::save(rviz_common::Config config) const
1356 {
1357  Panel::save(config);
1358 }
1359 
1360 void
1361 Nav2Panel::load(const rviz_common::Config & config)
1362 {
1363  Panel::load(config);
1364 }
1365 
1366 void
1367 Nav2Panel::resetUniqueId()
1368 {
1369  unique_id = 0;
1370 }
1371 
1372 int
1373 Nav2Panel::getUniqueId()
1374 {
1375  int temp_id = unique_id;
1376  unique_id += 1;
1377  return temp_id;
1378 }
1379 
1380 void
1381 Nav2Panel::updateWpNavigationMarkers()
1382 {
1383  resetUniqueId();
1384 
1385  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
1386 
1387  for (size_t i = 0; i < acummulated_poses_.goals.size(); i++) {
1388  // Draw a green arrow at the waypoint pose
1389  visualization_msgs::msg::Marker arrow_marker;
1390  arrow_marker.header = acummulated_poses_.goals[i].header;
1391  arrow_marker.id = getUniqueId();
1392  arrow_marker.type = visualization_msgs::msg::Marker::ARROW;
1393  arrow_marker.action = visualization_msgs::msg::Marker::ADD;
1394  arrow_marker.pose = acummulated_poses_.goals[i].pose;
1395  arrow_marker.scale.x = 0.3;
1396  arrow_marker.scale.y = 0.05;
1397  arrow_marker.scale.z = 0.02;
1398  arrow_marker.color.r = 0;
1399  arrow_marker.color.g = 255;
1400  arrow_marker.color.b = 0;
1401  arrow_marker.color.a = 1.0f;
1402  arrow_marker.lifetime = rclcpp::Duration(0s);
1403  arrow_marker.frame_locked = false;
1404  marker_array->markers.push_back(arrow_marker);
1405 
1406  // Draw a red circle at the waypoint pose
1407  visualization_msgs::msg::Marker circle_marker;
1408  circle_marker.header = acummulated_poses_.goals[i].header;
1409  circle_marker.id = getUniqueId();
1410  circle_marker.type = visualization_msgs::msg::Marker::SPHERE;
1411  circle_marker.action = visualization_msgs::msg::Marker::ADD;
1412  circle_marker.pose = acummulated_poses_.goals[i].pose;
1413  circle_marker.scale.x = 0.05;
1414  circle_marker.scale.y = 0.05;
1415  circle_marker.scale.z = 0.05;
1416  circle_marker.color.r = 255;
1417  circle_marker.color.g = 0;
1418  circle_marker.color.b = 0;
1419  circle_marker.color.a = 1.0f;
1420  circle_marker.lifetime = rclcpp::Duration(0s);
1421  circle_marker.frame_locked = false;
1422  marker_array->markers.push_back(circle_marker);
1423 
1424  // Draw the waypoint number
1425  visualization_msgs::msg::Marker marker_text;
1426  marker_text.header = acummulated_poses_.goals[i].header;
1427  marker_text.id = getUniqueId();
1428  marker_text.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
1429  marker_text.action = visualization_msgs::msg::Marker::ADD;
1430  marker_text.pose = acummulated_poses_.goals[i].pose;
1431  marker_text.pose.position.z += 0.2; // draw it on top of the waypoint
1432  marker_text.scale.x = 0.07;
1433  marker_text.scale.y = 0.07;
1434  marker_text.scale.z = 0.07;
1435  marker_text.color.r = 0;
1436  marker_text.color.g = 255;
1437  marker_text.color.b = 0;
1438  marker_text.color.a = 1.0f;
1439  marker_text.lifetime = rclcpp::Duration(0s);
1440  marker_text.frame_locked = false;
1441  marker_text.text = "wp_" + std::to_string(i + 1);
1442  marker_array->markers.push_back(marker_text);
1443  }
1444 
1445  if (marker_array->markers.empty()) {
1446  visualization_msgs::msg::Marker clear_all_marker;
1447  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
1448  marker_array->markers.push_back(clear_all_marker);
1449  }
1450 
1451  wp_navigation_markers_pub_->publish(std::move(marker_array));
1452 }
1453 
1454 inline QString
1455 Nav2Panel::getNavToPoseFeedbackLabel(nav2_msgs::action::NavigateToPose::Feedback msg)
1456 {
1457  return QString(std::string("<table>" + toLabel(msg) + "</table>").c_str());
1458 }
1459 
1460 inline QString
1461 Nav2Panel::getNavThroughPosesFeedbackLabel(nav2_msgs::action::NavigateThroughPoses::Feedback msg)
1462 {
1463  return QString(
1464  std::string(
1465  "<table><tr><td width=150>Poses remaining:</td><td>" +
1466  std::to_string(msg.number_of_poses_remaining) +
1467  "</td></tr>" + toLabel(msg) + "</table>").c_str());
1468 }
1469 
1470 template<typename T>
1471 inline std::string Nav2Panel::toLabel(T & msg)
1472 {
1473  return std::string(
1474  "<tr><td width=150>ETA:</td><td>" +
1475  toString(rclcpp::Duration(msg.estimated_time_remaining).seconds(), 0) + " s"
1476  "</td></tr><tr><td width=150>Distance remaining:</td><td>" +
1477  toString(msg.distance_remaining, 2) + " m"
1478  "</td></tr><tr><td width=150>Time taken:</td><td>" +
1479  toString(rclcpp::Duration(msg.navigation_time).seconds(), 0) + " s"
1480  "</td></tr><tr><td width=150>Recoveries:</td><td>" +
1481  std::to_string(msg.number_of_recoveries) +
1482  "</td></tr>");
1483 }
1484 
1485 inline std::string
1486 Nav2Panel::toString(double val, int precision)
1487 {
1488  std::ostringstream out;
1489  out.precision(precision);
1490  out << std::fixed << val;
1491  return out.str();
1492 }
1493 
1494 } // namespace nav2_rviz_plugins
1495 
1496 #include <pluginlib/class_list_macros.hpp> // NOLINT
1497 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:51