Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
docking_panel.hpp
1 // Copyright (c) 2024 Alberto J. Tudela Roldán
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_RVIZ_PLUGINS__DOCKING_PANEL_HPP_
16 #define NAV2_RVIZ_PLUGINS__DOCKING_PANEL_HPP_
17 
18 // QT
19 #include <QtWidgets>
20 #include <QBasicTimer>
21 
22 #include <string>
23 
24 // ROS
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"
32 
33 class QLineEdit;
34 class QPushButton;
35 
36 namespace nav2_rviz_plugins
37 {
38 
39 class InitialDockThread;
40 
42 class DockingPanel : public rviz_common::Panel
43 {
44  Q_OBJECT
45 
46 public:
47  explicit DockingPanel(QWidget * parent = 0);
48  virtual ~DockingPanel();
49 
50  void onInitialize() override;
51 
53  void load(const rviz_common::Config & config) override;
54  void save(rviz_common::Config config) const override;
55 
56 private Q_SLOTS:
57  void startThread();
58  void onStartup();
59  void onDockingButtonPressed();
60  void onUndockingButtonPressed();
61  void onCancelDocking();
62  void onCancelUndocking();
63  void dockIdCheckbox();
64 
65 private:
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>;
70 
71  // The (non-spinning) client node used to invoke the action client
72  void timerEvent(QTimerEvent * event) override;
73 
74  // Create label string from feedback msg
75  static inline QString getDockFeedbackLabel(Dock::Feedback msg = Dock::Feedback());
76 
77  // Create label string from status msg
78  template<typename T>
79  static inline std::string toLabel(T & msg);
80 
81  // Round off double to the specified precision and convert to string
82  static inline std::string toString(double val, int precision = 0);
83 
84  // Convert the dock state and error code to string
85  static inline std::string dockStateToString(int16_t state);
86  static inline std::string dockErrorToString(int16_t error_code);
87 
88  // The (non-spinning) client node used to invoke the action client
89  rclcpp::Node::SharedPtr client_node_;
90 
91  // Timeout value when waiting for action servers to respond
92  std::chrono::milliseconds server_timeout_;
93 
94  // A timer used to check on the completion status of the action
95  QBasicTimer action_timer_;
96 
97  // The Dock and Undock action client
98  rclcpp_action::Client<Dock>::SharedPtr dock_client_;
99  rclcpp_action::Client<Undock>::SharedPtr undock_client_;
100 
101  // Docking / Undocking action feedback subscribers
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_;
106 
107  // Goal related state
108  DockGoalHandle::SharedPtr dock_goal_handle_;
109  UndockGoalHandle::SharedPtr undock_goal_handle_;
110 
111  // Flags to indicate if the plugins have been loaded
112  bool plugins_loaded_ = false;
113  bool server_failed_ = false;
114 
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};
122 
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};
128 
129  QLabel * docking_goal_status_indicator_{nullptr};
130  QLabel * docking_feedback_indicator_{nullptr};
131  QLabel * docking_result_indicator_{nullptr};
132 
133  QLineEdit * dock_id_{nullptr};
134  QLineEdit * dock_pose_x_{nullptr};
135  QLineEdit * dock_pose_y_{nullptr};
136  QLineEdit * dock_pose_yaw_{nullptr};
137 
138  // The current state of the docking and undocking actions
139  bool docking_in_progress_ = false;
140  bool undocking_in_progress_ = false;
141  bool use_dock_id_ = false;
142 
143  QStateMachine state_machine_;
144  InitialDockThread * initial_thread_;
145 
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};
152 };
153 
154 class InitialDockThread : public QThread
155 {
156  Q_OBJECT
157 
158 public:
159  explicit InitialDockThread(
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)
163  {}
164 
165  void run() override
166  {
167  while (!dock_active_) {
168  dock_active_ = dock_client_->wait_for_action_server(std::chrono::seconds(1));
169  }
170 
171  while (!undock_active_) {
172  undock_active_ = undock_client_->wait_for_action_server(std::chrono::seconds(1));
173  }
174 
175  if (dock_active_) {
176  emit dockingActive();
177  } else {
178  emit dockingInactive();
179  }
180 
181  if (undock_active_) {
182  emit undockingActive();
183  } else {
184  emit undockingInactive();
185  }
186  }
187 
188 signals:
189  void dockingActive();
190  void dockingInactive();
191  void undockingActive();
192  void undockingInactive();
193 
194 private:
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;
199 };
200 
201 } // namespace nav2_rviz_plugins
202 
203 #endif // NAV2_RVIZ_PLUGINS__DOCKING_PANEL_HPP_
Panel to interface to the docking server.
void load(const rviz_common::Config &config) override
Load and save configuration data.
Definition: types.hpp:33