15 #ifndef NAV2_RVIZ_PLUGINS__DOCKING_PANEL_HPP_
16 #define NAV2_RVIZ_PLUGINS__DOCKING_PANEL_HPP_
20 #include <QBasicTimer>
25 #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp"
26 #include "rclcpp/rclcpp.hpp"
27 #include "rclcpp_action/rclcpp_action.hpp"
28 #include "rviz_common/panel.hpp"
29 #include "sensor_msgs/msg/battery_state.hpp"
30 #include "nav2_msgs/action/dock_robot.hpp"
31 #include "nav2_msgs/action/undock_robot.hpp"
36 namespace nav2_rviz_plugins
39 class InitialDockThread;
50 void onInitialize()
override;
53 void load(
const rviz_common::Config & config)
override;
54 void save(rviz_common::Config config)
const override;
59 void onDockingButtonPressed();
60 void onUndockingButtonPressed();
61 void onCancelDocking();
62 void onCancelUndocking();
63 void dockIdCheckbox();
66 using Dock = nav2_msgs::action::DockRobot;
67 using Undock = nav2_msgs::action::UndockRobot;
68 using DockGoalHandle = rclcpp_action::ClientGoalHandle<Dock>;
69 using UndockGoalHandle = rclcpp_action::ClientGoalHandle<Undock>;
72 void timerEvent(QTimerEvent * event)
override;
75 static inline QString getDockFeedbackLabel(Dock::Feedback msg = Dock::Feedback());
79 static inline std::string toLabel(T & msg);
82 static inline std::string toString(
double val,
int precision = 0);
85 static inline std::string dockStateToString(int16_t state);
86 static inline std::string dockErrorToString(int16_t error_code);
89 rclcpp::Node::SharedPtr client_node_;
92 std::chrono::milliseconds server_timeout_;
95 QBasicTimer action_timer_;
98 rclcpp_action::Client<Dock>::SharedPtr dock_client_;
99 rclcpp_action::Client<Undock>::SharedPtr undock_client_;
102 rclcpp::Subscription<Dock::Impl::FeedbackMessage>::SharedPtr docking_feedback_sub_;
103 rclcpp::Subscription<Undock::Impl::FeedbackMessage>::SharedPtr undocking_feedback_sub_;
104 rclcpp::Subscription<Dock::Impl::GoalStatusMessage>::SharedPtr docking_goal_status_sub_;
105 rclcpp::Subscription<Undock::Impl::GoalStatusMessage>::SharedPtr undocking_goal_status_sub_;
108 DockGoalHandle::SharedPtr dock_goal_handle_;
109 UndockGoalHandle::SharedPtr undock_goal_handle_;
112 bool plugins_loaded_ =
false;
113 bool server_failed_ =
false;
115 QVBoxLayout * main_layout_{
nullptr};
116 QHBoxLayout * info_layout_{
nullptr};
117 QVBoxLayout * feedback_layout_{
nullptr};
118 QHBoxLayout * dock_id_layout_{
nullptr};
119 QHBoxLayout * dock_type_layout_{
nullptr};
120 QHBoxLayout * dock_pose_layout_{
nullptr};
121 QHBoxLayout * nav_stage_layout_{
nullptr};
123 QComboBox * dock_type_{
nullptr};
124 QPushButton * docking_button_{
nullptr};
125 QPushButton * undocking_button_{
nullptr};
126 QCheckBox * use_dock_id_checkbox_{
nullptr};
127 QCheckBox * nav_to_staging_checkbox_{
nullptr};
129 QLabel * docking_goal_status_indicator_{
nullptr};
130 QLabel * docking_feedback_indicator_{
nullptr};
131 QLabel * docking_result_indicator_{
nullptr};
133 QLineEdit * dock_id_{
nullptr};
134 QLineEdit * dock_pose_x_{
nullptr};
135 QLineEdit * dock_pose_y_{
nullptr};
136 QLineEdit * dock_pose_yaw_{
nullptr};
139 bool docking_in_progress_ =
false;
140 bool undocking_in_progress_ =
false;
141 bool use_dock_id_ =
false;
143 QStateMachine state_machine_;
146 QState * pre_initial_{
nullptr};
147 QState * idle_{
nullptr};
148 QState * docking_{
nullptr};
149 QState * undocking_{
nullptr};
150 QState * canceled_docking_{
nullptr};
151 QState * canceled_undocking_{
nullptr};
160 rclcpp_action::Client<nav2_msgs::action::DockRobot>::SharedPtr & dock_client,
161 rclcpp_action::Client<nav2_msgs::action::UndockRobot>::SharedPtr & undock_client)
162 : dock_client_(dock_client), undock_client_(undock_client)
167 while (!dock_active_) {
168 dock_active_ = dock_client_->wait_for_action_server(std::chrono::seconds(1));
171 while (!undock_active_) {
172 undock_active_ = undock_client_->wait_for_action_server(std::chrono::seconds(1));
176 emit dockingActive();
178 emit dockingInactive();
181 if (undock_active_) {
182 emit undockingActive();
184 emit undockingInactive();
189 void dockingActive();
190 void dockingInactive();
191 void undockingActive();
192 void undockingInactive();
195 rclcpp_action::Client<nav2_msgs::action::DockRobot>::SharedPtr dock_client_;
196 rclcpp_action::Client<nav2_msgs::action::UndockRobot>::SharedPtr undock_client_;
197 bool dock_active_ =
false;
198 bool undock_active_ =
false;
Panel to interface to the docking server.
void load(const rviz_common::Config &config) override
Load and save configuration data.