15 #include "nav2_rviz_plugins/nav2_panel.hpp"
17 #include <QtConcurrent/QtConcurrent>
18 #include <QVBoxLayout>
26 #include "nav2_rviz_plugins/goal_common.hpp"
27 #include "rviz_common/display_context.hpp"
28 #include "ament_index_cpp/get_package_share_directory.hpp"
30 using namespace std::chrono_literals;
32 namespace nav2_rviz_plugins
34 using nav2_util::geometry_utils::orientationAroundZAxis;
37 GoalPoseUpdater GoalUpdater;
39 Nav2Panel::Nav2Panel(QWidget * parent)
45 start_reset_button_ =
new QPushButton;
46 pause_resume_button_ =
new QPushButton;
47 navigation_mode_button_ =
new QPushButton;
48 navigation_status_indicator_ =
new QLabel;
49 localization_status_indicator_ =
new QLabel;
50 navigation_goal_status_indicator_ =
new QLabel;
51 navigation_feedback_indicator_ =
new QLabel;
55 const char * startup_msg =
"Configure and activate all nav2 lifecycle nodes";
56 const char * shutdown_msg =
"Deactivate and cleanup all nav2 lifecycle nodes";
57 const char * cancel_msg =
"Cancel navigation";
58 const char * pause_msg =
"Deactivate all nav2 lifecycle nodes";
59 const char * resume_msg =
"Activate all nav2 lifecycle nodes";
60 const char * single_goal_msg =
"Change to waypoint / nav through poses style navigation";
61 const char * waypoint_goal_msg =
"Start following waypoints";
62 const char * nft_goal_msg =
"Start navigating through poses";
63 const char * cancel_waypoint_msg =
"Cancel waypoint / viapoint accumulation mode";
65 const QString navigation_active(
"<table><tr><td width=100><b>Navigation:</b></td>"
66 "<td><font color=green>active</color></td></tr></table>");
67 const QString navigation_inactive(
"<table><tr><td width=100><b>Navigation:</b></td>"
68 "<td>inactive</td></tr></table>");
69 const QString navigation_unknown(
"<table><tr><td width=100><b>Navigation:</b></td>"
70 "<td>unknown</td></tr></table>");
71 const QString localization_active(
"<table><tr><td width=100><b>Localization:</b></td>"
72 "<td><font color=green>active</color></td></tr></table>");
73 const QString localization_inactive(
"<table><tr><td width=100><b>Localization:</b></td>"
74 "<td>inactive</td></tr></table>");
75 const QString localization_unknown(
"<table><tr><td width=100><b>Localization:</b></td>"
76 "<td>unknown</td></tr></table>");
78 navigation_status_indicator_->setText(navigation_unknown);
79 localization_status_indicator_->setText(localization_unknown);
80 navigation_goal_status_indicator_->setText(getGoalStatusLabel());
81 navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
82 navigation_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
83 localization_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
84 navigation_goal_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
85 navigation_feedback_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
87 pre_initial_ =
new QState();
88 pre_initial_->setObjectName(
"pre_initial");
89 pre_initial_->assignProperty(start_reset_button_,
"text",
"Startup");
90 pre_initial_->assignProperty(start_reset_button_,
"enabled",
false);
92 pre_initial_->assignProperty(pause_resume_button_,
"text",
"Pause");
93 pre_initial_->assignProperty(pause_resume_button_,
"enabled",
false);
95 pre_initial_->assignProperty(
96 navigation_mode_button_,
"text",
97 "Waypoint / Nav Through Poses Mode");
98 pre_initial_->assignProperty(navigation_mode_button_,
"enabled",
false);
100 initial_ =
new QState();
101 initial_->setObjectName(
"initial");
102 initial_->assignProperty(start_reset_button_,
"text",
"Startup");
103 initial_->assignProperty(start_reset_button_,
"toolTip", startup_msg);
104 initial_->assignProperty(start_reset_button_,
"enabled",
true);
106 initial_->assignProperty(pause_resume_button_,
"text",
"Pause");
107 initial_->assignProperty(pause_resume_button_,
"enabled",
false);
109 initial_->assignProperty(navigation_mode_button_,
"text",
"Waypoint / Nav Through Poses Mode");
110 initial_->assignProperty(navigation_mode_button_,
"enabled",
false);
113 idle_ =
new QState();
114 idle_->setObjectName(
"idle");
115 idle_->assignProperty(start_reset_button_,
"text",
"Reset");
116 idle_->assignProperty(start_reset_button_,
"toolTip", shutdown_msg);
117 idle_->assignProperty(start_reset_button_,
"enabled",
true);
119 idle_->assignProperty(pause_resume_button_,
"text",
"Pause");
120 idle_->assignProperty(pause_resume_button_,
"enabled",
true);
121 idle_->assignProperty(pause_resume_button_,
"toolTip", pause_msg);
123 idle_->assignProperty(navigation_mode_button_,
"text",
"Waypoint / Nav Through Poses Mode");
124 idle_->assignProperty(navigation_mode_button_,
"enabled",
true);
125 idle_->assignProperty(navigation_mode_button_,
"toolTip", single_goal_msg);
128 accumulating_ =
new QState();
129 accumulating_->setObjectName(
"accumulating");
130 accumulating_->assignProperty(start_reset_button_,
"text",
"Cancel Accumulation");
131 accumulating_->assignProperty(start_reset_button_,
"toolTip", cancel_waypoint_msg);
132 accumulating_->assignProperty(start_reset_button_,
"enabled",
true);
134 accumulating_->assignProperty(pause_resume_button_,
"text",
"Start Nav Through Poses");
135 accumulating_->assignProperty(pause_resume_button_,
"enabled",
true);
136 accumulating_->assignProperty(pause_resume_button_,
"toolTip", nft_goal_msg);
138 accumulating_->assignProperty(navigation_mode_button_,
"text",
"Start Waypoint Following");
139 accumulating_->assignProperty(navigation_mode_button_,
"enabled",
true);
140 accumulating_->assignProperty(navigation_mode_button_,
"toolTip", waypoint_goal_msg);
142 accumulated_wp_ =
new QState();
143 accumulated_wp_->setObjectName(
"accumulated_wp");
144 accumulated_wp_->assignProperty(start_reset_button_,
"text",
"Cancel");
145 accumulated_wp_->assignProperty(start_reset_button_,
"toolTip", cancel_msg);
146 accumulated_wp_->assignProperty(start_reset_button_,
"enabled",
true);
148 accumulated_wp_->assignProperty(pause_resume_button_,
"text",
"Start Nav Through Poses");
149 accumulated_wp_->assignProperty(pause_resume_button_,
"enabled",
false);
150 accumulated_wp_->assignProperty(pause_resume_button_,
"toolTip", nft_goal_msg);
152 accumulated_wp_->assignProperty(navigation_mode_button_,
"text",
"Start Waypoint Following");
153 accumulated_wp_->assignProperty(navigation_mode_button_,
"enabled",
false);
154 accumulated_wp_->assignProperty(navigation_mode_button_,
"toolTip", waypoint_goal_msg);
156 accumulated_nav_through_poses_ =
new QState();
157 accumulated_nav_through_poses_->setObjectName(
"accumulated_nav_through_poses");
158 accumulated_nav_through_poses_->assignProperty(start_reset_button_,
"text",
"Cancel");
159 accumulated_nav_through_poses_->assignProperty(start_reset_button_,
"toolTip", cancel_msg);
160 accumulated_nav_through_poses_->assignProperty(start_reset_button_,
"enabled",
true);
162 accumulated_nav_through_poses_->assignProperty(
163 pause_resume_button_,
"text",
164 "Start Nav Through Poses");
165 accumulated_nav_through_poses_->assignProperty(pause_resume_button_,
"enabled",
false);
166 accumulated_nav_through_poses_->assignProperty(pause_resume_button_,
"toolTip", nft_goal_msg);
168 accumulated_nav_through_poses_->assignProperty(
169 navigation_mode_button_,
"text",
170 "Start Waypoint Following");
171 accumulated_nav_through_poses_->assignProperty(navigation_mode_button_,
"enabled",
false);
172 accumulated_nav_through_poses_->assignProperty(
173 navigation_mode_button_,
"toolTip",
177 canceled_ =
new QState();
178 canceled_->setObjectName(
"canceled");
181 reset_ =
new QState();
182 reset_->setObjectName(
"reset");
185 running_ =
new QState();
186 running_->setObjectName(
"running");
187 running_->assignProperty(start_reset_button_,
"text",
"Cancel");
188 running_->assignProperty(start_reset_button_,
"toolTip", cancel_msg);
190 running_->assignProperty(pause_resume_button_,
"text",
"Pause");
191 running_->assignProperty(pause_resume_button_,
"enabled",
false);
193 running_->assignProperty(navigation_mode_button_,
"text",
"Waypoint mode");
194 running_->assignProperty(navigation_mode_button_,
"enabled",
false);
197 paused_ =
new QState();
198 paused_->setObjectName(
"pausing");
199 paused_->assignProperty(start_reset_button_,
"text",
"Reset");
200 paused_->assignProperty(start_reset_button_,
"toolTip", shutdown_msg);
202 paused_->assignProperty(pause_resume_button_,
"text",
"Resume");
203 paused_->assignProperty(pause_resume_button_,
"toolTip", resume_msg);
204 paused_->assignProperty(pause_resume_button_,
"enabled",
true);
206 paused_->assignProperty(navigation_mode_button_,
"text",
"Start navigation");
207 paused_->assignProperty(navigation_mode_button_,
"toolTip", resume_msg);
208 paused_->assignProperty(navigation_mode_button_,
"enabled",
true);
211 resumed_ =
new QState();
212 resumed_->setObjectName(
"resuming");
214 QObject::connect(initial_, SIGNAL(exited()),
this, SLOT(onStartup()));
215 QObject::connect(canceled_, SIGNAL(exited()),
this, SLOT(onCancel()));
216 QObject::connect(reset_, SIGNAL(exited()),
this, SLOT(onShutdown()));
217 QObject::connect(paused_, SIGNAL(entered()),
this, SLOT(onPause()));
218 QObject::connect(resumed_, SIGNAL(exited()),
this, SLOT(onResume()));
219 QObject::connect(accumulating_, SIGNAL(entered()),
this, SLOT(onAccumulating()));
220 QObject::connect(accumulated_wp_, SIGNAL(entered()),
this, SLOT(onAccumulatedWp()));
222 accumulated_nav_through_poses_, SIGNAL(entered()),
this,
223 SLOT(onAccumulatedNTP()));
226 initial_->addTransition(start_reset_button_, SIGNAL(clicked()), idle_);
227 idle_->addTransition(start_reset_button_, SIGNAL(clicked()), reset_);
228 running_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
229 paused_->addTransition(start_reset_button_, SIGNAL(clicked()), reset_);
230 idle_->addTransition(navigation_mode_button_, SIGNAL(clicked()), accumulating_);
231 accumulating_->addTransition(navigation_mode_button_, SIGNAL(clicked()), accumulated_wp_);
232 accumulating_->addTransition(
233 pause_resume_button_, SIGNAL(
234 clicked()), accumulated_nav_through_poses_);
235 accumulating_->addTransition(start_reset_button_, SIGNAL(clicked()), idle_);
236 accumulated_wp_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
237 accumulated_nav_through_poses_->addTransition(start_reset_button_, SIGNAL(clicked()), canceled_);
240 canceled_->addTransition(canceled_, SIGNAL(entered()), idle_);
241 reset_->addTransition(reset_, SIGNAL(entered()), initial_);
242 resumed_->addTransition(resumed_, SIGNAL(entered()), idle_);
245 idle_->addTransition(pause_resume_button_, SIGNAL(clicked()), paused_);
246 paused_->addTransition(pause_resume_button_, SIGNAL(clicked()), resumed_);
251 ROSActionQTransition * idleTransition =
new ROSActionQTransition(QActionState::INACTIVE);
252 idleTransition->setTargetState(running_);
253 idle_->addTransition(idleTransition);
255 ROSActionQTransition * runningTransition =
new ROSActionQTransition(QActionState::ACTIVE);
256 runningTransition->setTargetState(idle_);
257 running_->addTransition(runningTransition);
259 ROSActionQTransition * idleAccumulatedWpTransition =
260 new ROSActionQTransition(QActionState::INACTIVE);
261 idleAccumulatedWpTransition->setTargetState(accumulated_wp_);
262 idle_->addTransition(idleAccumulatedWpTransition);
264 ROSActionQTransition * accumulatedWpTransition =
new ROSActionQTransition(QActionState::ACTIVE);
265 accumulatedWpTransition->setTargetState(idle_);
266 accumulated_wp_->addTransition(accumulatedWpTransition);
268 ROSActionQTransition * idleAccumulatedNTPTransition =
269 new ROSActionQTransition(QActionState::INACTIVE);
270 idleAccumulatedNTPTransition->setTargetState(accumulated_nav_through_poses_);
271 idle_->addTransition(idleAccumulatedNTPTransition);
273 ROSActionQTransition * accumulatedNTPTransition =
new ROSActionQTransition(QActionState::ACTIVE);
274 accumulatedNTPTransition->setTargetState(idle_);
275 accumulated_nav_through_poses_->addTransition(accumulatedNTPTransition);
277 auto options = rclcpp::NodeOptions().arguments(
278 {
"--ros-args",
"--remap",
"__node:=rviz_navigation_dialog_action_client",
"--"});
279 client_node_ = std::make_shared<rclcpp::Node>(
"_", options);
281 client_nav_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
282 "lifecycle_manager_navigation", client_node_);
283 client_loc_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
284 "lifecycle_manager_localization", client_node_);
285 initial_thread_ =
new InitialThread(client_nav_, client_loc_);
286 connect(initial_thread_, &InitialThread::finished, initial_thread_, &QObject::deleteLater);
288 QSignalTransition * activeSignal =
new QSignalTransition(
290 &InitialThread::navigationActive);
291 activeSignal->setTargetState(idle_);
292 pre_initial_->addTransition(activeSignal);
294 QSignalTransition * inactiveSignal =
new QSignalTransition(
296 &InitialThread::navigationInactive);
297 inactiveSignal->setTargetState(initial_);
298 pre_initial_->addTransition(inactiveSignal);
301 initial_thread_, &InitialThread::navigationActive,
302 [
this, navigation_active] {
303 navigation_status_indicator_->setText(navigation_active);
306 initial_thread_, &InitialThread::navigationInactive,
307 [
this, navigation_inactive] {
308 navigation_status_indicator_->setText(navigation_inactive);
309 navigation_goal_status_indicator_->setText(getGoalStatusLabel());
310 navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
313 initial_thread_, &InitialThread::localizationActive,
314 [
this, localization_active] {
315 localization_status_indicator_->setText(localization_active);
318 initial_thread_, &InitialThread::localizationInactive,
319 [
this, localization_inactive] {
320 localization_status_indicator_->setText(localization_inactive);
323 state_machine_.addState(pre_initial_);
324 state_machine_.addState(initial_);
325 state_machine_.addState(idle_);
326 state_machine_.addState(running_);
327 state_machine_.addState(canceled_);
328 state_machine_.addState(reset_);
329 state_machine_.addState(paused_);
330 state_machine_.addState(resumed_);
331 state_machine_.addState(accumulating_);
332 state_machine_.addState(accumulated_wp_);
333 state_machine_.addState(accumulated_nav_through_poses_);
335 state_machine_.setInitialState(pre_initial_);
338 QObject::connect(&state_machine_, SIGNAL(started()),
this, SLOT(startThread()));
339 state_machine_.start();
342 QVBoxLayout * main_layout =
new QVBoxLayout;
343 main_layout->addWidget(navigation_status_indicator_);
344 main_layout->addWidget(localization_status_indicator_);
345 main_layout->addWidget(navigation_goal_status_indicator_);
346 main_layout->addWidget(navigation_feedback_indicator_);
347 main_layout->addWidget(pause_resume_button_);
348 main_layout->addWidget(start_reset_button_);
349 main_layout->addWidget(navigation_mode_button_);
351 main_layout->setContentsMargins(10, 10, 10, 10);
352 setLayout(main_layout);
354 navigation_action_client_ =
355 rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
358 waypoint_follower_action_client_ =
359 rclcpp_action::create_client<nav2_msgs::action::FollowWaypoints>(
362 nav_through_poses_action_client_ =
363 rclcpp_action::create_client<nav2_msgs::action::NavigateThroughPoses>(
365 "navigate_through_poses");
366 navigation_goal_ = nav2_msgs::action::NavigateToPose::Goal();
367 waypoint_follower_goal_ = nav2_msgs::action::FollowWaypoints::Goal();
368 nav_through_poses_goal_ = nav2_msgs::action::NavigateThroughPoses::Goal();
370 wp_navigation_markers_pub_ =
371 client_node_->create_publisher<visualization_msgs::msg::MarkerArray>(
373 rclcpp::QoS(1).transient_local());
376 &GoalUpdater, SIGNAL(updateGoal(
double,
double,
double,QString)),
377 this, SLOT(onNewGoal(
double,
double,
double,QString)));
380 Nav2Panel::~Nav2Panel()
385 Nav2Panel::onInitialize()
387 auto node = getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();
390 navigation_feedback_sub_ =
391 node->create_subscription<nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage>(
392 "navigate_to_pose/_action/feedback",
393 rclcpp::SystemDefaultsQoS(),
394 [
this](
const nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage::SharedPtr msg) {
395 navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel(msg->feedback));
397 nav_through_poses_feedback_sub_ =
398 node->create_subscription<nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage>(
399 "navigate_through_poses/_action/feedback",
400 rclcpp::SystemDefaultsQoS(),
401 [
this](
const nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage::SharedPtr msg) {
402 navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel(msg->feedback));
406 navigation_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
407 "navigate_to_pose/_action/status",
408 rclcpp::SystemDefaultsQoS(),
409 [
this](
const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
410 navigation_goal_status_indicator_->setText(
411 getGoalStatusLabel(msg->status_list.back().status));
412 if (msg->status_list.back().status != action_msgs::msg::GoalStatus::STATUS_EXECUTING) {
413 navigation_feedback_indicator_->setText(getNavToPoseFeedbackLabel());
416 nav_through_poses_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
417 "navigate_through_poses/_action/status",
418 rclcpp::SystemDefaultsQoS(),
419 [
this](
const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
420 navigation_goal_status_indicator_->setText(
421 getGoalStatusLabel(msg->status_list.back().status));
422 if (msg->status_list.back().status != action_msgs::msg::GoalStatus::STATUS_EXECUTING) {
423 navigation_feedback_indicator_->setText(getNavThroughPosesFeedbackLabel());
429 Nav2Panel::startThread()
432 initial_thread_->start();
438 QFuture<void> futureNav =
442 client_nav_.get(), std::placeholders::_1), server_timeout_);
443 QFuture<void> futureLoc =
447 client_loc_.get(), std::placeholders::_1), server_timeout_);
451 Nav2Panel::onResume()
453 QFuture<void> futureNav =
457 client_nav_.get(), std::placeholders::_1), server_timeout_);
458 QFuture<void> futureLoc =
462 client_loc_.get(), std::placeholders::_1), server_timeout_);
466 Nav2Panel::onStartup()
468 QFuture<void> futureNav =
472 client_nav_.get(), std::placeholders::_1), server_timeout_);
473 QFuture<void> futureLoc =
477 client_loc_.get(), std::placeholders::_1), server_timeout_);
481 Nav2Panel::onShutdown()
483 QFuture<void> futureNav =
487 client_nav_.get(), std::placeholders::_1), server_timeout_);
488 QFuture<void> futureLoc =
492 client_loc_.get(), std::placeholders::_1), server_timeout_);
497 Nav2Panel::onCancel()
499 QFuture<void> future =
502 &Nav2Panel::onCancelButtonPressed,
507 Nav2Panel::onNewGoal(
double x,
double y,
double theta, QString frame)
509 auto pose = geometry_msgs::msg::PoseStamped();
511 pose.header.stamp = rclcpp::Clock().now();
512 pose.header.frame_id = frame.toStdString();
513 pose.pose.position.x = x;
514 pose.pose.position.y = y;
515 pose.pose.position.z = 0.0;
516 pose.pose.orientation = orientationAroundZAxis(theta);
518 if (state_machine_.configuration().contains(accumulating_)) {
519 acummulated_poses_.push_back(pose);
521 std::cout <<
"Start navigation" << std::endl;
522 startNavigation(pose);
525 updateWpNavigationMarkers();
529 Nav2Panel::onCancelButtonPressed()
531 if (navigation_goal_handle_) {
532 auto future_cancel = navigation_action_client_->async_cancel_goal(navigation_goal_handle_);
534 if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
535 rclcpp::FutureReturnCode::SUCCESS)
537 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel goal");
539 navigation_goal_handle_.reset();
543 if (waypoint_follower_goal_handle_) {
545 waypoint_follower_action_client_->async_cancel_goal(waypoint_follower_goal_handle_);
547 if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
548 rclcpp::FutureReturnCode::SUCCESS)
550 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel waypoint follower");
552 waypoint_follower_goal_handle_.reset();
556 if (nav_through_poses_goal_handle_) {
558 nav_through_poses_action_client_->async_cancel_goal(nav_through_poses_goal_handle_);
560 if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
561 rclcpp::FutureReturnCode::SUCCESS)
563 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel nav through pose action");
565 nav_through_poses_goal_handle_.reset();
574 Nav2Panel::onAccumulatedWp()
576 std::cout <<
"Start waypoint" << std::endl;
577 startWaypointFollowing(acummulated_poses_);
578 acummulated_poses_.clear();
582 Nav2Panel::onAccumulatedNTP()
584 std::cout <<
"Start navigate through poses" << std::endl;
585 startNavThroughPoses(acummulated_poses_);
586 acummulated_poses_.clear();
590 Nav2Panel::onAccumulating()
592 acummulated_poses_.clear();
596 Nav2Panel::timerEvent(QTimerEvent * event)
598 if (state_machine_.configuration().contains(accumulated_wp_)) {
599 if (event->timerId() == timer_.timerId()) {
600 if (!waypoint_follower_goal_handle_) {
601 RCLCPP_DEBUG(client_node_->get_logger(),
"Waiting for Goal");
602 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
606 rclcpp::spin_some(client_node_);
607 auto status = waypoint_follower_goal_handle_->get_status();
610 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
611 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
613 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
615 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
619 }
else if (state_machine_.configuration().contains(accumulated_nav_through_poses_)) {
620 if (event->timerId() == timer_.timerId()) {
621 if (!nav_through_poses_goal_handle_) {
622 RCLCPP_DEBUG(client_node_->get_logger(),
"Waiting for Goal");
623 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
627 rclcpp::spin_some(client_node_);
628 auto status = nav_through_poses_goal_handle_->get_status();
631 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
632 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
634 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
636 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
641 if (event->timerId() == timer_.timerId()) {
642 if (!navigation_goal_handle_) {
643 RCLCPP_DEBUG(client_node_->get_logger(),
"Waiting for Goal");
644 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
648 rclcpp::spin_some(client_node_);
649 auto status = navigation_goal_handle_->get_status();
652 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
653 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
655 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
657 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
665 Nav2Panel::startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses)
667 auto is_action_server_ready =
668 waypoint_follower_action_client_->wait_for_action_server(std::chrono::seconds(5));
669 if (!is_action_server_ready) {
671 client_node_->get_logger(),
"follow_waypoints action server is not available."
672 " Is the initial pose set?");
677 waypoint_follower_goal_.poses = poses;
680 client_node_->get_logger(),
"Sending a path of %zu waypoints:",
681 waypoint_follower_goal_.poses.size());
682 for (
auto waypoint : waypoint_follower_goal_.poses) {
684 client_node_->get_logger(),
685 "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
689 auto send_goal_options =
690 rclcpp_action::Client<nav2_msgs::action::FollowWaypoints>::SendGoalOptions();
691 send_goal_options.result_callback = [
this](
auto) {
692 waypoint_follower_goal_handle_.reset();
695 auto future_goal_handle =
696 waypoint_follower_action_client_->async_send_goal(waypoint_follower_goal_, send_goal_options);
697 if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
698 rclcpp::FutureReturnCode::SUCCESS)
700 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
705 waypoint_follower_goal_handle_ = future_goal_handle.get();
706 if (!waypoint_follower_goal_handle_) {
707 RCLCPP_ERROR(client_node_->get_logger(),
"Goal was rejected by server");
711 timer_.start(200,
this);
715 Nav2Panel::startNavThroughPoses(std::vector<geometry_msgs::msg::PoseStamped> poses)
717 auto is_action_server_ready =
718 nav_through_poses_action_client_->wait_for_action_server(std::chrono::seconds(5));
719 if (!is_action_server_ready) {
721 client_node_->get_logger(),
"navigate_through_poses action server is not available."
722 " Is the initial pose set?");
726 nav_through_poses_goal_.poses = poses;
728 client_node_->get_logger(),
729 "NavigateThroughPoses will be called using the BT Navigator's default behavior tree.");
732 client_node_->get_logger(),
"Sending a path of %zu waypoints:",
733 nav_through_poses_goal_.poses.size());
734 for (
auto waypoint : nav_through_poses_goal_.poses) {
736 client_node_->get_logger(),
737 "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y);
741 auto send_goal_options =
742 rclcpp_action::Client<nav2_msgs::action::NavigateThroughPoses>::SendGoalOptions();
743 send_goal_options.result_callback = [
this](
auto) {
744 nav_through_poses_goal_handle_.reset();
747 auto future_goal_handle =
748 nav_through_poses_action_client_->async_send_goal(nav_through_poses_goal_, send_goal_options);
749 if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
750 rclcpp::FutureReturnCode::SUCCESS)
752 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
757 nav_through_poses_goal_handle_ = future_goal_handle.get();
758 if (!nav_through_poses_goal_handle_) {
759 RCLCPP_ERROR(client_node_->get_logger(),
"Goal was rejected by server");
763 timer_.start(200,
this);
767 Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose)
769 auto is_action_server_ready =
770 navigation_action_client_->wait_for_action_server(std::chrono::seconds(5));
771 if (!is_action_server_ready) {
773 client_node_->get_logger(),
774 "navigate_to_pose action server is not available."
775 " Is the initial pose set?");
780 navigation_goal_.pose = pose;
783 client_node_->get_logger(),
784 "NavigateToPose will be called using the BT Navigator's default behavior tree.");
787 auto send_goal_options =
788 rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SendGoalOptions();
789 send_goal_options.result_callback = [
this](
auto) {
790 navigation_goal_handle_.reset();
793 auto future_goal_handle =
794 navigation_action_client_->async_send_goal(navigation_goal_, send_goal_options);
795 if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
796 rclcpp::FutureReturnCode::SUCCESS)
798 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
803 navigation_goal_handle_ = future_goal_handle.get();
804 if (!navigation_goal_handle_) {
805 RCLCPP_ERROR(client_node_->get_logger(),
"Goal was rejected by server");
809 timer_.start(200,
this);
813 Nav2Panel::save(rviz_common::Config config)
const
819 Nav2Panel::load(
const rviz_common::Config & config)
825 Nav2Panel::resetUniqueId()
831 Nav2Panel::getUniqueId()
833 int temp_id = unique_id;
839 Nav2Panel::updateWpNavigationMarkers()
843 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
845 for (
size_t i = 0; i < acummulated_poses_.size(); i++) {
847 visualization_msgs::msg::Marker arrow_marker;
848 arrow_marker.header = acummulated_poses_[i].header;
849 arrow_marker.id = getUniqueId();
850 arrow_marker.type = visualization_msgs::msg::Marker::ARROW;
851 arrow_marker.action = visualization_msgs::msg::Marker::ADD;
852 arrow_marker.pose = acummulated_poses_[i].pose;
853 arrow_marker.scale.x = 0.3;
854 arrow_marker.scale.y = 0.05;
855 arrow_marker.scale.z = 0.02;
856 arrow_marker.color.r = 0;
857 arrow_marker.color.g = 255;
858 arrow_marker.color.b = 0;
859 arrow_marker.color.a = 1.0f;
860 arrow_marker.lifetime = rclcpp::Duration(0s);
861 arrow_marker.frame_locked =
false;
862 marker_array->markers.push_back(arrow_marker);
865 visualization_msgs::msg::Marker circle_marker;
866 circle_marker.header = acummulated_poses_[i].header;
867 circle_marker.id = getUniqueId();
868 circle_marker.type = visualization_msgs::msg::Marker::SPHERE;
869 circle_marker.action = visualization_msgs::msg::Marker::ADD;
870 circle_marker.pose = acummulated_poses_[i].pose;
871 circle_marker.scale.x = 0.05;
872 circle_marker.scale.y = 0.05;
873 circle_marker.scale.z = 0.05;
874 circle_marker.color.r = 255;
875 circle_marker.color.g = 0;
876 circle_marker.color.b = 0;
877 circle_marker.color.a = 1.0f;
878 circle_marker.lifetime = rclcpp::Duration(0s);
879 circle_marker.frame_locked =
false;
880 marker_array->markers.push_back(circle_marker);
883 visualization_msgs::msg::Marker marker_text;
884 marker_text.header = acummulated_poses_[i].header;
885 marker_text.id = getUniqueId();
886 marker_text.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
887 marker_text.action = visualization_msgs::msg::Marker::ADD;
888 marker_text.pose = acummulated_poses_[i].pose;
889 marker_text.pose.position.z += 0.2;
890 marker_text.scale.x = 0.07;
891 marker_text.scale.y = 0.07;
892 marker_text.scale.z = 0.07;
893 marker_text.color.r = 0;
894 marker_text.color.g = 255;
895 marker_text.color.b = 0;
896 marker_text.color.a = 1.0f;
897 marker_text.lifetime = rclcpp::Duration(0s);
898 marker_text.frame_locked =
false;
899 marker_text.text =
"wp_" + std::to_string(i + 1);
900 marker_array->markers.push_back(marker_text);
903 if (marker_array->markers.empty()) {
904 visualization_msgs::msg::Marker clear_all_marker;
905 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
906 marker_array->markers.push_back(clear_all_marker);
909 wp_navigation_markers_pub_->publish(std::move(marker_array));
913 Nav2Panel::getGoalStatusLabel(int8_t status)
915 std::string status_str;
917 case action_msgs::msg::GoalStatus::STATUS_EXECUTING:
918 status_str =
"<font color=green>active</color>";
921 case action_msgs::msg::GoalStatus::STATUS_SUCCEEDED:
922 status_str =
"<font color=green>reached</color>";
925 case action_msgs::msg::GoalStatus::STATUS_CANCELED:
926 status_str =
"<font color=orange>canceled</color>";
929 case action_msgs::msg::GoalStatus::STATUS_ABORTED:
930 status_str =
"<font color=red>aborted</color>";
933 case action_msgs::msg::GoalStatus::STATUS_UNKNOWN:
934 status_str =
"unknown";
938 status_str =
"inactive";
943 "<table><tr><td width=100><b>Feedback:</b></td><td>" +
944 status_str +
"</td></tr></table>").c_str());
948 Nav2Panel::getNavToPoseFeedbackLabel(nav2_msgs::action::NavigateToPose::Feedback msg)
950 return QString(std::string(
"<table>" + toLabel(msg) +
"</table>").c_str());
954 Nav2Panel::getNavThroughPosesFeedbackLabel(nav2_msgs::action::NavigateThroughPoses::Feedback msg)
958 "<table><tr><td width=150>Poses remaining:</td><td>" +
959 std::to_string(msg.number_of_poses_remaining) +
960 "</td></tr>" + toLabel(msg) +
"</table>").c_str());
964 inline std::string Nav2Panel::toLabel(T & msg)
967 "<tr><td width=150>ETA:</td><td>" +
968 toString(rclcpp::Duration(msg.estimated_time_remaining).seconds(), 0) +
" s"
969 "</td></tr><tr><td width=150>Distance remaining:</td><td>" +
970 toString(msg.distance_remaining, 2) +
" m"
971 "</td></tr><tr><td width=150>Time taken:</td><td>" +
972 toString(rclcpp::Duration(msg.navigation_time).seconds(), 0) +
" s"
973 "</td></tr><tr><td width=150>Recoveries:</td><td>" +
974 std::to_string(msg.number_of_recoveries) +
979 Nav2Panel::toString(
double val,
int precision)
981 std::ostringstream out;
982 out.precision(precision);
983 out << std::fixed << val;
989 #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.