15 #include "nav2_rviz_plugins/nav2_panel.hpp"
17 #include <QtConcurrent/QtConcurrent>
18 #include <QVBoxLayout>
19 #include <QHBoxLayout>
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"
39 using namespace std::chrono_literals;
41 namespace nav2_rviz_plugins
43 using nav2_util::geometry_utils::orientationAroundZAxis;
46 GoalPoseUpdater GoalUpdater;
48 Nav2Panel::Nav2Panel(QWidget * parent)
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");
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";
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>");
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);
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);
110 pre_initial_->assignProperty(pause_resume_button_,
"text",
"Pause");
111 pre_initial_->assignProperty(pause_resume_button_,
"enabled",
false);
113 pre_initial_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
114 pre_initial_->assignProperty(save_waypoints_button_,
"enabled",
false);
116 pre_initial_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
117 pre_initial_->assignProperty(load_waypoints_button_,
"enabled",
false);
119 pre_initial_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
120 pre_initial_->assignProperty(pause_waypoint_button_,
"enabled",
false);
122 pre_initial_->assignProperty(nr_of_loops_,
"text",
"0");
123 pre_initial_->assignProperty(nr_of_loops_,
"enabled",
false);
125 pre_initial_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
127 pre_initial_->assignProperty(
128 navigation_mode_button_,
"text",
129 "Waypoint / Nav Through Poses Mode");
130 pre_initial_->assignProperty(navigation_mode_button_,
"enabled",
false);
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);
138 initial_->assignProperty(pause_resume_button_,
"text",
"Pause");
139 initial_->assignProperty(pause_resume_button_,
"enabled",
false);
141 initial_->assignProperty(navigation_mode_button_,
"text",
"Waypoint / Nav Through Poses Mode");
142 initial_->assignProperty(navigation_mode_button_,
"enabled",
false);
144 initial_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
145 initial_->assignProperty(save_waypoints_button_,
"enabled",
false);
147 initial_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
148 initial_->assignProperty(load_waypoints_button_,
"enabled",
false);
150 initial_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
151 initial_->assignProperty(pause_waypoint_button_,
"enabled",
false);
153 initial_->assignProperty(nr_of_loops_,
"text",
"0");
154 initial_->assignProperty(nr_of_loops_,
"enabled",
false);
156 initial_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
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);
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);
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);
173 idle_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
174 idle_->assignProperty(save_waypoints_button_,
"enabled",
false);
176 idle_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
177 idle_->assignProperty(load_waypoints_button_,
"enabled",
false);
179 idle_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
180 idle_->assignProperty(pause_waypoint_button_,
"enabled",
false);
182 idle_->assignProperty(nr_of_loops_,
"text",
"0");
183 idle_->assignProperty(nr_of_loops_,
"enabled",
false);
185 idle_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
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);
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);
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);
202 accumulating_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
203 accumulating_->assignProperty(save_waypoints_button_,
"enabled",
true);
205 accumulating_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
206 accumulating_->assignProperty(load_waypoints_button_,
"enabled",
true);
208 accumulating_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
209 accumulating_->assignProperty(pause_waypoint_button_,
"enabled",
false);
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);
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);
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);
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);
229 accumulated_wp_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
230 accumulated_wp_->assignProperty(save_waypoints_button_,
"enabled",
false);
232 accumulated_wp_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
233 accumulated_wp_->assignProperty(load_waypoints_button_,
"enabled",
false);
235 accumulated_wp_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
236 accumulated_wp_->assignProperty(pause_waypoint_button_,
"enabled",
true);
238 accumulated_wp_->assignProperty(nr_of_loops_,
"enabled",
false);
239 accumulated_wp_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
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);
246 accumulated_nav_through_poses_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
247 accumulated_nav_through_poses_->assignProperty(save_waypoints_button_,
"enabled",
false);
249 accumulated_nav_through_poses_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
250 accumulated_nav_through_poses_->assignProperty(load_waypoints_button_,
"enabled",
false);
252 accumulated_nav_through_poses_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
253 accumulated_nav_through_poses_->assignProperty(pause_waypoint_button_,
"enabled",
false);
255 accumulated_nav_through_poses_->assignProperty(nr_of_loops_,
"enabled",
false);
257 accumulated_nav_through_poses_->assignProperty(start_reset_button_,
"enabled",
true);
258 accumulated_nav_through_poses_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
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);
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",
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);
281 canceled_ =
new QState();
282 canceled_->setObjectName(
"canceled");
285 reset_ =
new QState();
286 reset_->setObjectName(
"reset");
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);
293 running_->assignProperty(pause_resume_button_,
"text",
"Pause");
294 running_->assignProperty(pause_resume_button_,
"enabled",
false);
296 running_->assignProperty(navigation_mode_button_,
"text",
"Waypoint mode");
297 running_->assignProperty(navigation_mode_button_,
"enabled",
false);
299 running_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
300 running_->assignProperty(save_waypoints_button_,
"enabled",
false);
302 running_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
303 running_->assignProperty(load_waypoints_button_,
"enabled",
false);
305 running_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
306 running_->assignProperty(pause_waypoint_button_,
"enabled",
false);
308 running_->assignProperty(nr_of_loops_,
"text",
"0");
309 running_->assignProperty(nr_of_loops_,
"enabled",
false);
311 running_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
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);
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);
323 paused_->assignProperty(navigation_mode_button_,
"text",
"");
324 paused_->assignProperty(navigation_mode_button_,
"enabled",
false);
326 paused_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
327 paused_->assignProperty(save_waypoints_button_,
"enabled",
false);
329 paused_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
330 paused_->assignProperty(load_waypoints_button_,
"enabled",
false);
332 paused_->assignProperty(pause_waypoint_button_,
"text",
"Pause WP");
333 paused_->assignProperty(pause_waypoint_button_,
"enabled",
false);
335 paused_->assignProperty(nr_of_loops_,
"enabled",
false);
337 paused_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
340 resumed_ =
new QState();
341 resumed_->setObjectName(
"resuming");
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);
349 resumed_wp_->assignProperty(pause_resume_button_,
"text",
"Start Nav Through Poses");
350 resumed_wp_->assignProperty(pause_resume_button_,
"enabled",
false);
352 resumed_wp_->assignProperty(navigation_mode_button_,
"text",
"Start Waypoint Following");
353 resumed_wp_->assignProperty(navigation_mode_button_,
"enabled",
false);
355 resumed_wp_->assignProperty(save_waypoints_button_,
"text",
"Save WPs");
356 resumed_wp_->assignProperty(save_waypoints_button_,
"enabled",
true);
358 resumed_wp_->assignProperty(load_waypoints_button_,
"text",
"Load WPs");
359 resumed_wp_->assignProperty(load_waypoints_button_,
"enabled",
false);
361 resumed_wp_->assignProperty(pause_waypoint_button_,
"text",
"Resume WP");
362 resumed_wp_->assignProperty(pause_waypoint_button_,
"enabled",
true);
364 resumed_wp_->assignProperty(nr_of_loops_,
"enabled",
false);
365 resumed_wp_->assignProperty(store_initial_pose_checkbox_,
"enabled",
false);
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()));
376 accumulated_nav_through_poses_, SIGNAL(entered()),
this,
377 SLOT(onAccumulatedNTP()));
379 save_waypoints_button_,
380 &QPushButton::released,
381 this, &Nav2Panel::handleGoalSaver);
383 load_waypoints_button_,
384 &QPushButton::released,
386 &Nav2Panel::handleGoalLoader);
389 &QLineEdit::editingFinished,
391 &Nav2Panel::loophandler);
393 store_initial_pose_checkbox_,
394 &QCheckBox::stateChanged,
396 &Nav2Panel::initialStateHandler);
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_);
413 canceled_->addTransition(canceled_, SIGNAL(entered()), idle_);
414 reset_->addTransition(reset_, SIGNAL(entered()), initial_);
415 resumed_->addTransition(resumed_, SIGNAL(entered()), idle_);
418 idle_->addTransition(pause_resume_button_, SIGNAL(clicked()), paused_);
419 paused_->addTransition(pause_resume_button_, SIGNAL(clicked()), resumed_);
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_);
429 ROSActionQTransition * idleTransition =
new ROSActionQTransition(QActionState::INACTIVE);
430 idleTransition->setTargetState(running_);
431 idle_->addTransition(idleTransition);
433 ROSActionQTransition * runningTransition =
new ROSActionQTransition(QActionState::ACTIVE);
434 runningTransition->setTargetState(idle_);
435 running_->addTransition(runningTransition);
437 ROSActionQTransition * idleAccumulatedWpTransition =
438 new ROSActionQTransition(QActionState::INACTIVE);
439 idleAccumulatedWpTransition->setTargetState(accumulated_wp_);
440 idle_->addTransition(idleAccumulatedWpTransition);
442 ROSActionQTransition * accumulatedWpTransition =
new ROSActionQTransition(QActionState::ACTIVE);
443 accumulatedWpTransition->setTargetState(accumulating_);
444 accumulated_wp_->addTransition(accumulatedWpTransition);
446 ROSActionQTransition * idleAccumulatedNTPTransition =
447 new ROSActionQTransition(QActionState::INACTIVE);
448 idleAccumulatedNTPTransition->setTargetState(accumulated_nav_through_poses_);
449 idle_->addTransition(idleAccumulatedNTPTransition);
451 ROSActionQTransition * accumulatedNTPTransition =
new ROSActionQTransition(QActionState::ACTIVE);
452 accumulatedNTPTransition->setTargetState(idle_);
453 accumulated_nav_through_poses_->addTransition(accumulatedNTPTransition);
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_);
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);
468 QSignalTransition * activeSignal =
new QSignalTransition(
470 &InitialThread::navigationActive);
471 activeSignal->setTargetState(idle_);
472 pre_initial_->addTransition(activeSignal);
473 QSignalTransition * inactiveSignal =
new QSignalTransition(
475 &InitialThread::navigationInactive);
476 inactiveSignal->setTargetState(initial_);
477 pre_initial_->addTransition(inactiveSignal);
480 initial_thread_, &InitialThread::navigationActive,
481 [
this, navigation_active] {
482 navigation_status_indicator_->setText(navigation_active);
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());
492 initial_thread_, &InitialThread::localizationActive,
493 [
this, localization_active] {
494 localization_status_indicator_->setText(localization_active);
497 initial_thread_, &InitialThread::localizationInactive,
498 [
this, localization_inactive] {
499 localization_status_indicator_->setText(localization_inactive);
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_);
515 state_machine_.setInitialState(pre_initial_);
518 QObject::connect(&state_machine_, SIGNAL(started()),
this, SLOT(startThread()));
519 state_machine_.start();
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;
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"));
533 status_layout->addWidget(navigation_status_indicator_);
534 status_layout->addWidget(localization_status_indicator_);
535 status_layout->addWidget(navigation_goal_status_indicator_);
537 logo_layout->addWidget(imgDisplayLabel_, 5, Qt::AlignRight);
539 side_layout->addLayout(status_layout);
540 side_layout->addLayout(logo_layout);
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_);
549 QHBoxLayout * group_box_l1_layout =
new QHBoxLayout;
550 QHBoxLayout * group_box_l2_layout =
new QHBoxLayout;
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_);
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_);
560 group_box_layout->addLayout(group_box_l1_layout);
561 group_box_layout->addLayout(group_box_l2_layout);
563 groupBox->setLayout(group_box_layout);
565 main_layout->addWidget(groupBox);
566 main_layout->setContentsMargins(10, 10, 10, 10);
567 setLayout(main_layout);
569 navigation_action_client_ =
570 rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
573 waypoint_follower_action_client_ =
574 rclcpp_action::create_client<nav2_msgs::action::FollowWaypoints>(
577 nav_through_poses_action_client_ =
578 rclcpp_action::create_client<nav2_msgs::action::NavigateThroughPoses>(
580 "navigate_through_poses");
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_);
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();
594 wp_navigation_markers_pub_ =
595 client_node_->create_publisher<visualization_msgs::msg::MarkerArray>(
597 rclcpp::QoS(1).transient_local());
600 &GoalUpdater, SIGNAL(updateGoal(
double,
double,
double,QString)),
601 this, SLOT(onNewGoal(
double,
double,
double,QString)));
604 Nav2Panel::~Nav2Panel()
608 void Nav2Panel::initialStateHandler()
610 if (store_initial_pose_checkbox_->isChecked()) {
611 store_initial_pose_ =
true;
614 store_initial_pose_ =
false;
618 bool Nav2Panel::isLoopValueValid(std::string & loop_value)
621 if (loop_value.empty()) {
622 std::cout <<
"Loop value cannot be set to empty, setting to 0" << std::endl;
624 nr_of_loops_->setText(
"0");
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);
641 }
catch (std::invalid_argument
const & ex) {
643 waypoint_status_indicator_->setText(
"<b> Note: </b> Set a valid value for the loop");
644 navigation_mode_button_->setEnabled(
false);
646 }
catch (std::out_of_range
const & ex) {
648 waypoint_status_indicator_->setText(
649 "<b> Note: </b> Loop value out of range, setting max possible value"
651 loop_value = std::to_string(std::numeric_limits<int>::max());
652 nr_of_loops_->setText(QString::fromStdString(loop_value));
657 void Nav2Panel::loophandler()
659 loop_no_ = nr_of_loops_->displayText().toStdString();
662 if (!isLoopValueValid(loop_no_)) {
667 navigation_mode_button_->setEnabled(
true);
670 if (!loop_no_.empty() && stoi(loop_no_) > 0) {
671 pause_resume_button_->setEnabled(
false);
673 pause_resume_button_->setEnabled(
true);
677 void Nav2Panel::handleGoalLoader()
679 acummulated_poses_ = nav_msgs::msg::Goals();
681 std::cout <<
"Loading Waypoints!" << std::endl;
683 QString file = QFileDialog::getOpenFileName(
686 tr(
"yaml(*.yaml);;All Files (*)"));
688 YAML::Node available_waypoints;
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();
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));
707 updateWpNavigationMarkers();
710 geometry_msgs::msg::PoseStamped Nav2Panel::convert_to_msg(
711 std::vector<double> pose,
712 std::vector<double> orientation)
714 auto msg = geometry_msgs::msg::PoseStamped();
716 msg.header.frame_id =
"map";
719 msg.pose.position.x = pose[0];
720 msg.pose.position.y = pose[1];
721 msg.pose.position.z = pose[2];
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];
731 void Nav2Panel::handleGoalSaver()
735 if (acummulated_poses_.goals.empty()) {
736 std::cout <<
"No accumulated Points to Save!" << std::endl;
739 std::cout <<
"Saving Waypoints!" << std::endl;
743 out << YAML::BeginMap;
744 out << YAML::Key <<
"waypoints";
745 out << YAML::BeginMap;
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;
766 QString file = QFileDialog::getSaveFileName(
769 tr(
"yaml(*.yaml);;All Files (*)"));
771 if (!file.toStdString().empty()) {
772 std::ofstream fout(file.toStdString() +
".yaml");
774 std::cout <<
"Saving waypoints succeeded" << std::endl;
776 std::cout <<
"Saving waypoints aborted" << std::endl;
781 Nav2Panel::onInitialize()
783 node_ptr_ = getDisplayContext()->getRosNodeAbstraction().lock();
784 if (node_ptr_ ==
nullptr) {
787 rclcpp::get_logger(
"nav2_panel"),
788 "Underlying ROS node no longer exists, initialization failed");
791 rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
794 node->declare_parameter(
"base_frame", rclcpp::ParameterValue(std::string(
"base_footprint")));
795 node->get_parameter(
"base_frame", base_frame_);
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_) {
806 loop_counter_stop_ =
true;
808 if (goal_index_ != 0) {
809 loop_counter_stop_ =
false;
811 navigation_feedback_indicator_->setText(
812 getNavToPoseFeedbackLabel(msg->feedback) + QString(
814 "</td></tr><tr><td width=150>Waypoint:</td><td>" +
815 toString(goal_index_ + 1)).c_str()) + QString(
817 "</td></tr><tr><td width=150>Loop:</td><td>" +
818 toString(loop_count_)).c_str()));
820 navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel(msg->feedback));
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));
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));
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)
844 store_poses_ = nav_msgs::msg::Goals();
845 waypoint_status_indicator_->clear();
848 navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel());
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());
864 Nav2Panel::startThread()
867 initial_thread_->start();
873 QFuture<void> futureNav =
877 client_nav_.get(), std::placeholders::_1), server_timeout_);
878 QFuture<void> futureLoc =
882 client_loc_.get(), std::placeholders::_1), server_timeout_);
886 Nav2Panel::onResume()
888 QFuture<void> futureNav =
892 client_nav_.get(), std::placeholders::_1), server_timeout_);
893 QFuture<void> futureLoc =
897 client_loc_.get(), std::placeholders::_1), server_timeout_);
901 Nav2Panel::onStartup()
903 QFuture<void> futureNav =
907 client_nav_.get(), std::placeholders::_1), server_timeout_);
908 QFuture<void> futureLoc =
912 client_loc_.get(), std::placeholders::_1), server_timeout_);
916 Nav2Panel::onShutdown()
918 QFuture<void> futureNav =
922 client_nav_.get(), std::placeholders::_1), server_timeout_);
923 QFuture<void> futureLoc =
927 client_loc_.get(), std::placeholders::_1), server_timeout_);
932 Nav2Panel::onCancel()
934 QFuture<void> future =
937 &Nav2Panel::onCancelButtonPressed,
939 waypoint_status_indicator_->clear();
940 store_poses_ = nav_msgs::msg::Goals();
941 acummulated_poses_ = nav_msgs::msg::Goals();
944 void Nav2Panel::onResumedWp()
946 QFuture<void> future =
949 &Nav2Panel::onCancelButtonPressed,
951 acummulated_poses_ = store_poses_;
952 loop_no_ = std::to_string(
953 stoi(nr_of_loops_->displayText().toStdString()) -
955 waypoint_status_indicator_->setText(
956 QString(std::string(
"<b> Note: </b> Navigation is paused.").c_str()));
960 Nav2Panel::onNewGoal(
double x,
double y,
double theta, QString frame)
962 auto pose = geometry_msgs::msg::PoseStamped();
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);
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);
976 acummulated_poses_ = nav_msgs::msg::Goals();
977 updateWpNavigationMarkers();
978 std::cout <<
"Start navigation" << std::endl;
979 startNavigation(pose);
982 waypoint_status_indicator_->setText(
983 QString(std::string(
"<b> Note: </b> Cannot set goal in pause state").c_str()));
985 updateWpNavigationMarkers();
989 Nav2Panel::onCancelButtonPressed()
991 if (navigation_goal_handle_) {
992 auto future_cancel = navigation_action_client_->async_cancel_goal(navigation_goal_handle_);
994 if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
995 rclcpp::FutureReturnCode::SUCCESS)
997 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel goal");
999 navigation_goal_handle_.reset();
1003 if (waypoint_follower_goal_handle_) {
1004 auto future_cancel =
1005 waypoint_follower_action_client_->async_cancel_goal(waypoint_follower_goal_handle_);
1007 if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
1008 rclcpp::FutureReturnCode::SUCCESS)
1010 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel waypoint follower");
1012 waypoint_follower_goal_handle_.reset();
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_);
1020 if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
1021 rclcpp::FutureReturnCode::SUCCESS)
1023 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel nav through pose action");
1025 nav_through_poses_goal_handle_.reset();
1033 Nav2Panel::onAccumulatedWp()
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");
1043 if (!isLoopValueValid(loop_no_)) {
1044 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
1049 waypoint_status_indicator_->clear();
1052 navigation_mode_button_->setEnabled(
false);
1053 pause_resume_button_->setEnabled(
false);
1057 if (store_poses_.goals.empty()) {
1058 std::cout <<
"Start waypoint" << std::endl;
1061 nr_of_loops_->setText(QString::fromStdString(loop_no_));
1064 geometry_msgs::msg::TransformStamped init_transform;
1067 if (store_initial_pose_) {
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) {
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());
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;
1091 acummulated_poses_.goals.insert(acummulated_poses_.goals.begin(), initial_pose);
1092 updateWpNavigationMarkers();
1093 initial_pose_stored_ =
true;
1094 if (loop_count_ == 0) {
1097 }
else if (!store_initial_pose_ && initial_pose_stored_) {
1098 acummulated_poses_.goals.erase(
1099 acummulated_poses_.goals.begin(),
1100 acummulated_poses_.goals.begin());
1103 std::cout <<
"Resuming waypoint" << std::endl;
1106 startWaypointFollowing(acummulated_poses_.goals);
1107 store_poses_ = acummulated_poses_;
1108 acummulated_poses_ = nav_msgs::msg::Goals();
1112 Nav2Panel::onAccumulatedNTP()
1114 std::cout <<
"Start navigate through poses" << std::endl;
1115 startNavThroughPoses(acummulated_poses_);
1119 Nav2Panel::onAccumulating()
1121 acummulated_poses_ = nav_msgs::msg::Goals();
1122 store_poses_ = nav_msgs::msg::Goals();
1125 initial_pose_stored_ =
false;
1126 loop_counter_stop_ =
true;
1128 updateWpNavigationMarkers();
1132 Nav2Panel::timerEvent(QTimerEvent * event)
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));
1142 executor_->spin_some();
1143 auto status = waypoint_follower_goal_handle_->get_status();
1146 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1147 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1149 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
1151 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
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));
1163 executor_->spin_some();
1164 auto status = nav_through_poses_goal_handle_->get_status();
1167 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1168 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1170 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
1172 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
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));
1184 executor_->spin_some();
1185 auto status = navigation_goal_handle_->get_status();
1188 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
1189 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
1191 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
1193 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
1201 Nav2Panel::startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses)
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) {
1207 client_node_->get_logger(),
"follow_waypoints action server is not available."
1208 " Is the initial pose set?");
1213 waypoint_follower_goal_.poses = poses;
1214 waypoint_follower_goal_.goal_index = goal_index_;
1215 waypoint_follower_goal_.number_of_loops = stoi(loop_no_);
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) {
1222 client_node_->get_logger(),
1223 "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
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();
1233 send_goal_options.feedback_callback = [
this](
1234 WaypointFollowerGoalHandle::SharedPtr ,
1235 const std::shared_ptr<const nav2_msgs::action::FollowWaypoints::Feedback> feedback) {
1236 goal_index_ = feedback->current_waypoint;
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)
1244 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
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");
1255 timer_.start(200,
this);
1259 Nav2Panel::startNavThroughPoses(nav_msgs::msg::Goals poses)
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) {
1265 client_node_->get_logger(),
"navigate_through_poses action server is not available."
1266 " Is the initial pose set?");
1270 nav_through_poses_goal_.poses = poses;
1272 client_node_->get_logger(),
1273 "NavigateThroughPoses will be called using the BT Navigator's default behavior tree.");
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) {
1280 client_node_->get_logger(),
1281 "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
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();
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)
1296 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
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");
1307 timer_.start(200,
this);
1311 Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose)
1313 auto is_action_server_ready =
1314 navigation_action_client_->wait_for_action_server(std::chrono::seconds(5));
1315 if (!is_action_server_ready) {
1317 client_node_->get_logger(),
1318 "navigate_to_pose action server is not available."
1319 " Is the initial pose set?");
1324 navigation_goal_.pose = pose;
1327 client_node_->get_logger(),
1328 "NavigateToPose will be called using the BT Navigator's default behavior tree.");
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();
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)
1342 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
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");
1353 timer_.start(200,
this);
1357 Nav2Panel::save(rviz_common::Config config)
const
1359 Panel::save(config);
1363 Nav2Panel::load(
const rviz_common::Config & config)
1365 Panel::load(config);
1369 Nav2Panel::resetUniqueId()
1375 Nav2Panel::getUniqueId()
1377 int temp_id = unique_id;
1383 Nav2Panel::updateWpNavigationMarkers()
1387 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
1389 for (
size_t i = 0; i < acummulated_poses_.goals.size(); i++) {
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);
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);
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;
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);
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);
1453 wp_navigation_markers_pub_->publish(std::move(marker_array));
1457 Nav2Panel::getNavToPoseFeedbackLabel(nav2_msgs::action::NavigateToPose::Feedback msg)
1459 return QString(std::string(
"<table>" + toLabel(msg) +
"</table>").c_str());
1463 Nav2Panel::getNavThroughPosesFeedbackLabel(nav2_msgs::action::NavigateThroughPoses::Feedback msg)
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());
1472 template<
typename T>
1473 inline std::string Nav2Panel::toLabel(T & msg)
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) +
1488 Nav2Panel::toString(
double val,
int precision)
1490 std::ostringstream out;
1491 out.precision(precision);
1492 out << std::fixed << val;
1498 #include <pluginlib/class_list_macros.hpp>
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.