Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
nav2_panel.hpp
1 // Copyright (c) 2019 Intel Corporation
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__NAV2_PANEL_HPP_
16 #define NAV2_RVIZ_PLUGINS__NAV2_PANEL_HPP_
17 
18 #include <QtWidgets>
19 #include <QBasicTimer>
20 #undef NO_ERROR
21 
22 #include <memory>
23 #include <string>
24 #include <vector>
25 
26 #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp"
27 #include "nav2_msgs/action/navigate_to_pose.hpp"
28 #include "nav2_msgs/action/navigate_through_poses.hpp"
29 #include "nav2_msgs/action/follow_waypoints.hpp"
30 #include "nav2_rviz_plugins/ros_action_qevent.hpp"
31 #include "rclcpp/rclcpp.hpp"
32 #include "rclcpp_action/rclcpp_action.hpp"
33 #include "rviz_common/panel.hpp"
34 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
35 #include "visualization_msgs/msg/marker_array.hpp"
36 #include "nav2_util/geometry_utils.hpp"
37 
38 class QPushButton;
39 
40 namespace nav2_rviz_plugins
41 {
42 
43 class InitialThread;
44 
46 class Nav2Panel : public rviz_common::Panel
47 {
48  Q_OBJECT
49 
50 public:
51  explicit Nav2Panel(QWidget * parent = 0);
52  virtual ~Nav2Panel();
53 
54  void onInitialize() override;
55 
57  void load(const rviz_common::Config & config) override;
58  void save(rviz_common::Config config) const override;
59 
60 private Q_SLOTS:
61  void startThread();
62  void onStartup();
63  void onShutdown();
64  void onCancel();
65  void onPause();
66  void onResume();
67  void onAccumulatedWp();
68  void onAccumulatedNTP();
69  void onAccumulating();
70  void onNewGoal(double x, double y, double theta, QString frame);
71 
72 private:
73  void loadLogFiles();
74  void onCancelButtonPressed();
75  void timerEvent(QTimerEvent * event) override;
76 
77  int unique_id {0};
78 
79  // Call to send NavigateToPose action request for goal poses
80  void startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses);
81  void startNavigation(geometry_msgs::msg::PoseStamped);
82  void startNavThroughPoses(std::vector<geometry_msgs::msg::PoseStamped> poses);
83  using NavigationGoalHandle =
84  rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>;
85  using WaypointFollowerGoalHandle =
86  rclcpp_action::ClientGoalHandle<nav2_msgs::action::FollowWaypoints>;
87  using NavThroughPosesGoalHandle =
88  rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateThroughPoses>;
89 
90  // The (non-spinning) client node used to invoke the action client
91  rclcpp::Node::SharedPtr client_node_;
92 
93  // Timeout value when waiting for action servers to respnd
94  std::chrono::milliseconds server_timeout_;
95 
96  // A timer used to check on the completion status of the action
97  QBasicTimer timer_;
98 
99  // The NavigateToPose action client
100  rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SharedPtr navigation_action_client_;
101  rclcpp_action::Client<nav2_msgs::action::FollowWaypoints>::SharedPtr
102  waypoint_follower_action_client_;
103  rclcpp_action::Client<nav2_msgs::action::NavigateThroughPoses>::SharedPtr
104  nav_through_poses_action_client_;
105 
106  // Navigation action feedback subscribers
107  rclcpp::Subscription<nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage>::SharedPtr
108  navigation_feedback_sub_;
109  rclcpp::Subscription<nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage>::SharedPtr
110  nav_through_poses_feedback_sub_;
111  rclcpp::Subscription<nav2_msgs::action::NavigateToPose::Impl::GoalStatusMessage>::SharedPtr
112  navigation_goal_status_sub_;
113  rclcpp::Subscription<nav2_msgs::action::NavigateThroughPoses::Impl::GoalStatusMessage>::SharedPtr
114  nav_through_poses_goal_status_sub_;
115 
116  // Goal-related state
117  nav2_msgs::action::NavigateToPose::Goal navigation_goal_;
118  nav2_msgs::action::FollowWaypoints::Goal waypoint_follower_goal_;
119  nav2_msgs::action::NavigateThroughPoses::Goal nav_through_poses_goal_;
120  NavigationGoalHandle::SharedPtr navigation_goal_handle_;
121  WaypointFollowerGoalHandle::SharedPtr waypoint_follower_goal_handle_;
122  NavThroughPosesGoalHandle::SharedPtr nav_through_poses_goal_handle_;
123 
124  // The client used to control the nav2 stack
125  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
126  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
127 
128  QPushButton * start_reset_button_{nullptr};
129  QPushButton * pause_resume_button_{nullptr};
130  QPushButton * navigation_mode_button_{nullptr};
131 
132  QLabel * navigation_status_indicator_{nullptr};
133  QLabel * localization_status_indicator_{nullptr};
134  QLabel * navigation_goal_status_indicator_{nullptr};
135  QLabel * navigation_feedback_indicator_{nullptr};
136 
137  QStateMachine state_machine_;
138  InitialThread * initial_thread_;
139 
140  QState * pre_initial_{nullptr};
141  QState * initial_{nullptr};
142  QState * idle_{nullptr};
143  QState * reset_{nullptr};
144  QState * paused_{nullptr};
145  QState * resumed_{nullptr};
146  // The following states are added to allow for the state of the button to only expose reset
147  // while the NavigateToPoses action is not active. While running, the user will be allowed to
148  // cancel the action. The ROSActionTransition allows for the state of the action to be detected
149  // and the button state to change automatically.
150  QState * running_{nullptr};
151  QState * canceled_{nullptr};
152  // The following states are added to allow to collect several poses to perform a waypoint-mode
153  // navigation or navigate through poses mode.
154  QState * accumulating_{nullptr};
155  QState * accumulated_wp_{nullptr};
156  QState * accumulated_nav_through_poses_{nullptr};
157 
158  std::vector<geometry_msgs::msg::PoseStamped> acummulated_poses_;
159 
160  // Publish the visual markers with the waypoints
161  void updateWpNavigationMarkers();
162 
163  // Create unique id numbers for markers
164  int getUniqueId();
165 
166  void resetUniqueId();
167 
168  // create label string from goal status msg
169  static inline QString getGoalStatusLabel(
170  int8_t status = action_msgs::msg::GoalStatus::STATUS_UNKNOWN);
171 
172  // create label string from feedback msg
173  static inline QString getNavToPoseFeedbackLabel(
174  nav2_msgs::action::NavigateToPose::Feedback msg =
175  nav2_msgs::action::NavigateToPose::Feedback());
176  static inline QString getNavThroughPosesFeedbackLabel(
177  nav2_msgs::action::NavigateThroughPoses::Feedback =
178  nav2_msgs::action::NavigateThroughPoses::Feedback());
179  template<typename T>
180  static inline std::string toLabel(T & msg);
181 
182  // round off double to the specified precision and convert to string
183  static inline std::string toString(double val, int precision = 0);
184 
185  // Waypoint navigation visual markers publisher
186  rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr wp_navigation_markers_pub_;
187 };
188 
189 class InitialThread : public QThread
190 {
191  Q_OBJECT
192 
193 public:
194  using SystemStatus = nav2_lifecycle_manager::SystemStatus;
195 
196  explicit InitialThread(
197  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_nav,
198  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_loc)
199  : client_nav_(client_nav), client_loc_(client_loc)
200  {}
201 
202  void run() override
203  {
204  SystemStatus status_nav = SystemStatus::TIMEOUT;
205  SystemStatus status_loc = SystemStatus::TIMEOUT;
206 
207  while (status_nav == SystemStatus::TIMEOUT) {
208  if (status_nav == SystemStatus::TIMEOUT) {
209  status_nav = client_nav_->is_active(std::chrono::seconds(1));
210  }
211  }
212 
213  // try to communicate twice, might not actually be up if in SLAM mode
214  bool tried_loc_bringup_once = false;
215  while (status_loc == SystemStatus::TIMEOUT) {
216  status_loc = client_loc_->is_active(std::chrono::seconds(1));
217  if (tried_loc_bringup_once) {
218  break;
219  }
220  tried_loc_bringup_once = true;
221  }
222 
223  if (status_nav == SystemStatus::ACTIVE) {
224  emit navigationActive();
225  } else {
226  emit navigationInactive();
227  }
228 
229  if (status_loc == SystemStatus::ACTIVE) {
230  emit localizationActive();
231  } else {
232  emit localizationInactive();
233  }
234  }
235 
236 signals:
237  void navigationActive();
238  void navigationInactive();
239  void localizationActive();
240  void localizationInactive();
241 
242 private:
243  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
244  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
245 };
246 
247 } // namespace nav2_rviz_plugins
248 
249 #endif // NAV2_RVIZ_PLUGINS__NAV2_PANEL_HPP_
Panel to interface to the nav2 stack.
Definition: nav2_panel.hpp:47
void load(const rviz_common::Config &config) override
Load and save configuration data.
Definition: nav2_panel.cpp:819