Nav2 Navigation Stack - rolling  main
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 <memory>
23 #include <string>
24 
25 // ROS
26 #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp"
27 #include "rclcpp/rclcpp.hpp"
28 #include "rclcpp_action/rclcpp_action.hpp"
29 #include "rviz_common/panel.hpp"
30 #include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp"
31 #include "sensor_msgs/msg/battery_state.hpp"
32 #include "nav2_msgs/action/dock_robot.hpp"
33 #include "nav2_msgs/action/undock_robot.hpp"
34 
35 class QLineEdit;
36 class QPushButton;
37 
38 namespace nav2_rviz_plugins
39 {
40 
41 class InitialDockThread;
42 
44 class DockingPanel : public rviz_common::Panel
45 {
46  Q_OBJECT
47 
48 public:
49  explicit DockingPanel(QWidget * parent = 0);
50  virtual ~DockingPanel();
51 
52  void onInitialize() override;
53 
55  void load(const rviz_common::Config & config) override;
56  void save(rviz_common::Config config) const override;
57 
58 private Q_SLOTS:
59  void startThread();
60  void onDockingButtonPressed();
61  void onUndockingButtonPressed();
62  void onCancelDocking();
63  void onCancelUndocking();
64  void dockIdCheckbox();
65 
66 private:
67  using Dock = nav2_msgs::action::DockRobot;
68  using Undock = nav2_msgs::action::UndockRobot;
69  using DockGoalHandle = rclcpp_action::ClientGoalHandle<Dock>;
70  using UndockGoalHandle = rclcpp_action::ClientGoalHandle<Undock>;
71 
72  // The (non-spinning) client node used to invoke the action client
73  void timerEvent(QTimerEvent * event) override;
74 
75  // Create label string from feedback msg
76  static inline QString getDockFeedbackLabel(Dock::Feedback msg = Dock::Feedback());
77 
78  // Create label string from status msg
79  template<typename T>
80  static inline std::string toLabel(T & msg);
81 
82  // Round off double to the specified precision and convert to string
83  static inline std::string toString(double val, int precision = 0);
84 
85  // Convert the dock state and error code to string
86  static inline std::string dockStateToString(int16_t state);
87  static inline std::string dockErrorToString(int16_t error_code);
88 
89  // The (non-spinning) client node used to invoke the action client
90  rclcpp::Node::SharedPtr client_node_;
91  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
92 
93  // The Node pointer that we need to keep alive for the duration of this plugin.
94  std::shared_ptr<rviz_common::ros_integration::RosNodeAbstractionIface> node_ptr_;
95 
96  // Timeout value when waiting for action servers to respond
97  std::chrono::milliseconds server_timeout_;
98 
99  // A timer used to check on the completion status of the action
100  QBasicTimer action_timer_;
101 
102  // The Dock and Undock action client
103  nav2::ActionClient<Dock>::SharedPtr dock_client_;
104  nav2::ActionClient<Undock>::SharedPtr undock_client_;
105 
106  // Docking / Undocking action feedback subscribers
107  nav2::Subscription<Dock::Impl::FeedbackMessage>::SharedPtr docking_feedback_sub_;
108  nav2::Subscription<Undock::Impl::FeedbackMessage>::SharedPtr undocking_feedback_sub_;
109  nav2::Subscription<Dock::Impl::GoalStatusMessage>::SharedPtr docking_goal_status_sub_;
110  nav2::Subscription<Undock::Impl::GoalStatusMessage>::SharedPtr undocking_goal_status_sub_;
111 
112  // Goal related state
113  DockGoalHandle::SharedPtr dock_goal_handle_;
114  UndockGoalHandle::SharedPtr undock_goal_handle_;
115 
116  // Flags to indicate if the plugins have been loaded
117  bool plugins_loaded_ = false;
118  bool server_failed_ = false;
119 
120  QVBoxLayout * main_layout_{nullptr};
121  QHBoxLayout * info_layout_{nullptr};
122  QVBoxLayout * feedback_layout_{nullptr};
123  QHBoxLayout * dock_id_layout_{nullptr};
124  QHBoxLayout * dock_type_layout_{nullptr};
125  QHBoxLayout * dock_pose_layout_{nullptr};
126  QHBoxLayout * nav_stage_layout_{nullptr};
127 
128  QComboBox * dock_type_{nullptr};
129  QPushButton * docking_button_{nullptr};
130  QPushButton * undocking_button_{nullptr};
131  QCheckBox * use_dock_id_checkbox_{nullptr};
132  QCheckBox * nav_to_staging_checkbox_{nullptr};
133 
134  QLabel * docking_goal_status_indicator_{nullptr};
135  QLabel * docking_feedback_indicator_{nullptr};
136  QLabel * docking_result_indicator_{nullptr};
137 
138  QLineEdit * dock_id_{nullptr};
139  QLineEdit * dock_pose_x_{nullptr};
140  QLineEdit * dock_pose_y_{nullptr};
141  QLineEdit * dock_pose_yaw_{nullptr};
142 
143  // The current state of the docking and undocking actions
144  bool docking_in_progress_ = false;
145  bool undocking_in_progress_ = false;
146  bool use_dock_id_ = false;
147 
148  QStateMachine state_machine_;
149  InitialDockThread * initial_thread_;
150 
151  QState * pre_initial_{nullptr};
152  QState * idle_{nullptr};
153  QState * docking_{nullptr};
154  QState * undocking_{nullptr};
155  QState * canceled_docking_{nullptr};
156  QState * canceled_undocking_{nullptr};
157 };
158 
159 class InitialDockThread : public QThread
160 {
161  Q_OBJECT
162 
163 public:
164  explicit InitialDockThread(
165  nav2::ActionClient<nav2_msgs::action::DockRobot>::SharedPtr & dock_client,
166  nav2::ActionClient<nav2_msgs::action::UndockRobot>::SharedPtr & undock_client)
167  : dock_client_(dock_client), undock_client_(undock_client)
168  {}
169 
170  void run() override
171  {
172  while (!dock_active_) {
173  dock_active_ = dock_client_->wait_for_action_server(std::chrono::seconds(1));
174  }
175 
176  while (!undock_active_) {
177  undock_active_ = undock_client_->wait_for_action_server(std::chrono::seconds(1));
178  }
179 
180  if (dock_active_) {
181  emit dockingActive();
182  } else {
183  emit dockingInactive();
184  }
185 
186  if (undock_active_) {
187  emit undockingActive();
188  } else {
189  emit undockingInactive();
190  }
191  }
192 
193 signals:
194  void dockingActive();
195  void dockingInactive();
196  void undockingActive();
197  void undockingInactive();
198 
199 private:
200  nav2::ActionClient<nav2_msgs::action::DockRobot>::SharedPtr dock_client_;
201  nav2::ActionClient<nav2_msgs::action::UndockRobot>::SharedPtr undock_client_;
202  bool dock_active_ = false;
203  bool undock_active_ = false;
204 };
205 
206 } // namespace nav2_rviz_plugins
207 
208 #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