15 #ifndef NAV2_RVIZ_PLUGINS__DOCKING_PANEL_HPP_
16 #define NAV2_RVIZ_PLUGINS__DOCKING_PANEL_HPP_
20 #include <QBasicTimer>
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"
38 namespace nav2_rviz_plugins
41 class InitialDockThread;
52 void onInitialize()
override;
55 void load(
const rviz_common::Config & config)
override;
56 void save(rviz_common::Config config)
const override;
60 void onDockingButtonPressed();
61 void onUndockingButtonPressed();
62 void onCancelDocking();
63 void onCancelUndocking();
64 void dockIdCheckbox();
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>;
73 void timerEvent(QTimerEvent * event)
override;
76 static inline QString getDockFeedbackLabel(Dock::Feedback msg = Dock::Feedback());
80 static inline std::string toLabel(T & msg);
83 static inline std::string toString(
double val,
int precision = 0);
86 static inline std::string dockStateToString(int16_t state);
87 static inline std::string dockErrorToString(int16_t error_code);
90 rclcpp::Node::SharedPtr client_node_;
93 std::shared_ptr<rviz_common::ros_integration::RosNodeAbstractionIface> node_ptr_;
96 std::chrono::milliseconds server_timeout_;
99 QBasicTimer action_timer_;
102 rclcpp_action::Client<Dock>::SharedPtr dock_client_;
103 rclcpp_action::Client<Undock>::SharedPtr undock_client_;
106 rclcpp::Subscription<Dock::Impl::FeedbackMessage>::SharedPtr docking_feedback_sub_;
107 rclcpp::Subscription<Undock::Impl::FeedbackMessage>::SharedPtr undocking_feedback_sub_;
108 rclcpp::Subscription<Dock::Impl::GoalStatusMessage>::SharedPtr docking_goal_status_sub_;
109 rclcpp::Subscription<Undock::Impl::GoalStatusMessage>::SharedPtr undocking_goal_status_sub_;
112 DockGoalHandle::SharedPtr dock_goal_handle_;
113 UndockGoalHandle::SharedPtr undock_goal_handle_;
116 bool plugins_loaded_ =
false;
117 bool server_failed_ =
false;
119 QVBoxLayout * main_layout_{
nullptr};
120 QHBoxLayout * info_layout_{
nullptr};
121 QVBoxLayout * feedback_layout_{
nullptr};
122 QHBoxLayout * dock_id_layout_{
nullptr};
123 QHBoxLayout * dock_type_layout_{
nullptr};
124 QHBoxLayout * dock_pose_layout_{
nullptr};
125 QHBoxLayout * nav_stage_layout_{
nullptr};
127 QComboBox * dock_type_{
nullptr};
128 QPushButton * docking_button_{
nullptr};
129 QPushButton * undocking_button_{
nullptr};
130 QCheckBox * use_dock_id_checkbox_{
nullptr};
131 QCheckBox * nav_to_staging_checkbox_{
nullptr};
133 QLabel * docking_goal_status_indicator_{
nullptr};
134 QLabel * docking_feedback_indicator_{
nullptr};
135 QLabel * docking_result_indicator_{
nullptr};
137 QLineEdit * dock_id_{
nullptr};
138 QLineEdit * dock_pose_x_{
nullptr};
139 QLineEdit * dock_pose_y_{
nullptr};
140 QLineEdit * dock_pose_yaw_{
nullptr};
143 bool docking_in_progress_ =
false;
144 bool undocking_in_progress_ =
false;
145 bool use_dock_id_ =
false;
147 QStateMachine state_machine_;
150 QState * pre_initial_{
nullptr};
151 QState * idle_{
nullptr};
152 QState * docking_{
nullptr};
153 QState * undocking_{
nullptr};
154 QState * canceled_docking_{
nullptr};
155 QState * canceled_undocking_{
nullptr};
164 rclcpp_action::Client<nav2_msgs::action::DockRobot>::SharedPtr & dock_client,
165 rclcpp_action::Client<nav2_msgs::action::UndockRobot>::SharedPtr & undock_client)
166 : dock_client_(dock_client), undock_client_(undock_client)
171 while (!dock_active_) {
172 dock_active_ = dock_client_->wait_for_action_server(std::chrono::seconds(1));
175 while (!undock_active_) {
176 undock_active_ = undock_client_->wait_for_action_server(std::chrono::seconds(1));
180 emit dockingActive();
182 emit dockingInactive();
185 if (undock_active_) {
186 emit undockingActive();
188 emit undockingInactive();
193 void dockingActive();
194 void dockingInactive();
195 void undockingActive();
196 void undockingInactive();
199 rclcpp_action::Client<nav2_msgs::action::DockRobot>::SharedPtr dock_client_;
200 rclcpp_action::Client<nav2_msgs::action::UndockRobot>::SharedPtr undock_client_;
201 bool dock_active_ =
false;
202 bool undock_active_ =
false;
Panel to interface to the docking server.
void load(const rviz_common::Config &config) override
Load and save configuration data.