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  executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
459  executor_->add_node(client_node_);
460 
461  client_nav_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
462  "lifecycle_manager_navigation", client_node_);
463  client_loc_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
464  "lifecycle_manager_localization", client_node_);
465  initial_thread_ = new InitialThread(client_nav_, client_loc_);
466  connect(initial_thread_, &InitialThread::finished, initial_thread_, &QObject::deleteLater);
467 
468  QSignalTransition * activeSignal = new QSignalTransition(
469  initial_thread_,
470  &InitialThread::navigationActive);
471  activeSignal->setTargetState(idle_);
472  pre_initial_->addTransition(activeSignal);
473  QSignalTransition * inactiveSignal = new QSignalTransition(
474  initial_thread_,
475  &InitialThread::navigationInactive);
476  inactiveSignal->setTargetState(initial_);
477  pre_initial_->addTransition(inactiveSignal);
478 
479  QObject::connect(
480  initial_thread_, &InitialThread::navigationActive,
481  [this, navigation_active] {
482  navigation_status_indicator_->setText(navigation_active);
483  });
484  QObject::connect(
485  initial_thread_, &InitialThread::navigationInactive,
486  [this, navigation_inactive] {
487  navigation_status_indicator_->setText(navigation_inactive);
488  navigation_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel());
489  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
490  });
491  QObject::connect(
492  initial_thread_, &InitialThread::localizationActive,
493  [this, localization_active] {
494  localization_status_indicator_->setText(localization_active);
495  });
496  QObject::connect(
497  initial_thread_, &InitialThread::localizationInactive,
498  [this, localization_inactive] {
499  localization_status_indicator_->setText(localization_inactive);
500  });
501 
502  state_machine_.addState(pre_initial_);
503  state_machine_.addState(initial_);
504  state_machine_.addState(idle_);
505  state_machine_.addState(running_);
506  state_machine_.addState(canceled_);
507  state_machine_.addState(reset_);
508  state_machine_.addState(paused_);
509  state_machine_.addState(resumed_);
510  state_machine_.addState(accumulating_);
511  state_machine_.addState(accumulated_wp_);
512  state_machine_.addState(accumulated_nav_through_poses_);
513  state_machine_.addState(resumed_wp_);
514 
515  state_machine_.setInitialState(pre_initial_);
516 
517  // delay starting initial thread until state machine has started or a race occurs
518  QObject::connect(&state_machine_, SIGNAL(started()), this, SLOT(startThread()));
519  state_machine_.start();
520 
521  // Lay out the items in the panel
522  QVBoxLayout * main_layout = new QVBoxLayout;
523  QHBoxLayout * side_layout = new QHBoxLayout;
524  QVBoxLayout * status_layout = new QVBoxLayout;
525  QHBoxLayout * logo_layout = new QHBoxLayout;
526  QVBoxLayout * group_box_layout = new QVBoxLayout;
527 
528  QGroupBox * groupBox = new QGroupBox(tr("Tools for WP-Following"));
529  imgDisplayLabel_ = new QLabel("");
530  imgDisplayLabel_->setPixmap(
531  rviz_common::loadPixmap("package://nav2_rviz_plugins/icons/classes/nav2_logo_small.png"));
532 
533  status_layout->addWidget(navigation_status_indicator_);
534  status_layout->addWidget(localization_status_indicator_);
535  status_layout->addWidget(navigation_goal_status_indicator_);
536 
537  logo_layout->addWidget(imgDisplayLabel_, 5, Qt::AlignRight);
538 
539  side_layout->addLayout(status_layout);
540  side_layout->addLayout(logo_layout);
541 
542  main_layout->addLayout(side_layout);
543  main_layout->addWidget(navigation_feedback_indicator_);
544  main_layout->addWidget(waypoint_status_indicator_);
545  main_layout->addWidget(pause_resume_button_);
546  main_layout->addWidget(start_reset_button_);
547  main_layout->addWidget(navigation_mode_button_);
548 
549  QHBoxLayout * group_box_l1_layout = new QHBoxLayout;
550  QHBoxLayout * group_box_l2_layout = new QHBoxLayout;
551 
552  group_box_l1_layout->addWidget(save_waypoints_button_);
553  group_box_l1_layout->addWidget(load_waypoints_button_);
554  group_box_l1_layout->addWidget(pause_waypoint_button_);
555 
556  group_box_l2_layout->addWidget(number_of_loops_);
557  group_box_l2_layout->addWidget(nr_of_loops_);
558  group_box_l2_layout->addWidget(store_initial_pose_checkbox_);
559 
560  group_box_layout->addLayout(group_box_l1_layout);
561  group_box_layout->addLayout(group_box_l2_layout);
562 
563  groupBox->setLayout(group_box_layout);
564 
565  main_layout->addWidget(groupBox);
566  main_layout->setContentsMargins(10, 10, 10, 10);
567  setLayout(main_layout);
568 
569  navigation_action_client_ =
570  rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
571  client_node_,
572  "navigate_to_pose");
573  waypoint_follower_action_client_ =
574  rclcpp_action::create_client<nav2_msgs::action::FollowWaypoints>(
575  client_node_,
576  "follow_waypoints");
577  nav_through_poses_action_client_ =
578  rclcpp_action::create_client<nav2_msgs::action::NavigateThroughPoses>(
579  client_node_,
580  "navigate_through_poses");
581 
582  // Setting up tf for initial pose
583  tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(client_node_->get_clock());
584  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
585  client_node_->get_node_base_interface(),
586  client_node_->get_node_timers_interface());
587  tf2_buffer_->setCreateTimerInterface(timer_interface);
588  transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);
589 
590  navigation_goal_ = nav2_msgs::action::NavigateToPose::Goal();
591  waypoint_follower_goal_ = nav2_msgs::action::FollowWaypoints::Goal();
592  nav_through_poses_goal_ = nav2_msgs::action::NavigateThroughPoses::Goal();
593 
594  wp_navigation_markers_pub_ =
595  client_node_->create_publisher<visualization_msgs::msg::MarkerArray>(
596  "waypoints",
597  rclcpp::QoS(1).transient_local());
598 
599  QObject::connect(
600  &GoalUpdater, SIGNAL(updateGoal(double,double,double,QString)), // NOLINT
601  this, SLOT(onNewGoal(double,double,double,QString))); // NOLINT
602 }
603 
604 Nav2Panel::~Nav2Panel()
605 {
606 }
607 
608 void Nav2Panel::initialStateHandler()
609 {
610  if (store_initial_pose_checkbox_->isChecked()) {
611  store_initial_pose_ = true;
612 
613  } else {
614  store_initial_pose_ = false;
615  }
616 }
617 
618 bool Nav2Panel::isLoopValueValid(std::string & loop_value)
619 {
620  // Check for just empty space
621  if (loop_value.empty()) {
622  std::cout << "Loop value cannot be set to empty, setting to 0" << std::endl;
623  loop_value = "0";
624  nr_of_loops_->setText("0");
625  return true;
626  }
627 
628  // Check for any chars or spaces in the string
629  for (char & c : loop_value) {
630  if (isalpha(c) || isspace(c) || ispunct(c)) {
631  waypoint_status_indicator_->setText(
632  "<b> Note: </b> Set a valid value for the loop");
633  std::cout << "Set a valid value for the loop, check for alphabets and spaces" << std::endl;
634  navigation_mode_button_->setEnabled(false);
635  return false;
636  }
637  }
638 
639  try {
640  stoi(loop_value);
641  } catch (std::invalid_argument const & ex) {
642  // Handling special symbols
643  waypoint_status_indicator_->setText("<b> Note: </b> Set a valid value for the loop");
644  navigation_mode_button_->setEnabled(false);
645  return false;
646  } catch (std::out_of_range const & ex) {
647  // Handling out of range values
648  waypoint_status_indicator_->setText(
649  "<b> Note: </b> Loop value out of range, setting max possible value"
650  );
651  loop_value = std::to_string(std::numeric_limits<int>::max());
652  nr_of_loops_->setText(QString::fromStdString(loop_value));
653  }
654  return true;
655 }
656 
657 void Nav2Panel::loophandler()
658 {
659  loop_no_ = nr_of_loops_->displayText().toStdString();
660 
661  // Sanity check for the loop value
662  if (!isLoopValueValid(loop_no_)) {
663  return;
664  }
665 
666  // Enabling the start_waypoint_follow button, if disabled.
667  navigation_mode_button_->setEnabled(true);
668 
669  // Disabling nav_through_poses button
670  if (!loop_no_.empty() && stoi(loop_no_) > 0) {
671  pause_resume_button_->setEnabled(false);
672  } else {
673  pause_resume_button_->setEnabled(true);
674  }
675 }
676 
677 void Nav2Panel::handleGoalLoader()
678 {
679  acummulated_poses_ = nav_msgs::msg::Goals();
680 
681  std::cout << "Loading Waypoints!" << std::endl;
682 
683  QString file = QFileDialog::getOpenFileName(
684  this,
685  tr("Open File"), "",
686  tr("yaml(*.yaml);;All Files (*)"));
687 
688  YAML::Node available_waypoints;
689 
690  try {
691  available_waypoints = YAML::LoadFile(file.toStdString());
692  } catch (const std::exception & ex) {
693  std::cout << ex.what() << ", please select a valid file" << std::endl;
694  updateWpNavigationMarkers();
695  return;
696  }
697 
698  const YAML::Node & waypoint_iter = available_waypoints["waypoints"];
699  for (YAML::const_iterator it = waypoint_iter.begin(); it != waypoint_iter.end(); ++it) {
700  auto waypoint = waypoint_iter[it->first.as<std::string>()];
701  auto pose = waypoint["pose"].as<std::vector<double>>();
702  auto orientation = waypoint["orientation"].as<std::vector<double>>();
703  acummulated_poses_.goals.push_back(convert_to_msg(pose, orientation));
704  }
705 
706  // Publishing Waypoint Navigation marker after loading wp's
707  updateWpNavigationMarkers();
708 }
709 
710 geometry_msgs::msg::PoseStamped Nav2Panel::convert_to_msg(
711  std::vector<double> pose,
712  std::vector<double> orientation)
713 {
714  auto msg = geometry_msgs::msg::PoseStamped();
715 
716  msg.header.frame_id = "map";
717  // msg.header.stamp = client_node_->now(); // client node doesn't respect sim time yet
718 
719  msg.pose.position.x = pose[0];
720  msg.pose.position.y = pose[1];
721  msg.pose.position.z = pose[2];
722 
723  msg.pose.orientation.w = orientation[0];
724  msg.pose.orientation.x = orientation[1];
725  msg.pose.orientation.y = orientation[2];
726  msg.pose.orientation.z = orientation[3];
727 
728  return msg;
729 }
730 
731 void Nav2Panel::handleGoalSaver()
732 {
733 // Check if the waypoints are accumulated
734 
735  if (acummulated_poses_.goals.empty()) {
736  std::cout << "No accumulated Points to Save!" << std::endl;
737  return;
738  } else {
739  std::cout << "Saving Waypoints!" << std::endl;
740  }
741 
742  YAML::Emitter out;
743  out << YAML::BeginMap;
744  out << YAML::Key << "waypoints";
745  out << YAML::BeginMap;
746 
747  // Save WPs to data structure
748  for (unsigned int i = 0; i < acummulated_poses_.goals.size(); ++i) {
749  out << YAML::Key << "waypoint" + std::to_string(i);
750  out << YAML::BeginMap;
751  out << YAML::Key << "pose";
752  std::vector<double> pose =
753  {acummulated_poses_.goals[i].pose.position.x, acummulated_poses_.goals[i].pose.position.y,
754  acummulated_poses_.goals[i].pose.position.z};
755  out << YAML::Value << pose;
756  out << YAML::Key << "orientation";
757  std::vector<double> orientation =
758  {acummulated_poses_.goals[i].pose.orientation.w, acummulated_poses_.goals[i].pose.orientation.x,
759  acummulated_poses_.goals[i].pose.orientation.y,
760  acummulated_poses_.goals[i].pose.orientation.z};
761  out << YAML::Value << orientation;
762  out << YAML::EndMap;
763  }
764 
765  // open dialog to save it in a file
766  QString file = QFileDialog::getSaveFileName(
767  this,
768  tr("Open File"), "",
769  tr("yaml(*.yaml);;All Files (*)"));
770 
771  if (!file.toStdString().empty()) {
772  std::ofstream fout(file.toStdString() + ".yaml");
773  fout << out.c_str();
774  std::cout << "Saving waypoints succeeded" << std::endl;
775  } else {
776  std::cout << "Saving waypoints aborted" << std::endl;
777  }
778 }
779 
780 void
781 Nav2Panel::onInitialize()
782 {
783  node_ptr_ = getDisplayContext()->getRosNodeAbstraction().lock();
784  if (node_ptr_ == nullptr) {
785  // The node no longer exists, so just don't initialize
786  RCLCPP_ERROR(
787  rclcpp::get_logger("nav2_panel"),
788  "Underlying ROS node no longer exists, initialization failed");
789  return;
790  }
791  rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
792 
793  // declaring parameter to get the base frame
794  node->declare_parameter("base_frame", rclcpp::ParameterValue(std::string("base_footprint")));
795  node->get_parameter("base_frame", base_frame_);
796 
797  // create action feedback subscribers
798  navigation_feedback_sub_ =
799  node->create_subscription<nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage>(
800  "navigate_to_pose/_action/feedback",
801  rclcpp::SystemDefaultsQoS(),
802  [this](const nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage::SharedPtr msg) {
803  if (stoi(nr_of_loops_->displayText().toStdString()) > 0) {
804  if (goal_index_ == 0 && !loop_counter_stop_) {
805  loop_count_++;
806  loop_counter_stop_ = true;
807  }
808  if (goal_index_ != 0) {
809  loop_counter_stop_ = false;
810  }
811  navigation_feedback_indicator_->setText(
812  getNavToPoseFeedbackLabel(msg->feedback) + QString(
813  std::string(
814  "</td></tr><tr><td width=150>Waypoint:</td><td>" +
815  toString(goal_index_ + 1)).c_str()) + QString(
816  std::string(
817  "</td></tr><tr><td width=150>Loop:</td><td>" +
818  toString(loop_count_)).c_str()));
819  } else {
820  navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel(msg->feedback));
821  }
822  });
823  nav_through_poses_feedback_sub_ =
824  node->create_subscription<nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage>(
825  "navigate_through_poses/_action/feedback",
826  rclcpp::SystemDefaultsQoS(),
827  [this](const nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage::SharedPtr msg) {
828  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel(msg->feedback));
829  });
830 
831  // create action goal status subscribers
832  navigation_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
833  "navigate_to_pose/_action/status",
834  rclcpp::SystemDefaultsQoS(),
835  [this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
836  navigation_goal_status_indicator_->setText(
837  nav2_rviz_plugins::getGoalStatusLabel("Feedback", msg->status_list.back().status));
838  // Clearing all the stored values once reaching the final goal
839  if (
840  loop_count_ == stoi(nr_of_loops_->displayText().toStdString()) &&
841  goal_index_ == static_cast<int>(store_poses_.goals.size()) - 1 &&
842  msg->status_list.back().status == action_msgs::msg::GoalStatus::STATUS_SUCCEEDED)
843  {
844  store_poses_ = nav_msgs::msg::Goals();
845  waypoint_status_indicator_->clear();
846  loop_no_ = "0";
847  loop_count_ = 0;
848  navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel());
849  }
850  });
851  nav_through_poses_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
852  "navigate_through_poses/_action/status",
853  rclcpp::SystemDefaultsQoS(),
854  [this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
855  navigation_goal_status_indicator_->setText(
856  nav2_rviz_plugins::getGoalStatusLabel("Feedback", msg->status_list.back().status));
857  if (msg->status_list.back().status != action_msgs::msg::GoalStatus::STATUS_EXECUTING) {
858  navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
859  }
860  });
861 }
862 
863 void
864 Nav2Panel::startThread()
865 {
866  // start initial thread now that state machine is started
867  initial_thread_->start();
868 }
869 
870 void
871 Nav2Panel::onPause()
872 {
873  QFuture<void> futureNav =
874  QtConcurrent::run(
875  std::bind(
877  client_nav_.get(), std::placeholders::_1), server_timeout_);
878  QFuture<void> futureLoc =
879  QtConcurrent::run(
880  std::bind(
882  client_loc_.get(), std::placeholders::_1), server_timeout_);
883 }
884 
885 void
886 Nav2Panel::onResume()
887 {
888  QFuture<void> futureNav =
889  QtConcurrent::run(
890  std::bind(
892  client_nav_.get(), std::placeholders::_1), server_timeout_);
893  QFuture<void> futureLoc =
894  QtConcurrent::run(
895  std::bind(
897  client_loc_.get(), std::placeholders::_1), server_timeout_);
898 }
899 
900 void
901 Nav2Panel::onStartup()
902 {
903  QFuture<void> futureNav =
904  QtConcurrent::run(
905  std::bind(
907  client_nav_.get(), std::placeholders::_1), server_timeout_);
908  QFuture<void> futureLoc =
909  QtConcurrent::run(
910  std::bind(
912  client_loc_.get(), std::placeholders::_1), server_timeout_);
913 }
914 
915 void
916 Nav2Panel::onShutdown()
917 {
918  QFuture<void> futureNav =
919  QtConcurrent::run(
920  std::bind(
922  client_nav_.get(), std::placeholders::_1), server_timeout_);
923  QFuture<void> futureLoc =
924  QtConcurrent::run(
925  std::bind(
927  client_loc_.get(), std::placeholders::_1), server_timeout_);
928  timer_.stop();
929 }
930 
931 void
932 Nav2Panel::onCancel()
933 {
934  QFuture<void> future =
935  QtConcurrent::run(
936  std::bind(
937  &Nav2Panel::onCancelButtonPressed,
938  this));
939  waypoint_status_indicator_->clear();
940  store_poses_ = nav_msgs::msg::Goals();
941  acummulated_poses_ = nav_msgs::msg::Goals();
942 }
943 
944 void Nav2Panel::onResumedWp()
945 {
946  QFuture<void> future =
947  QtConcurrent::run(
948  std::bind(
949  &Nav2Panel::onCancelButtonPressed,
950  this));
951  acummulated_poses_ = store_poses_;
952  loop_no_ = std::to_string(
953  stoi(nr_of_loops_->displayText().toStdString()) -
954  loop_count_);
955  waypoint_status_indicator_->setText(
956  QString(std::string("<b> Note: </b> Navigation is paused.").c_str()));
957 }
958 
959 void
960 Nav2Panel::onNewGoal(double x, double y, double theta, QString frame)
961 {
962  auto pose = geometry_msgs::msg::PoseStamped();
963 
964  // pose.header.stamp = client_node_->now(); // client node doesn't respect sim time yet
965  pose.header.frame_id = frame.toStdString();
966  pose.pose.position.x = x;
967  pose.pose.position.y = y;
968  pose.pose.position.z = 0.0;
969  pose.pose.orientation = orientationAroundZAxis(theta);
970 
971  if (store_poses_.goals.empty()) {
972  if (state_machine_.configuration().contains(accumulating_)) {
973  waypoint_status_indicator_->clear();
974  acummulated_poses_.goals.push_back(pose);
975  } else {
976  acummulated_poses_ = nav_msgs::msg::Goals();
977  updateWpNavigationMarkers();
978  std::cout << "Start navigation" << std::endl;
979  startNavigation(pose);
980  }
981  } else {
982  waypoint_status_indicator_->setText(
983  QString(std::string("<b> Note: </b> Cannot set goal in pause state").c_str()));
984  }
985  updateWpNavigationMarkers();
986 }
987 
988 void
989 Nav2Panel::onCancelButtonPressed()
990 {
991  if (navigation_goal_handle_) {
992  auto future_cancel = navigation_action_client_->async_cancel_goal(navigation_goal_handle_);
993 
994  if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
995  rclcpp::FutureReturnCode::SUCCESS)
996  {
997  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel goal");
998  } else {
999  navigation_goal_handle_.reset();
1000  }
1001  }
1002 
1003  if (waypoint_follower_goal_handle_) {
1004  auto future_cancel =
1005  waypoint_follower_action_client_->async_cancel_goal(waypoint_follower_goal_handle_);
1006 
1007  if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
1008  rclcpp::FutureReturnCode::SUCCESS)
1009  {
1010  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel waypoint follower");
1011  } else {
1012  waypoint_follower_goal_handle_.reset();
1013  }
1014  }
1015 
1016  if (nav_through_poses_goal_handle_) {
1017  auto future_cancel =
1018  nav_through_poses_action_client_->async_cancel_goal(nav_through_poses_goal_handle_);
1019 
1020  if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
1021  rclcpp::FutureReturnCode::SUCCESS)
1022  {
1023  RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel nav through pose action");
1024  } else {
1025  nav_through_poses_goal_handle_.reset();
1026  }
1027  }
1028 
1029  timer_.stop();
1030 }
1031 
1032 void
1033 Nav2Panel::onAccumulatedWp()
1034 {
1035  if (acummulated_poses_.goals.empty()) {
1036  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1037  waypoint_status_indicator_->setText(
1038  "<b> Note: </b> Uh oh! Someone forgot to select the waypoints");
1039  return;
1040  }
1041 
1042  // Sanity check for the loop value
1043  if (!isLoopValueValid(loop_no_)) {
1044  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1045  return;
1046  }
1047 
1048  // Remove any warning status at this point
1049  waypoint_status_indicator_->clear();
1050 
1051  // Disable navigation modes
1052  navigation_mode_button_->setEnabled(false);
1053  pause_resume_button_->setEnabled(false);
1054 
1057  if (store_poses_.goals.empty()) {
1058  std::cout << "Start waypoint" << std::endl;
1059 
1060  // Setting the final loop value on the text box for sanity
1061  nr_of_loops_->setText(QString::fromStdString(loop_no_));
1062 
1063  // Variable to store initial pose
1064  geometry_msgs::msg::TransformStamped init_transform;
1065 
1066  // Looking up transform to get initial pose
1067  if (store_initial_pose_) {
1068  try {
1069  init_transform = tf2_buffer_->lookupTransform(
1070  acummulated_poses_.goals[0].header.frame_id, base_frame_,
1071  tf2::TimePointZero);
1072  } catch (const tf2::TransformException & ex) {
1073  RCLCPP_INFO(
1074  client_node_->get_logger(), "Could not transform %s to %s: %s",
1075  acummulated_poses_.goals[0].header.frame_id.c_str(), base_frame_.c_str(), ex.what());
1076  return;
1077  }
1078 
1079  // Converting TransformStamped to PoseStamped
1080  geometry_msgs::msg::PoseStamped initial_pose;
1081  initial_pose.header = init_transform.header;
1082  initial_pose.pose.position.x = init_transform.transform.translation.x;
1083  initial_pose.pose.position.y = init_transform.transform.translation.y;
1084  initial_pose.pose.position.z = init_transform.transform.translation.z;
1085  initial_pose.pose.orientation.x = init_transform.transform.rotation.x;
1086  initial_pose.pose.orientation.y = init_transform.transform.rotation.y;
1087  initial_pose.pose.orientation.z = init_transform.transform.rotation.z;
1088  initial_pose.pose.orientation.w = init_transform.transform.rotation.w;
1089 
1090  // inserting the acummulated pose
1091  acummulated_poses_.goals.insert(acummulated_poses_.goals.begin(), initial_pose);
1092  updateWpNavigationMarkers();
1093  initial_pose_stored_ = true;
1094  if (loop_count_ == 0) {
1095  goal_index_ = 1;
1096  }
1097  } else if (!store_initial_pose_ && initial_pose_stored_) {
1098  acummulated_poses_.goals.erase(
1099  acummulated_poses_.goals.begin(),
1100  acummulated_poses_.goals.begin());
1101  }
1102  } else {
1103  std::cout << "Resuming waypoint" << std::endl;
1104  }
1105 
1106  startWaypointFollowing(acummulated_poses_.goals);
1107  store_poses_ = acummulated_poses_;
1108  acummulated_poses_ = nav_msgs::msg::Goals();
1109 }
1110 
1111 void
1112 Nav2Panel::onAccumulatedNTP()
1113 {
1114  std::cout << "Start navigate through poses" << std::endl;
1115  startNavThroughPoses(acummulated_poses_);
1116 }
1117 
1118 void
1119 Nav2Panel::onAccumulating()
1120 {
1121  acummulated_poses_ = nav_msgs::msg::Goals();
1122  store_poses_ = nav_msgs::msg::Goals();
1123  loop_count_ = 0;
1124  loop_no_ = "0";
1125  initial_pose_stored_ = false;
1126  loop_counter_stop_ = true;
1127  goal_index_ = 0;
1128  updateWpNavigationMarkers();
1129 }
1130 
1131 void
1132 Nav2Panel::timerEvent(QTimerEvent * event)
1133 {
1134  if (state_machine_.configuration().contains(accumulated_wp_)) {
1135  if (event->timerId() == timer_.timerId()) {
1136  if (!waypoint_follower_goal_handle_) {
1137  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
1138  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1139  return;
1140  }
1141 
1142  executor_->spin_some();
1143  auto status = waypoint_follower_goal_handle_->get_status();
1144 
1145  // Check if the goal is still executing
1146  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1147  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1148  {
1149  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
1150  } else {
1151  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1152  timer_.stop();
1153  }
1154  }
1155  } else if (state_machine_.configuration().contains(accumulated_nav_through_poses_)) {
1156  if (event->timerId() == timer_.timerId()) {
1157  if (!nav_through_poses_goal_handle_) {
1158  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
1159  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1160  return;
1161  }
1162 
1163  executor_->spin_some();
1164  auto status = nav_through_poses_goal_handle_->get_status();
1165 
1166  // Check if the goal is still executing
1167  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1168  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1169  {
1170  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
1171  } else {
1172  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1173  timer_.stop();
1174  }
1175  }
1176  } else {
1177  if (event->timerId() == timer_.timerId()) {
1178  if (!navigation_goal_handle_) {
1179  RCLCPP_DEBUG(client_node_->get_logger(), "Waiting for Goal");
1180  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1181  return;
1182  }
1183 
1184  executor_->spin_some();
1185  auto status = navigation_goal_handle_->get_status();
1186 
1187  // Check if the goal is still executing
1188  if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1189  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1190  {
1191  state_machine_.postEvent(new ROSActionQEvent(QActionState::ACTIVE));
1192  } else {
1193  state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE));
1194  timer_.stop();
1195  }
1196  }
1197  }
1198 }
1199 
1200 void
1201 Nav2Panel::startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses)
1202 {
1203  auto is_action_server_ready =
1204  waypoint_follower_action_client_->wait_for_action_server(std::chrono::seconds(5));
1205  if (!is_action_server_ready) {
1206  RCLCPP_ERROR(
1207  client_node_->get_logger(), "follow_waypoints action server is not available."
1208  " Is the initial pose set?");
1209  return;
1210  }
1211 
1212  // Send the goal poses
1213  waypoint_follower_goal_.poses = poses;
1214  waypoint_follower_goal_.goal_index = goal_index_;
1215  waypoint_follower_goal_.number_of_loops = stoi(loop_no_);
1216 
1217  RCLCPP_DEBUG(
1218  client_node_->get_logger(), "Sending a path of %zu waypoints:",
1219  waypoint_follower_goal_.poses.size());
1220  for (auto waypoint : waypoint_follower_goal_.poses) {
1221  RCLCPP_DEBUG(
1222  client_node_->get_logger(),
1223  "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
1224  }
1225 
1226  // Enable result awareness by providing an empty lambda function
1227  auto send_goal_options =
1228  nav2::ActionClient<nav2_msgs::action::FollowWaypoints>::SendGoalOptions();
1229  send_goal_options.result_callback = [this](auto) {
1230  waypoint_follower_goal_handle_.reset();
1231  };
1232 
1233  send_goal_options.feedback_callback = [this](
1234  WaypointFollowerGoalHandle::SharedPtr /*goal_handle*/,
1235  const std::shared_ptr<const nav2_msgs::action::FollowWaypoints::Feedback> feedback) {
1236  goal_index_ = feedback->current_waypoint;
1237  };
1238 
1239  auto future_goal_handle =
1240  waypoint_follower_action_client_->async_send_goal(waypoint_follower_goal_, send_goal_options);
1241  if (executor_->spin_until_future_complete(future_goal_handle, server_timeout_) !=
1242  rclcpp::FutureReturnCode::SUCCESS)
1243  {
1244  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
1245  return;
1246  }
1247 
1248  // Get the goal handle and save so that we can check on completion in the timer callback
1249  waypoint_follower_goal_handle_ = future_goal_handle.get();
1250  if (!waypoint_follower_goal_handle_) {
1251  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
1252  return;
1253  }
1254 
1255  timer_.start(200, this);
1256 }
1257 
1258 void
1259 Nav2Panel::startNavThroughPoses(nav_msgs::msg::Goals poses)
1260 {
1261  auto is_action_server_ready =
1262  nav_through_poses_action_client_->wait_for_action_server(std::chrono::seconds(5));
1263  if (!is_action_server_ready) {
1264  RCLCPP_ERROR(
1265  client_node_->get_logger(), "navigate_through_poses action server is not available."
1266  " Is the initial pose set?");
1267  return;
1268  }
1269 
1270  nav_through_poses_goal_.poses = poses;
1271  RCLCPP_INFO(
1272  client_node_->get_logger(),
1273  "NavigateThroughPoses will be called using the BT Navigator's default behavior tree.");
1274 
1275  RCLCPP_DEBUG(
1276  client_node_->get_logger(), "Sending a path of %zu waypoints:",
1277  nav_through_poses_goal_.poses.goals.size());
1278  for (auto waypoint : nav_through_poses_goal_.poses.goals) {
1279  RCLCPP_DEBUG(
1280  client_node_->get_logger(),
1281  "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
1282  }
1283 
1284  // Enable result awareness by providing an empty lambda function
1285  auto send_goal_options =
1286  nav2::ActionClient<nav2_msgs::action::NavigateThroughPoses>::SendGoalOptions();
1287  send_goal_options.result_callback = [this](auto) {
1288  nav_through_poses_goal_handle_.reset();
1289  };
1290 
1291  auto future_goal_handle =
1292  nav_through_poses_action_client_->async_send_goal(nav_through_poses_goal_, send_goal_options);
1293  if (executor_->spin_until_future_complete(future_goal_handle, server_timeout_) !=
1294  rclcpp::FutureReturnCode::SUCCESS)
1295  {
1296  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
1297  return;
1298  }
1299 
1300  // Get the goal handle and save so that we can check on completion in the timer callback
1301  nav_through_poses_goal_handle_ = future_goal_handle.get();
1302  if (!nav_through_poses_goal_handle_) {
1303  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
1304  return;
1305  }
1306 
1307  timer_.start(200, this);
1308 }
1309 
1310 void
1311 Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose)
1312 {
1313  auto is_action_server_ready =
1314  navigation_action_client_->wait_for_action_server(std::chrono::seconds(5));
1315  if (!is_action_server_ready) {
1316  RCLCPP_ERROR(
1317  client_node_->get_logger(),
1318  "navigate_to_pose action server is not available."
1319  " Is the initial pose set?");
1320  return;
1321  }
1322 
1323  // Send the goal pose
1324  navigation_goal_.pose = pose;
1325 
1326  RCLCPP_INFO(
1327  client_node_->get_logger(),
1328  "NavigateToPose will be called using the BT Navigator's default behavior tree.");
1329 
1330  // Enable result awareness by providing an empty lambda function
1331  auto send_goal_options =
1332  nav2::ActionClient<nav2_msgs::action::NavigateToPose>::SendGoalOptions();
1333  send_goal_options.result_callback = [this](auto) {
1334  navigation_goal_handle_.reset();
1335  };
1336 
1337  auto future_goal_handle =
1338  navigation_action_client_->async_send_goal(navigation_goal_, send_goal_options);
1339  if (executor_->spin_until_future_complete(future_goal_handle, server_timeout_) !=
1340  rclcpp::FutureReturnCode::SUCCESS)
1341  {
1342  RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
1343  return;
1344  }
1345 
1346  // Get the goal handle and save so that we can check on completion in the timer callback
1347  navigation_goal_handle_ = future_goal_handle.get();
1348  if (!navigation_goal_handle_) {
1349  RCLCPP_ERROR(client_node_->get_logger(), "Goal was rejected by server");
1350  return;
1351  }
1352 
1353  timer_.start(200, this);
1354 }
1355 
1356 void
1357 Nav2Panel::save(rviz_common::Config config) const
1358 {
1359  Panel::save(config);
1360 }
1361 
1362 void
1363 Nav2Panel::load(const rviz_common::Config & config)
1364 {
1365  Panel::load(config);
1366 }
1367 
1368 void
1369 Nav2Panel::resetUniqueId()
1370 {
1371  unique_id = 0;
1372 }
1373 
1374 int
1375 Nav2Panel::getUniqueId()
1376 {
1377  int temp_id = unique_id;
1378  unique_id += 1;
1379  return temp_id;
1380 }
1381 
1382 void
1383 Nav2Panel::updateWpNavigationMarkers()
1384 {
1385  resetUniqueId();
1386 
1387  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
1388 
1389  for (size_t i = 0; i < acummulated_poses_.goals.size(); i++) {
1390  // Draw a green arrow at the waypoint pose
1391  visualization_msgs::msg::Marker arrow_marker;
1392  arrow_marker.header = acummulated_poses_.goals[i].header;
1393  arrow_marker.id = getUniqueId();
1394  arrow_marker.type = visualization_msgs::msg::Marker::ARROW;
1395  arrow_marker.action = visualization_msgs::msg::Marker::ADD;
1396  arrow_marker.pose = acummulated_poses_.goals[i].pose;
1397  arrow_marker.scale.x = 0.3;
1398  arrow_marker.scale.y = 0.05;
1399  arrow_marker.scale.z = 0.02;
1400  arrow_marker.color.r = 0;
1401  arrow_marker.color.g = 255;
1402  arrow_marker.color.b = 0;
1403  arrow_marker.color.a = 1.0f;
1404  arrow_marker.lifetime = rclcpp::Duration(0s);
1405  arrow_marker.frame_locked = false;
1406  marker_array->markers.push_back(arrow_marker);
1407 
1408  // Draw a red circle at the waypoint pose
1409  visualization_msgs::msg::Marker circle_marker;
1410  circle_marker.header = acummulated_poses_.goals[i].header;
1411  circle_marker.id = getUniqueId();
1412  circle_marker.type = visualization_msgs::msg::Marker::SPHERE;
1413  circle_marker.action = visualization_msgs::msg::Marker::ADD;
1414  circle_marker.pose = acummulated_poses_.goals[i].pose;
1415  circle_marker.scale.x = 0.05;
1416  circle_marker.scale.y = 0.05;
1417  circle_marker.scale.z = 0.05;
1418  circle_marker.color.r = 255;
1419  circle_marker.color.g = 0;
1420  circle_marker.color.b = 0;
1421  circle_marker.color.a = 1.0f;
1422  circle_marker.lifetime = rclcpp::Duration(0s);
1423  circle_marker.frame_locked = false;
1424  marker_array->markers.push_back(circle_marker);
1425 
1426  // Draw the waypoint number
1427  visualization_msgs::msg::Marker marker_text;
1428  marker_text.header = acummulated_poses_.goals[i].header;
1429  marker_text.id = getUniqueId();
1430  marker_text.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
1431  marker_text.action = visualization_msgs::msg::Marker::ADD;
1432  marker_text.pose = acummulated_poses_.goals[i].pose;
1433  marker_text.pose.position.z += 0.2; // draw it on top of the waypoint
1434  marker_text.scale.x = 0.07;
1435  marker_text.scale.y = 0.07;
1436  marker_text.scale.z = 0.07;
1437  marker_text.color.r = 0;
1438  marker_text.color.g = 255;
1439  marker_text.color.b = 0;
1440  marker_text.color.a = 1.0f;
1441  marker_text.lifetime = rclcpp::Duration(0s);
1442  marker_text.frame_locked = false;
1443  marker_text.text = "wp_" + std::to_string(i + 1);
1444  marker_array->markers.push_back(marker_text);
1445  }
1446 
1447  if (marker_array->markers.empty()) {
1448  visualization_msgs::msg::Marker clear_all_marker;
1449  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
1450  marker_array->markers.push_back(clear_all_marker);
1451  }
1452 
1453  wp_navigation_markers_pub_->publish(std::move(marker_array));
1454 }
1455 
1456 inline QString
1457 Nav2Panel::getNavToPoseFeedbackLabel(nav2_msgs::action::NavigateToPose::Feedback msg)
1458 {
1459  return QString(std::string("<table>" + toLabel(msg) + "</table>").c_str());
1460 }
1461 
1462 inline QString
1463 Nav2Panel::getNavThroughPosesFeedbackLabel(nav2_msgs::action::NavigateThroughPoses::Feedback msg)
1464 {
1465  return QString(
1466  std::string(
1467  "<table><tr><td width=150>Poses remaining:</td><td>" +
1468  std::to_string(msg.number_of_poses_remaining) +
1469  "</td></tr>" + toLabel(msg) + "</table>").c_str());
1470 }
1471 
1472 template<typename T>
1473 inline std::string Nav2Panel::toLabel(T & msg)
1474 {
1475  return std::string(
1476  "<tr><td width=150>ETA:</td><td>" +
1477  toString(rclcpp::Duration(msg.estimated_time_remaining).seconds(), 0) + " s"
1478  "</td></tr><tr><td width=150>Distance remaining:</td><td>" +
1479  toString(msg.distance_remaining, 2) + " m"
1480  "</td></tr><tr><td width=150>Time taken:</td><td>" +
1481  toString(rclcpp::Duration(msg.navigation_time).seconds(), 0) + " s"
1482  "</td></tr><tr><td width=150>Recoveries:</td><td>" +
1483  std::to_string(msg.number_of_recoveries) +
1484  "</td></tr>");
1485 }
1486 
1487 inline std::string
1488 Nav2Panel::toString(double val, int precision)
1489 {
1490  std::ostringstream out;
1491  out.precision(precision);
1492  out << std::fixed << val;
1493  return out.str();
1494 }
1495 
1496 } // namespace nav2_rviz_plugins
1497 
1498 #include <pluginlib/class_list_macros.hpp> // NOLINT
1499 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