Skip to content

Commit

Permalink
Only one goal status
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Tudela <[email protected]>
  • Loading branch information
ajtudela committed Jun 21, 2024
1 parent 0ac9056 commit 52d6c7e
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 22 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,7 @@ private Q_SLOTS:
QBasicTimer timer_;

QVBoxLayout * main_layout_{nullptr};
QHBoxLayout * dock_info_layout_{nullptr};
QHBoxLayout * undock_info_layout_{nullptr};
QHBoxLayout * info_layout_{nullptr};
QVBoxLayout * feedback_layout_{nullptr};
QHBoxLayout * dock_id_layout_{nullptr};
QHBoxLayout * dock_type_layout_{nullptr};
Expand All @@ -104,10 +103,8 @@ private Q_SLOTS:
QCheckBox * use_dock_id_checkbox_{nullptr};

QLabel * docking_goal_status_indicator_{nullptr};
QLabel * undocking_goal_status_indicator_{nullptr};
QLabel * docking_feedback_indicator_{nullptr};
QLabel * docking_result_indicator_{nullptr};
QLabel * undocking_result_indicator_{nullptr};

QLineEdit * dock_id_{nullptr};

Expand Down
28 changes: 10 additions & 18 deletions nav2_rviz_plugins/src/docking_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,37 +37,30 @@ DockingPanel::DockingPanel(QWidget * parent)
client_node_ = std::make_shared<rclcpp::Node>("nav2_rviz_docking_panel_node");

main_layout_ = new QVBoxLayout;
dock_info_layout_ = new QHBoxLayout;
undock_info_layout_ = new QHBoxLayout;
info_layout_ = new QHBoxLayout;
feedback_layout_ = new QVBoxLayout;
dock_id_layout_ = new QHBoxLayout;
dock_type_layout_ = new QHBoxLayout;
dock_type_ = new QComboBox;
docking_button_ = new QPushButton("Dock robot");
undocking_button_ = new QPushButton("Undock robot");
docking_goal_status_indicator_ = new QLabel;
undocking_goal_status_indicator_ = new QLabel;
docking_feedback_indicator_ = new QLabel;
docking_result_indicator_ = new QLabel;
undocking_result_indicator_ = new QLabel;
use_dock_id_checkbox_ = new QCheckBox;
dock_id_ = new QLineEdit;

docking_button_->setEnabled(false);
undocking_button_->setEnabled(false);
dock_id_->setEnabled(false);
use_dock_id_checkbox_->setEnabled(false);
docking_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel("Docking"));
undocking_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel("Undocking"));
docking_goal_status_indicator_->setText(nav2_rviz_plugins::getGoalStatusLabel());
docking_feedback_indicator_->setText(getDockFeedbackLabel());
docking_goal_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
undocking_goal_status_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
docking_feedback_indicator_->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);

dock_info_layout_->addWidget(docking_goal_status_indicator_);
dock_info_layout_->addWidget(docking_result_indicator_);
undock_info_layout_->addWidget(undocking_goal_status_indicator_);
undock_info_layout_->addWidget(undocking_result_indicator_);
info_layout_->addWidget(docking_goal_status_indicator_);
info_layout_->addWidget(docking_result_indicator_);
feedback_layout_->addWidget(docking_feedback_indicator_);
dock_id_layout_->addWidget(new QLabel("Dock id"));
dock_id_layout_->addWidget(use_dock_id_checkbox_);
Expand All @@ -76,8 +69,7 @@ DockingPanel::DockingPanel(QWidget * parent)
dock_type_layout_->addWidget(dock_type_);

main_layout_->setContentsMargins(10, 10, 10, 10);
main_layout_->addLayout(dock_info_layout_);
main_layout_->addLayout(undock_info_layout_);
main_layout_->addLayout(info_layout_);
main_layout_->addLayout(feedback_layout_);
main_layout_->addLayout(dock_id_layout_);
main_layout_->addLayout(dock_type_layout_);
Expand Down Expand Up @@ -127,7 +119,7 @@ void DockingPanel::onInitialize()
rclcpp::SystemDefaultsQoS(),
[this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
docking_goal_status_indicator_->setText(
nav2_rviz_plugins::getGoalStatusLabel("Docking", msg->status_list.back().status));
nav2_rviz_plugins::getGoalStatusLabel("Feedback", msg->status_list.back().status));
docking_button_->setText("Dock robot");
docking_in_progress_ = false;
// Reset values when action is completed
Expand All @@ -140,8 +132,8 @@ void DockingPanel::onInitialize()
"undock_robot/_action/status",
rclcpp::SystemDefaultsQoS(),
[this](const action_msgs::msg::GoalStatusArray::SharedPtr msg) {
undocking_goal_status_indicator_->setText(
nav2_rviz_plugins::getGoalStatusLabel("Undocking", msg->status_list.back().status));
docking_goal_status_indicator_->setText(
nav2_rviz_plugins::getGoalStatusLabel("Feedback", msg->status_list.back().status));
undocking_button_->setText("Undock robot");
undocking_in_progress_ = false;
});
Expand Down Expand Up @@ -262,9 +254,9 @@ void DockingPanel::startUndocking()
send_goal_options.result_callback = [this](const UndockGoalHandle::WrappedResult & result) {
undock_goal_handle_.reset();
if (result.result->success) {
undocking_result_indicator_->setText("");
docking_result_indicator_->setText("");
} else {
undocking_result_indicator_->setText(
docking_result_indicator_->setText(
QString(std::string("(" + dockErrorToString(result.result->error_code) + ")").c_str()));
}
};
Expand Down

0 comments on commit 52d6c7e

Please sign in to comment.