2323#include < string>
2424
2525// ROS
26+ #include " nav2_lifecycle_manager/lifecycle_manager_client.hpp"
2627#include " rclcpp/rclcpp.hpp"
2728#include " rclcpp_action/rclcpp_action.hpp"
2829#include " rviz_common/panel.hpp"
@@ -37,18 +38,30 @@ class QPushButton;
3738namespace nav2_rviz_plugins
3839{
3940
41+ class InitialDockThread ;
42+
43+ // / Panel to interface to the docking server
4044class DockingPanel : public rviz_common ::Panel
4145{
4246 Q_OBJECT
4347
4448public:
4549 explicit DockingPanel (QWidget * parent = 0 );
4650 virtual ~DockingPanel ();
51+
4752 void onInitialize () override ;
4853
54+ // / Load and save configuration data
55+ void load (const rviz_common::Config & config) override ;
56+ void save (rviz_common::Config config) const override ;
57+
4958private Q_SLOTS:
59+ void startThread ();
60+ void onStartup ();
5061 void onDockingButtonPressed ();
5162 void onUndockingButtonPressed ();
63+ void onCancelDocking ();
64+ void onCancelUndocking ();
5265 void dockIdCheckbox ();
5366
5467private:
@@ -57,14 +70,6 @@ private Q_SLOTS:
5770 using DockGoalHandle = rclcpp_action::ClientGoalHandle<Dock>;
5871 using UndockGoalHandle = rclcpp_action::ClientGoalHandle<Undock>;
5972
60- // Start the actions
61- void startDocking ();
62- void startUndocking ();
63-
64- // Cancel the actions
65- void cancelDocking ();
66- void cancelUndocking ();
67-
6873 // The (non-spinning) client node used to invoke the action client
6974 void timerEvent (QTimerEvent * event) override ;
7075
@@ -84,14 +89,33 @@ private Q_SLOTS:
8489
8590 // The (non-spinning) client node used to invoke the action client
8691 rclcpp::Node::SharedPtr client_node_;
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+
8796 // Timeout value when waiting for action servers to respond
8897 std::chrono::milliseconds server_timeout_;
8998
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+ rclcpp_action::Client<Dock>::SharedPtr dock_client_;
104+ rclcpp_action::Client<Undock>::SharedPtr undock_client_;
105+
106+ // Docking / Undocking action feedback subscribers
107+ rclcpp::Subscription<Dock::Impl::FeedbackMessage>::SharedPtr docking_feedback_sub_;
108+ rclcpp::Subscription<Undock::Impl::FeedbackMessage>::SharedPtr undocking_feedback_sub_;
109+ rclcpp::Subscription<Dock::Impl::GoalStatusMessage>::SharedPtr docking_goal_status_sub_;
110+ rclcpp::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+
90116 // Flags to indicate if the plugins have been loaded
91117 bool plugins_loaded_ = false ;
92118 bool server_failed_ = false ;
93- bool tried_once_ = false ;
94- QBasicTimer timer_;
95119
96120 QVBoxLayout * main_layout_{nullptr };
97121 QHBoxLayout * info_layout_{nullptr };
@@ -121,20 +145,62 @@ private Q_SLOTS:
121145 bool undocking_in_progress_ = false ;
122146 bool use_dock_id_ = false ;
123147
124- // The Dock and Undock action client
125- rclcpp_action::Client<Dock>::SharedPtr dock_client_;
126- rclcpp_action::Client<Undock>::SharedPtr undock_client_;
127- DockGoalHandle::SharedPtr dock_goal_handle_;
128- UndockGoalHandle::SharedPtr undock_goal_handle_;
148+ QStateMachine state_machine_;
149+ InitialDockThread * initial_thread_;
129150
130- // The Node pointer that we need to keep alive for the duration of this plugin.
131- std::shared_ptr<rviz_common::ros_integration::RosNodeAbstractionIface> node_ptr_;
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+ };
132158
133- // Docking / Undocking action feedback subscribers
134- rclcpp::Subscription<Dock::Impl::FeedbackMessage>::SharedPtr docking_feedback_sub_;
135- rclcpp::Subscription<Undock::Impl::FeedbackMessage>::SharedPtr undocking_feedback_sub_;
136- rclcpp::Subscription<Dock::Impl::GoalStatusMessage>::SharedPtr docking_goal_status_sub_;
137- rclcpp::Subscription<Undock::Impl::GoalStatusMessage>::SharedPtr undocking_goal_status_sub_;
159+ class InitialDockThread : public QThread
160+ {
161+ Q_OBJECT
162+
163+ public:
164+ explicit InitialDockThread (
165+ rclcpp_action::Client<nav2_msgs::action::DockRobot>::SharedPtr & dock_client,
166+ rclcpp_action::Client<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+ rclcpp_action::Client<nav2_msgs::action::DockRobot>::SharedPtr dock_client_;
201+ rclcpp_action::Client<nav2_msgs::action::UndockRobot>::SharedPtr undock_client_;
202+ bool dock_active_ = false ;
203+ bool undock_active_ = false ;
138204};
139205
140206} // namespace nav2_rviz_plugins
0 commit comments