20 #include <QVBoxLayout>
21 #include <QHBoxLayout>
23 #include <rviz_common/display_context.hpp>
25 #include "nav2_util/geometry_utils.hpp"
26 #include "nav2_rviz_plugins/docking_panel.hpp"
27 #include "nav2_rviz_plugins/ros_action_qevent.hpp"
28 #include "nav2_rviz_plugins/utils.hpp"
30 using namespace std::chrono_literals;
32 namespace nav2_rviz_plugins
35 DockingPanel::DockingPanel(QWidget * parent)
40 main_layout_ =
new QVBoxLayout;
41 info_layout_ =
new QHBoxLayout;
42 feedback_layout_ =
new QVBoxLayout;
43 dock_id_layout_ =
new QHBoxLayout;
44 dock_type_layout_ =
new QHBoxLayout;
45 dock_pose_layout_ =
new QHBoxLayout;
46 nav_stage_layout_ =
new QHBoxLayout;
47 dock_type_ =
new QComboBox;
48 docking_button_ =
new QPushButton;
49 undocking_button_ =
new QPushButton;
50 docking_goal_status_indicator_ =
new QLabel;
51 docking_feedback_indicator_ =
new QLabel;
52 docking_result_indicator_ =
new QLabel;
53 use_dock_id_checkbox_ =
new QCheckBox;
54 nav_to_staging_checkbox_ =
new QCheckBox;
55 dock_id_ =
new QLineEdit;
56 dock_pose_x_ =
new QLineEdit;
57 dock_pose_y_ =
new QLineEdit;
58 dock_pose_yaw_ =
new QLineEdit;
61 const char * nav_to_stage_msg =
"Navigate to the staging pose before docking";
62 const char * use_dock_id_msg =
"Use the dock id or the dock pose to dock the robot";
63 const char * dock_msg =
"Dock the robot at the specified docking station";
64 const char * undock_msg =
"Undock the robot from the docking station";
65 const char * cancel_dock_msg =
"Cancel the current docking action";
66 const char * cancel_undock_msg =
"Cancel the current undocking action";
68 docking_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel());
69 docking_feedback_indicator_->setText(getDockFeedbackLabel());
70 docking_goal_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
71 docking_feedback_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
73 pre_initial_ =
new QState();
74 pre_initial_->setObjectName(
"pre_initial");
75 pre_initial_->assignProperty(docking_button_,
"text",
"Dock robot");
76 pre_initial_->assignProperty(docking_button_,
"enabled",
false);
78 pre_initial_->assignProperty(undocking_button_,
"text",
"Undock robot");
79 pre_initial_->assignProperty(undocking_button_,
"enabled",
false);
81 pre_initial_->assignProperty(nav_to_staging_checkbox_,
"enabled",
false);
82 pre_initial_->assignProperty(nav_to_staging_checkbox_,
"checked",
true);
83 pre_initial_->assignProperty(use_dock_id_checkbox_,
"enabled",
false);
84 pre_initial_->assignProperty(use_dock_id_checkbox_,
"checked",
true);
85 pre_initial_->assignProperty(dock_id_,
"enabled",
false);
86 pre_initial_->assignProperty(dock_type_,
"enabled",
false);
87 pre_initial_->assignProperty(dock_pose_x_,
"enabled",
false);
88 pre_initial_->assignProperty(dock_pose_y_,
"enabled",
false);
89 pre_initial_->assignProperty(dock_pose_yaw_,
"enabled",
false);
93 idle_->setObjectName(
"idle");
94 idle_->assignProperty(docking_button_,
"text",
"Dock robot");
95 idle_->assignProperty(docking_button_,
"toolTip", dock_msg);
96 idle_->assignProperty(docking_button_,
"enabled",
true);
98 idle_->assignProperty(undocking_button_,
"text",
"Undock robot");
99 idle_->assignProperty(undocking_button_,
"toolTip", undock_msg);
100 idle_->assignProperty(undocking_button_,
"enabled",
true);
102 idle_->assignProperty(nav_to_staging_checkbox_,
"enabled",
true);
103 idle_->assignProperty(nav_to_staging_checkbox_,
"toolTip", nav_to_stage_msg);
104 idle_->assignProperty(use_dock_id_checkbox_,
"enabled",
true);
105 idle_->assignProperty(use_dock_id_checkbox_,
"toolTip", use_dock_id_msg);
106 idle_->assignProperty(dock_id_,
"enabled",
true);
107 idle_->assignProperty(dock_type_,
"enabled",
true);
110 canceled_docking_ =
new QState();
111 canceled_docking_->setObjectName(
"canceled_docking");
114 canceled_undocking_ =
new QState();
115 canceled_undocking_->setObjectName(
"canceled_undocking");
118 docking_ =
new QState();
119 docking_->setObjectName(
"docking");
120 docking_->assignProperty(docking_button_,
"text",
"Cancel docking");
121 docking_->assignProperty(docking_button_,
"toolTip", cancel_dock_msg);
123 docking_->assignProperty(undocking_button_,
"enabled",
false);
126 undocking_ =
new QState();
127 undocking_->setObjectName(
"undocking");
128 undocking_->assignProperty(docking_button_,
"enabled",
false);
130 undocking_->assignProperty(undocking_button_,
"text",
"Cancel undocking");
131 undocking_->assignProperty(undocking_button_,
"toolTip", cancel_undock_msg);
133 QObject::connect(docking_, SIGNAL(entered()),
this, SLOT(onDockingButtonPressed()));
134 QObject::connect(undocking_, SIGNAL(entered()),
this, SLOT(onUndockingButtonPressed()));
135 QObject::connect(canceled_docking_, SIGNAL(exited()),
this, SLOT(onCancelDocking()));
136 QObject::connect(canceled_undocking_, SIGNAL(exited()),
this, SLOT(onCancelUndocking()));
139 idle_->addTransition(docking_button_, SIGNAL(clicked()), docking_);
140 idle_->addTransition(undocking_button_, SIGNAL(clicked()), undocking_);
141 docking_->addTransition(docking_button_, SIGNAL(clicked()), canceled_docking_);
142 undocking_->addTransition(undocking_button_, SIGNAL(clicked()), canceled_undocking_);
145 canceled_docking_->addTransition(canceled_docking_, SIGNAL(entered()), idle_);
146 canceled_undocking_->addTransition(canceled_undocking_, SIGNAL(entered()), idle_);
151 ROSActionQTransition * idleDockTransition =
new ROSActionQTransition(QActionState::INACTIVE);
152 idleDockTransition->setTargetState(docking_);
153 idle_->addTransition(idleDockTransition);
155 ROSActionQTransition * idleUndockTransition =
new ROSActionQTransition(QActionState::INACTIVE);
156 idleUndockTransition->setTargetState(undocking_);
157 idle_->addTransition(idleUndockTransition);
159 ROSActionQTransition * dockingTransition =
new ROSActionQTransition(QActionState::ACTIVE);
160 dockingTransition->setTargetState(idle_);
161 docking_->addTransition(dockingTransition);
163 ROSActionQTransition * undockingTransition =
new ROSActionQTransition(QActionState::ACTIVE);
164 undockingTransition->setTargetState(idle_);
165 undocking_->addTransition(undockingTransition);
167 client_node_ = std::make_shared<rclcpp::Node>(
"nav2_rviz_docking_panel_node");
169 state_machine_.addState(pre_initial_);
170 state_machine_.addState(idle_);
171 state_machine_.addState(docking_);
172 state_machine_.addState(undocking_);
173 state_machine_.addState(canceled_docking_);
174 state_machine_.addState(canceled_undocking_);
176 state_machine_.setInitialState(pre_initial_);
179 QObject::connect(&state_machine_, SIGNAL(started()),
this, SLOT(startThread()));
180 state_machine_.start();
183 info_layout_->addWidget(docking_goal_status_indicator_);
184 info_layout_->addWidget(docking_result_indicator_);
185 feedback_layout_->addWidget(docking_feedback_indicator_);
187 QLabel * nav_stage_label =
new QLabel(
"Nav. to staging pose");
188 QLabel * dock_id_label =
new QLabel(
"Dock id");
189 QLabel * dock_type_label =
new QLabel(
"Dock type");
191 nav_stage_label->setFixedWidth(150);
192 dock_id_label->setFixedWidth(150);
193 dock_type_label->setFixedWidth(170);
195 nav_stage_layout_->addWidget(nav_stage_label);
196 nav_stage_layout_->addWidget(nav_to_staging_checkbox_);
197 dock_id_layout_->addWidget(dock_id_label);
198 dock_id_layout_->addWidget(use_dock_id_checkbox_);
199 dock_id_layout_->addWidget(dock_id_);
200 dock_type_layout_->addWidget(dock_type_label);
201 dock_type_layout_->addWidget(dock_type_);
202 dock_pose_layout_->addWidget(
new QLabel(
"Dock pose {X"));
203 dock_pose_layout_->addWidget(dock_pose_x_);
204 dock_pose_layout_->addWidget(
new QLabel(
"Y"));
205 dock_pose_layout_->addWidget(dock_pose_y_);
206 dock_pose_layout_->addWidget(
new QLabel(
"θ"));
207 dock_pose_layout_->addWidget(dock_pose_yaw_);
208 dock_pose_layout_->addWidget(
new QLabel(
"}"));
210 QGroupBox * group_box =
new QGroupBox();
211 QVBoxLayout * group_box_layout =
new QVBoxLayout;
212 group_box_layout->addLayout(nav_stage_layout_);
213 group_box_layout->addLayout(dock_id_layout_);
214 group_box_layout->addLayout(dock_type_layout_);
215 group_box_layout->addLayout(dock_pose_layout_);
216 group_box->setLayout(group_box_layout);
218 main_layout_->setContentsMargins(10, 10, 10, 10);
219 main_layout_->addLayout(info_layout_);
220 main_layout_->addLayout(feedback_layout_);
221 main_layout_->addWidget(group_box);
222 main_layout_->addWidget(docking_button_);
223 main_layout_->addWidget(undocking_button_);
225 setLayout(main_layout_);
226 action_timer_.start(200,
this);
228 dock_client_ = rclcpp_action::create_client<Dock>(client_node_,
"dock_robot");
229 undock_client_ = rclcpp_action::create_client<Undock>(client_node_,
"undock_robot");
230 initial_thread_ =
new InitialDockThread(dock_client_, undock_client_);
231 connect(initial_thread_, &InitialDockThread::finished, initial_thread_, &QObject::deleteLater);
233 QSignalTransition * activeDockSignal =
new QSignalTransition(
234 initial_thread_, &InitialDockThread::dockingActive);
235 activeDockSignal->setTargetState(idle_);
236 pre_initial_->addTransition(activeDockSignal);
238 QSignalTransition * activeUndockSignal =
new QSignalTransition(
239 initial_thread_, &InitialDockThread::undockingActive);
240 activeUndockSignal->setTargetState(idle_);
241 pre_initial_->addTransition(activeUndockSignal);
244 initial_thread_, &InitialDockThread::dockingActive,
247 if (!plugins_loaded_) {
248 RCLCPP_INFO(client_node_->get_logger(),
"Loading dock plugins");
249 nav2_rviz_plugins::pluginLoader(
250 client_node_, server_failed_,
"docking_server",
"dock_plugins", dock_type_);
251 plugins_loaded_ =
true;
257 use_dock_id_checkbox_, &QCheckBox::stateChanged,
this, &DockingPanel::dockIdCheckbox);
260 void DockingPanel::onInitialize()
262 auto node = getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();
265 docking_feedback_sub_ = node->create_subscription<Dock::Impl::FeedbackMessage>(
266 "dock_robot/_action/feedback",
267 rclcpp::SystemDefaultsQoS(),
268 [
this](
const Dock::Impl::FeedbackMessage::SharedPtr msg) {
269 docking_feedback_indicator_->setText(getDockFeedbackLabel(msg->feedback));
273 docking_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
274 "dock_robot/_action/status",
275 rclcpp::SystemDefaultsQoS(),
276 [
this](
const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
277 docking_goal_status_indicator_->setText(
278 nav2_rviz_plugins::getGoalStatusLabel(
"Feedback", msg->status_list.back().status));
280 if (msg->status_list.back().status == action_msgs::msg::GoalStatus::STATUS_SUCCEEDED) {
281 docking_feedback_indicator_->setText(getDockFeedbackLabel());
285 undocking_goal_status_sub_ = node->create_subscription<action_msgs::msg::GoalStatusArray>(
286 "undock_robot/_action/status",
287 rclcpp::SystemDefaultsQoS(),
288 [
this](
const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
289 docking_goal_status_indicator_->setText(
290 nav2_rviz_plugins::getGoalStatusLabel(
"Feedback", msg->status_list.back().status));
294 void DockingPanel::startThread()
297 initial_thread_->start();
300 DockingPanel::~DockingPanel()
304 void DockingPanel::load(
const rviz_common::Config & config)
309 void DockingPanel::save(rviz_common::Config config)
const
314 void DockingPanel::onDockingButtonPressed()
316 auto is_action_server_ready =
317 dock_client_->wait_for_action_server(std::chrono::seconds(5));
318 if (!is_action_server_ready) {
319 RCLCPP_ERROR(client_node_->get_logger(),
"dock_robot action server is not available.");
323 QComboBox * combo_box = dock_type_;
325 if (combo_box->findText(
"Default") != -1) {
326 combo_box->removeItem(0);
330 if (combo_box->count() == 0) {
335 auto goal_msg = Dock::Goal();
336 goal_msg.use_dock_id = use_dock_id_;
337 goal_msg.navigate_to_staging_pose = nav_to_staging_checkbox_->isChecked();
339 if (dock_id_->text().isEmpty()) {
340 RCLCPP_ERROR(client_node_->get_logger(),
"Dock id is empty.");
343 goal_msg.dock_id = dock_id_->text().toStdString();
346 client_node_->get_logger(),
"DockRobot will be called using dock id: %s",
347 goal_msg.dock_id.c_str());
350 if (dock_pose_x_->text().isEmpty() || dock_pose_y_->text().isEmpty() ||
351 dock_pose_yaw_->text().isEmpty())
353 RCLCPP_ERROR(client_node_->get_logger(),
"Dock pose is empty.");
356 goal_msg.dock_pose.header.frame_id =
"map";
357 goal_msg.dock_pose.header.stamp = client_node_->now();
358 goal_msg.dock_pose.pose.position.x = dock_pose_x_->text().toDouble();
359 goal_msg.dock_pose.pose.position.y = dock_pose_y_->text().toDouble();
360 goal_msg.dock_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
361 dock_pose_yaw_->text().toDouble());
362 goal_msg.dock_type = combo_box->currentText().toStdString();
365 client_node_->get_logger(),
"DockRobot will be called using dock pose: (%f, %f) and type: %s",
366 goal_msg.dock_pose.pose.position.x, goal_msg.dock_pose.pose.position.y,
367 goal_msg.dock_type.c_str());
371 auto send_goal_options = rclcpp_action::Client<Dock>::SendGoalOptions();
372 send_goal_options.result_callback = [
this](
const DockGoalHandle::WrappedResult & result) {
373 dock_goal_handle_.reset();
374 if (result.result->success) {
375 docking_result_indicator_->setText(
"");
377 docking_result_indicator_->setText(
378 QString(std::string(
"(" + dockErrorToString(result.result->error_code) +
")").c_str()));
382 auto future_goal_handle = dock_client_->async_send_goal(goal_msg, send_goal_options);
383 if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
384 rclcpp::FutureReturnCode::SUCCESS)
386 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
391 dock_goal_handle_ = future_goal_handle.get();
392 if (!dock_goal_handle_) {
393 RCLCPP_ERROR(client_node_->get_logger(),
"Goal was rejected by server");
397 action_timer_.start(200,
this);
400 void DockingPanel::onUndockingButtonPressed()
402 auto is_action_server_ready =
403 undock_client_->wait_for_action_server(std::chrono::seconds(5));
404 if (!is_action_server_ready) {
405 RCLCPP_ERROR(client_node_->get_logger(),
"undock_robot action server is not available.");
409 QComboBox * combo_box = dock_type_;
411 if (combo_box->findText(
"Default") != -1) {
412 combo_box->removeItem(0);
416 if (combo_box->count() == 0) {
421 auto goal_msg = Undock::Goal();
422 goal_msg.dock_type = combo_box->currentText().toStdString();
425 client_node_->get_logger(),
"UndockRobot will be called using dock type: %s",
426 goal_msg.dock_type.c_str());
429 auto send_goal_options = rclcpp_action::Client<Undock>::SendGoalOptions();
430 send_goal_options.result_callback = [
this](
const UndockGoalHandle::WrappedResult & result) {
431 undock_goal_handle_.reset();
432 if (result.result->success) {
433 docking_result_indicator_->setText(
"");
435 docking_result_indicator_->setText(
436 QString(std::string(
"(" + dockErrorToString(result.result->error_code) +
")").c_str()));
440 auto future_goal_handle = undock_client_->async_send_goal(goal_msg, send_goal_options);
441 if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle, server_timeout_) !=
442 rclcpp::FutureReturnCode::SUCCESS)
444 RCLCPP_ERROR(client_node_->get_logger(),
"Send goal call failed");
449 undock_goal_handle_ = future_goal_handle.get();
450 if (!undock_goal_handle_) {
451 RCLCPP_ERROR(client_node_->get_logger(),
"Goal was rejected by server");
455 action_timer_.start(200,
this);
458 void DockingPanel::dockIdCheckbox()
460 if (use_dock_id_checkbox_->isChecked()) {
462 dock_id_->setEnabled(
true);
463 dock_pose_x_->setEnabled(
false);
464 dock_pose_y_->setEnabled(
false);
465 dock_pose_yaw_->setEnabled(
false);
467 use_dock_id_ =
false;
468 dock_id_->setEnabled(
false);
469 dock_pose_x_->setEnabled(
true);
470 dock_pose_y_->setEnabled(
true);
471 dock_pose_yaw_->setEnabled(
true);
475 void DockingPanel::onCancelDocking()
477 if (dock_goal_handle_) {
478 auto future_cancel = dock_client_->async_cancel_goal(dock_goal_handle_);
480 if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
481 rclcpp::FutureReturnCode::SUCCESS)
483 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel goal");
485 dock_goal_handle_.reset();
489 action_timer_.stop();
492 void DockingPanel::onCancelUndocking()
494 if (undock_goal_handle_) {
495 auto future_cancel = undock_client_->async_cancel_goal(undock_goal_handle_);
497 if (rclcpp::spin_until_future_complete(client_node_, future_cancel, server_timeout_) !=
498 rclcpp::FutureReturnCode::SUCCESS)
500 RCLCPP_ERROR(client_node_->get_logger(),
"Failed to cancel goal");
502 undock_goal_handle_.reset();
506 action_timer_.stop();
509 void DockingPanel::timerEvent(QTimerEvent * event)
511 if (event->timerId() == action_timer_.timerId()) {
513 if (state_machine_.configuration().contains(docking_)) {
514 if (!dock_goal_handle_) {
515 RCLCPP_DEBUG(client_node_->get_logger(),
"Waiting for Goal");
516 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
520 rclcpp::spin_some(client_node_);
521 auto status = dock_goal_handle_->get_status();
524 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
525 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
527 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
529 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
530 action_timer_.stop();
532 }
else if (state_machine_.configuration().contains(undocking_)) {
533 if (!undock_goal_handle_) {
534 RCLCPP_DEBUG(client_node_->get_logger(),
"Waiting for Goal");
535 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
539 rclcpp::spin_some(client_node_);
540 auto status = undock_goal_handle_->get_status();
543 if (status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
544 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING)
546 state_machine_.postEvent(
new ROSActionQEvent(QActionState::ACTIVE));
548 state_machine_.postEvent(
new ROSActionQEvent(QActionState::INACTIVE));
549 action_timer_.stop();
555 inline QString DockingPanel::getDockFeedbackLabel(Dock::Feedback msg)
557 return QString(std::string(
"<table>" + toLabel(msg) +
"</table>").c_str());
561 inline std::string DockingPanel::toLabel(T & msg)
564 "</td></tr><tr><td width=150>State:</td><td>" +
565 dockStateToString(msg.state) +
566 "</td></tr><tr><td width=150>Time taken:</td><td>" +
567 toString(rclcpp::Duration(msg.docking_time).seconds(), 0) +
" s"
568 "</td></tr><tr><td width=150>Retries:</td><td>" +
569 std::to_string(msg.num_retries) +
573 inline std::string DockingPanel::toString(
double val,
int precision)
575 std::ostringstream out;
576 out.precision(precision);
577 out << std::fixed << val;
581 inline std::string DockingPanel::dockStateToString(int16_t state)
587 return "nav. to staging pose";
589 return "initial perception";
591 return "controlling";
593 return "wait for charge";
601 inline std::string DockingPanel::dockErrorToString(int16_t error_code)
603 switch (error_code) {
607 return "dock not in database";
609 return "dock not valid";
611 return "failed to stage";
613 return "failed to detect dock";
615 return "failed to control";
617 return "failed to charge";
626 #include <pluginlib/class_list_macros.hpp>
Panel to interface to the docking server.