17 #include <QVBoxLayout>
18 #include <QHBoxLayout>
27 #include <rclcpp/rclcpp.hpp>
28 #include <rviz_common/display_context.hpp>
30 #include "nav2_util/geometry_utils.hpp"
31 #include "nav2_rviz_plugins/docking_panel.hpp"
32 #include "nav2_rviz_plugins/ros_action_qevent.hpp"
33 #include "nav2_rviz_plugins/utils.hpp"
35 using namespace std::chrono_literals;
37 namespace nav2_rviz_plugins
40 DockingPanel::DockingPanel(QWidget * parent)
45 main_layout_ =
new QVBoxLayout;
46 info_layout_ =
new QHBoxLayout;
47 feedback_layout_ =
new QVBoxLayout;
48 dock_id_layout_ =
new QHBoxLayout;
49 dock_type_layout_ =
new QHBoxLayout;
50 dock_pose_layout_ =
new QHBoxLayout;
51 nav_stage_layout_ =
new QHBoxLayout;
52 dock_type_ =
new QComboBox;
53 docking_button_ =
new QPushButton;
54 undocking_button_ =
new QPushButton;
55 docking_goal_status_indicator_ =
new QLabel;
56 docking_feedback_indicator_ =
new QLabel;
57 docking_result_indicator_ =
new QLabel;
58 use_dock_id_checkbox_ =
new QCheckBox;
59 nav_to_staging_checkbox_ =
new QCheckBox;
60 dock_id_ =
new QLineEdit;
61 dock_pose_x_ =
new QLineEdit;
62 dock_pose_y_ =
new QLineEdit;
63 dock_pose_yaw_ =
new QLineEdit;
66 const char * nav_to_stage_msg =
"Navigate to the staging pose before docking";
67 const char * use_dock_id_msg =
"Use the dock id or the dock pose to dock the robot";
68 const char * dock_msg =
"Dock the robot at the specified docking station";
69 const char * undock_msg =
"Undock the robot from the docking station";
70 const char * cancel_dock_msg =
"Cancel the current docking action";
71 const char * cancel_undock_msg =
"Cancel the current undocking action";
73 docking_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel());
74 docking_feedback_indicator_->setText(getDockFeedbackLabel());
75 docking_goal_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
76 docking_feedback_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
78 pre_initial_ =
new QState();
79 pre_initial_->setObjectName(
"pre_initial");
80 pre_initial_->assignProperty(docking_button_,
"text",
"Dock robot");
81 pre_initial_->assignProperty(docking_button_,
"enabled",
false);
83 pre_initial_->assignProperty(undocking_button_,
"text",
"Undock robot");
84 pre_initial_->assignProperty(undocking_button_,
"enabled",
false);
86 pre_initial_->assignProperty(nav_to_staging_checkbox_,
"enabled",
false);
87 pre_initial_->assignProperty(nav_to_staging_checkbox_,
"checked",
true);
88 pre_initial_->assignProperty(use_dock_id_checkbox_,
"enabled",
false);
89 pre_initial_->assignProperty(use_dock_id_checkbox_,
"checked",
true);
90 pre_initial_->assignProperty(dock_id_,
"enabled",
false);
91 pre_initial_->assignProperty(dock_type_,
"enabled",
false);
92 pre_initial_->assignProperty(dock_pose_x_,
"enabled",
false);
93 pre_initial_->assignProperty(dock_pose_y_,
"enabled",
false);
94 pre_initial_->assignProperty(dock_pose_yaw_,
"enabled",
false);
98 idle_->setObjectName(
"idle");
99 idle_->assignProperty(docking_button_,
"text",
"Dock robot");
100 idle_->assignProperty(docking_button_,
"toolTip", dock_msg);
101 idle_->assignProperty(docking_button_,
"enabled",
true);
103 idle_->assignProperty(undocking_button_,
"text",
"Undock robot");
104 idle_->assignProperty(undocking_button_,
"toolTip", undock_msg);
105 idle_->assignProperty(undocking_button_,
"enabled",
true);
107 idle_->assignProperty(nav_to_staging_checkbox_,
"enabled",
true);
108 idle_->assignProperty(nav_to_staging_checkbox_,
"toolTip", nav_to_stage_msg);
109 idle_->assignProperty(use_dock_id_checkbox_,
"enabled",
true);
110 idle_->assignProperty(use_dock_id_checkbox_,
"toolTip", use_dock_id_msg);
111 idle_->assignProperty(dock_id_,
"enabled",
true);
112 idle_->assignProperty(dock_type_,
"enabled",
true);
115 canceled_docking_ =
new QState();
116 canceled_docking_->setObjectName(
"canceled_docking");
119 canceled_undocking_ =
new QState();
120 canceled_undocking_->setObjectName(
"canceled_undocking");
123 docking_ =
new QState();
124 docking_->setObjectName(
"docking");
125 docking_->assignProperty(docking_button_,
"text",
"Cancel docking");
126 docking_->assignProperty(docking_button_,
"toolTip", cancel_dock_msg);
128 docking_->assignProperty(undocking_button_,
"enabled",
false);
131 undocking_ =
new QState();
132 undocking_->setObjectName(
"undocking");
133 undocking_->assignProperty(docking_button_,
"enabled",
false);
135 undocking_->assignProperty(undocking_button_,
"text",
"Cancel undocking");
136 undocking_->assignProperty(undocking_button_,
"toolTip", cancel_undock_msg);
138 QObject::connect(docking_, SIGNAL(entered()),
this, SLOT(onDockingButtonPressed()));
139 QObject::connect(undocking_, SIGNAL(entered()),
this, SLOT(onUndockingButtonPressed()));
140 QObject::connect(canceled_docking_, SIGNAL(exited()),
this, SLOT(onCancelDocking()));
141 QObject::connect(canceled_undocking_, SIGNAL(exited()),
this, SLOT(onCancelUndocking()));
144 idle_->addTransition(docking_button_, SIGNAL(clicked()), docking_);
145 idle_->addTransition(undocking_button_, SIGNAL(clicked()), undocking_);
146 docking_->addTransition(docking_button_, SIGNAL(clicked()), canceled_docking_);
147 undocking_->addTransition(undocking_button_, SIGNAL(clicked()), canceled_undocking_);
150 canceled_docking_->addTransition(canceled_docking_, SIGNAL(entered()), idle_);
151 canceled_undocking_->addTransition(canceled_undocking_, SIGNAL(entered()), idle_);
156 ROSActionQTransition * idleDockTransition =
new ROSActionQTransition(QActionState::INACTIVE);
157 idleDockTransition->setTargetState(docking_);
158 idle_->addTransition(idleDockTransition);
160 ROSActionQTransition * idleUndockTransition =
new ROSActionQTransition(QActionState::INACTIVE);
161 idleUndockTransition->setTargetState(undocking_);
162 idle_->addTransition(idleUndockTransition);
164 ROSActionQTransition * dockingTransition =
new ROSActionQTransition(QActionState::ACTIVE);
165 dockingTransition->setTargetState(idle_);
166 docking_->addTransition(dockingTransition);
168 ROSActionQTransition * undockingTransition =
new ROSActionQTransition(QActionState::ACTIVE);
169 undockingTransition->setTargetState(idle_);
170 undocking_->addTransition(undockingTransition);
172 client_node_ = std::make_shared<rclcpp::Node>(
"nav2_rviz_docking_panel_node");
173 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
174 executor_->add_node(client_node_);
176 state_machine_.addState(pre_initial_);
177 state_machine_.addState(idle_);
178 state_machine_.addState(docking_);
179 state_machine_.addState(undocking_);
180 state_machine_.addState(canceled_docking_);
181 state_machine_.addState(canceled_undocking_);
183 state_machine_.setInitialState(pre_initial_);
186 QObject::connect(&state_machine_, SIGNAL(started()),
this, SLOT(startThread()));
187 state_machine_.start();
190 info_layout_->addWidget(docking_goal_status_indicator_);
191 info_layout_->addWidget(docking_result_indicator_);
192 feedback_layout_->addWidget(docking_feedback_indicator_);
194 QLabel * nav_stage_label =
new QLabel(
"Nav. to staging pose");
195 QLabel * dock_id_label =
new QLabel(
"Dock id");
196 QLabel * dock_type_label =
new QLabel(
"Dock type");
198 nav_stage_label->setFixedWidth(150);
199 dock_id_label->setFixedWidth(150);
200 dock_type_label->setFixedWidth(170);
202 nav_stage_layout_->addWidget(nav_stage_label);
203 nav_stage_layout_->addWidget(nav_to_staging_checkbox_);
204 dock_id_layout_->addWidget(dock_id_label);
205 dock_id_layout_->addWidget(use_dock_id_checkbox_);
206 dock_id_layout_->addWidget(dock_id_);
207 dock_type_layout_->addWidget(dock_type_label);
208 dock_type_layout_->addWidget(dock_type_);
209 dock_pose_layout_->addWidget(
new QLabel(
"Dock pose {X"));
210 dock_pose_layout_->addWidget(dock_pose_x_);
211 dock_pose_layout_->addWidget(
new QLabel(
"Y"));
212 dock_pose_layout_->addWidget(dock_pose_y_);
213 dock_pose_layout_->addWidget(
new QLabel(
"θ"));
214 dock_pose_layout_->addWidget(dock_pose_yaw_);
215 dock_pose_layout_->addWidget(
new QLabel(
"}"));
217 QGroupBox * group_box =
new QGroupBox();
218 QVBoxLayout * group_box_layout =
new QVBoxLayout;
219 group_box_layout->addLayout(nav_stage_layout_);
220 group_box_layout->addLayout(dock_id_layout_);
221 group_box_layout->addLayout(dock_type_layout_);
222 group_box_layout->addLayout(dock_pose_layout_);
223 group_box->setLayout(group_box_layout);
225 main_layout_->setContentsMargins(10, 10, 10, 10);
226 main_layout_->addLayout(info_layout_);
227 main_layout_->addLayout(feedback_layout_);
228 main_layout_->addWidget(group_box);
229 main_layout_->addWidget(docking_button_);
230 main_layout_->addWidget(undocking_button_);
232 setLayout(main_layout_);
233 action_timer_.start(200,
this);
235 dock_client_ = rclcpp_action::create_client<Dock>(client_node_,
"dock_robot");
236 undock_client_ = rclcpp_action::create_client<Undock>(client_node_,
"undock_robot");
237 initial_thread_ =
new InitialDockThread(dock_client_, undock_client_);
238 connect(initial_thread_, &InitialDockThread::finished, initial_thread_, &QObject::deleteLater);
240 QSignalTransition * activeDockSignal =
new QSignalTransition(
241 initial_thread_, &InitialDockThread::dockingActive);
242 activeDockSignal->setTargetState(idle_);
243 pre_initial_->addTransition(activeDockSignal);
245 QSignalTransition * activeUndockSignal =
new QSignalTransition(
246 initial_thread_, &InitialDockThread::undockingActive);
247 activeUndockSignal->setTargetState(idle_);
248 pre_initial_->addTransition(activeUndockSignal);
251 initial_thread_, &InitialDockThread::dockingActive,
254 if (!plugins_loaded_) {
255 RCLCPP_INFO(client_node_->get_logger(),
"Loading dock plugins");
256 nav2_rviz_plugins::pluginLoader(
257 client_node_, server_failed_,
"docking_server",
"dock_plugins", dock_type_, executor_);
258 plugins_loaded_ =
true;
264 use_dock_id_checkbox_, &QCheckBox::stateChanged,
this, &DockingPanel::dockIdCheckbox);
267 void DockingPanel::onInitialize()
269 node_ptr_ = getDisplayContext()->getRosNodeAbstraction().lock();
270 if (node_ptr_ ==
nullptr) {
273 rclcpp::get_logger(
"docking_panel"),
274 "Underlying ROS node no longer exists, initialization failed");
277 rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
280 docking_feedback_sub_ = node->create_subscription<Dock::Impl::FeedbackMessage>(
281 "dock_robot/_action/feedback",
282 rclcpp::SystemDefaultsQoS(),
283 [
this](
const Dock::Impl::FeedbackMessage::SharedPtr msg) {
284 docking_feedback_indicator_->setText(getDockFeedbackLabel(msg->feedback));
288 docking_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
289 "dock_robot/_action/status",
290 rclcpp::SystemDefaultsQoS(),
291 [
this](
const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
292 docking_goal_status_indicator_->setText(
293 nav2_rviz_plugins::getGoalStatusLabel(
"Feedback", msg->status_list.back().status));
295 if (msg->status_list.back().status == action_msgs::msg::GoalStatus::STATUS_SUCCEEDED) {
296 docking_feedback_indicator_->setText(getDockFeedbackLabel());
300 undocking_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
301 "undock_robot/_action/status",
302 rclcpp::SystemDefaultsQoS(),
303 [
this](
const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
304 docking_goal_status_indicator_->setText(
305 nav2_rviz_plugins::getGoalStatusLabel(
"Feedback", msg->status_list.back().status));
309 void DockingPanel::startThread()
312 initial_thread_->start();
315 DockingPanel::~DockingPanel()
319 void DockingPanel::load(
const rviz_common::Config & config)
324 void DockingPanel::save(rviz_common::Config config)
const
329 void DockingPanel::onDockingButtonPressed()
331 auto is_action_server_ready =
332 dock_client_->wait_for_action_server(std::chrono::seconds(5));
333 if (!is_action_server_ready) {
334 RCLCPP_ERROR(client_node_->get_logger(),
"dock_robot action server is not available.");
338 QComboBox * combo_box = dock_type_;
340 if (combo_box->findText(
"Default") != -1) {
341 combo_box->removeItem(0);
345 if (combo_box->count() == 0) {
350 auto goal_msg = Dock::Goal();
351 goal_msg.use_dock_id = use_dock_id_;
352 goal_msg.navigate_to_staging_pose = nav_to_staging_checkbox_->isChecked();
354 if (dock_id_->text().isEmpty()) {
355 RCLCPP_ERROR(client_node_->get_logger(),
"Dock id is empty.");
358 goal_msg.dock_id = dock_id_->text().toStdString();
361 client_node_->get_logger(),
"DockRobot will be called using dock id: %s",
362 goal_msg.dock_id.c_str());
365 if (dock_pose_x_->text().isEmpty() || dock_pose_y_->text().isEmpty() ||
366 dock_pose_yaw_->text().isEmpty())
368 RCLCPP_ERROR(client_node_->get_logger(),
"Dock pose is empty.");
371 goal_msg.dock_pose.header.frame_id =
"map";
372 goal_msg.dock_pose.header.stamp = client_node_->now();
373 goal_msg.dock_pose.pose.position.x = dock_pose_x_->text().toDouble();
374 goal_msg.dock_pose.pose.position.y = dock_pose_y_->text().toDouble();
375 goal_msg.dock_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
376 dock_pose_yaw_->text().toDouble());
377 goal_msg.dock_type = combo_box->currentText().toStdString();
380 client_node_->get_logger(),
"DockRobot will be called using dock pose: (%f, %f) and type: %s",
381 goal_msg.dock_pose.pose.position.x, goal_msg.dock_pose.pose.position.y,
382 goal_msg.dock_type.c_str());
386 auto send_goal_options = nav2::ActionClient<Dock>::SendGoalOptions();
387 send_goal_options.result_callback = [
this](
const DockGoalHandle::WrappedResult & result) {
388 dock_goal_handle_.reset();
389 if (result.result->success) {
390 docking_result_indicator_->setText(
"");
392 docking_result_indicator_->setText(
393 QString(std::string(
"(" + dockErrorToString(result.result->error_code) +
")").c_str()));
397 auto future_goal_handle = dock_client_->async_send_goal(goal_msg, send_goal_options);
398 if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
399 rclcpp::FutureReturnCode::SUCCESS)
401 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
406 dock_goal_handle_ = future_goal_handle.get();
407 if (!dock_goal_handle_) {
408 RCLCPP_ERROR(client_node_->get_logger(),
"Goal was rejected by server");
412 action_timer_.start(200,
this);
415 void DockingPanel::onUndockingButtonPressed()
417 auto is_action_server_ready =
418 undock_client_->wait_for_action_server(std::chrono::seconds(5));
419 if (!is_action_server_ready) {
420 RCLCPP_ERROR(client_node_->get_logger(),
"undock_robot action server is not available.");
424 QComboBox * combo_box = dock_type_;
426 if (combo_box->findText(
"Default") != -1) {
427 combo_box->removeItem(0);
431 if (combo_box->count() == 0) {
436 auto goal_msg = Undock::Goal();
437 goal_msg.dock_type = combo_box->currentText().toStdString();
440 client_node_->get_logger(),
"UndockRobot will be called using dock type: %s",
441 goal_msg.dock_type.c_str());
444 auto send_goal_options = nav2::ActionClient<Undock>::SendGoalOptions();
445 send_goal_options.result_callback = [
this](
const UndockGoalHandle::WrappedResult & result) {
446 undock_goal_handle_.reset();
447 if (result.result->success) {
448 docking_result_indicator_->setText(
"");
450 docking_result_indicator_->setText(
451 QString(std::string(
"(" + dockErrorToString(result.result->error_code) +
")").c_str()));
455 auto future_goal_handle = undock_client_->async_send_goal(goal_msg, send_goal_options);
456 if (executor_->spin_until_future_complete(future_goal_handle, server_timeout_) !=
457 rclcpp::FutureReturnCode::SUCCESS)
459 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
464 undock_goal_handle_ = future_goal_handle.get();
465 if (!undock_goal_handle_) {
466 RCLCPP_ERROR(client_node_->get_logger(),
"Goal was rejected by server");
470 action_timer_.start(200,
this);
473 void DockingPanel::dockIdCheckbox()
475 if (use_dock_id_checkbox_->isChecked()) {
477 dock_id_->setEnabled(
true);
478 dock_pose_x_->setEnabled(
false);
479 dock_pose_y_->setEnabled(
false);
480 dock_pose_yaw_->setEnabled(
false);
482 use_dock_id_ =
false;
483 dock_id_->setEnabled(
false);
484 dock_pose_x_->setEnabled(
true);
485 dock_pose_y_->setEnabled(
true);
486 dock_pose_yaw_->setEnabled(
true);
490 void DockingPanel::onCancelDocking()
492 if (dock_goal_handle_) {
493 auto future_cancel = dock_client_->async_cancel_goal(dock_goal_handle_);
495 if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
496 rclcpp::FutureReturnCode::SUCCESS)
498 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel goal");
500 dock_goal_handle_.reset();
504 action_timer_.stop();
507 void DockingPanel::onCancelUndocking()
509 if (undock_goal_handle_) {
510 auto future_cancel = undock_client_->async_cancel_goal(undock_goal_handle_);
512 if (executor_->spin_until_future_complete(future_cancel, server_timeout_) !=
513 rclcpp::FutureReturnCode::SUCCESS)
515 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel goal");
517 undock_goal_handle_.reset();
521 action_timer_.stop();
524 void DockingPanel::timerEvent(QTimerEvent * event)
526 if (event->timerId() == action_timer_.timerId()) {
528 if (state_machine_.configuration().contains(docking_)) {
529 if (!dock_goal_handle_) {
530 RCLCPP_DEBUG(client_node_->get_logger(),
"Waiting for Goal");
531 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
535 executor_->spin_some();
536 auto status = dock_goal_handle_->get_status();
539 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
540 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
542 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
544 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
545 action_timer_.stop();
547 }
else if (state_machine_.configuration().contains(undocking_)) {
548 if (!undock_goal_handle_) {
549 RCLCPP_DEBUG(client_node_->get_logger(),
"Waiting for Goal");
550 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
554 executor_->spin_some();
555 auto status = undock_goal_handle_->get_status();
558 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
559 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
561 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
563 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
564 action_timer_.stop();
570 inline QString DockingPanel::getDockFeedbackLabel(Dock::Feedback msg)
572 return QString(std::string(
"<table>" + toLabel(msg) +
"</table>").c_str());
576 inline std::string DockingPanel::toLabel(T & msg)
579 "</td></tr><tr><td width=150>State:</td><td>" +
580 dockStateToString(msg.state) +
581 "</td></tr><tr><td width=150>Time taken:</td><td>" +
582 toString(rclcpp::Duration(msg.docking_time).seconds(), 0) +
" s"
583 "</td></tr><tr><td width=150>Retries:</td><td>" +
584 std::to_string(msg.num_retries) +
588 inline std::string DockingPanel::toString(
double val,
int precision)
590 std::ostringstream out;
591 out.precision(precision);
592 out << std::fixed << val;
596 inline std::string DockingPanel::dockStateToString(int16_t state)
602 return "nav. to staging pose";
604 return "initial perception";
606 return "controlling";
608 return "wait for charge";
616 inline std::string DockingPanel::dockErrorToString(int16_t error_code)
618 switch (error_code) {
622 return "dock not in database";
624 return "dock not valid";
626 return "failed to stage";
628 return "failed to detect dock";
630 return "failed to control";
632 return "failed to charge";
641 #include <pluginlib/class_list_macros.hpp>
Panel to interface to the docking server.