Nav2 Navigation Stack - jazzy  jazzy
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 #include "tf2_ros/transform_listener.h"
38 #include "tf2_ros/create_timer_ros.h"
39 #include "tf2_ros/buffer.h"
40 
41 class QPushButton;
42 
43 namespace nav2_rviz_plugins
44 {
45 
46 class InitialThread;
47 
49 class Nav2Panel : public rviz_common::Panel
50 {
51  Q_OBJECT
52 
53 public:
54  explicit Nav2Panel(QWidget * parent = 0);
55  virtual ~Nav2Panel();
56 
57  void onInitialize() override;
58 
60  void load(const rviz_common::Config & config) override;
61  void save(rviz_common::Config config) const override;
62 
63 private Q_SLOTS:
64  void startThread();
65  void onStartup();
66  void onShutdown();
67  void onCancel();
68  void onPause();
69  void onResume();
70  void onResumedWp();
71  void onAccumulatedWp();
72  void onAccumulatedNTP();
73  void onAccumulating();
74  void onNewGoal(double x, double y, double theta, QString frame);
75  void handleGoalSaver();
76  void handleGoalLoader();
77  void loophandler();
78  void initialStateHandler();
79 
80 private:
81  void loadLogFiles();
82  void onCancelButtonPressed();
83  void timerEvent(QTimerEvent * event) override;
84  bool isLoopValueValid(std::string & loop);
85 
86  int unique_id {0};
87  int goal_index_ = 0;
88  int loop_count_ = 0;
89  bool store_initial_pose_ = false;
90  bool initial_pose_stored_ = false;
91  bool loop_counter_stop_ = true;
92  std::string loop_no_ = "0";
93  std::string base_frame_;
94 
95  // Call to send NavigateToPose action request for goal poses
96  geometry_msgs::msg::PoseStamped convert_to_msg(
97  std::vector<double> pose,
98  std::vector<double> orientation);
99  void startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses);
100  void startNavigation(geometry_msgs::msg::PoseStamped);
101  void startNavThroughPoses(std::vector<geometry_msgs::msg::PoseStamped> poses);
102  using NavigationGoalHandle =
103  rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>;
104  using WaypointFollowerGoalHandle =
105  rclcpp_action::ClientGoalHandle<nav2_msgs::action::FollowWaypoints>;
106  using NavThroughPosesGoalHandle =
107  rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateThroughPoses>;
108 
109  // The (non-spinning) client node used to invoke the action client
110  rclcpp::Node::SharedPtr client_node_;
111 
112  // Timeout value when waiting for action servers to respnd
113  std::chrono::milliseconds server_timeout_;
114 
115  // A timer used to check on the completion status of the action
116  QBasicTimer timer_;
117 
118  // The NavigateToPose action client
119  rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SharedPtr navigation_action_client_;
120  rclcpp_action::Client<nav2_msgs::action::FollowWaypoints>::SharedPtr
121  waypoint_follower_action_client_;
122  rclcpp_action::Client<nav2_msgs::action::NavigateThroughPoses>::SharedPtr
123  nav_through_poses_action_client_;
124 
125  // Navigation action feedback subscribers
126  rclcpp::Subscription<nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage>::SharedPtr
127  navigation_feedback_sub_;
128  rclcpp::Subscription<nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage>::SharedPtr
129  nav_through_poses_feedback_sub_;
130  rclcpp::Subscription<nav2_msgs::action::NavigateToPose::Impl::GoalStatusMessage>::SharedPtr
131  navigation_goal_status_sub_;
132  rclcpp::Subscription<nav2_msgs::action::NavigateThroughPoses::Impl::GoalStatusMessage>::SharedPtr
133  nav_through_poses_goal_status_sub_;
134 
135  // Tf's for initial pose
136  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
137  std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
138 
139  // Goal-related state
140  nav2_msgs::action::NavigateToPose::Goal navigation_goal_;
141  nav2_msgs::action::FollowWaypoints::Goal waypoint_follower_goal_;
142  nav2_msgs::action::NavigateThroughPoses::Goal nav_through_poses_goal_;
143  NavigationGoalHandle::SharedPtr navigation_goal_handle_;
144  WaypointFollowerGoalHandle::SharedPtr waypoint_follower_goal_handle_;
145  NavThroughPosesGoalHandle::SharedPtr nav_through_poses_goal_handle_;
146 
147  // The client used to control the nav2 stack
148  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
149  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
150 
151  QCheckBox * store_initial_pose_checkbox_{nullptr};
152 
153  QPushButton * start_reset_button_{nullptr};
154  QPushButton * pause_resume_button_{nullptr};
155  QPushButton * navigation_mode_button_{nullptr};
156  QPushButton * save_waypoints_button_{nullptr};
157  QPushButton * load_waypoints_button_{nullptr};
158  QPushButton * pause_waypoint_button_{nullptr};
159 
160  QLabel * navigation_status_indicator_{nullptr};
161  QLabel * localization_status_indicator_{nullptr};
162  QLabel * navigation_goal_status_indicator_{nullptr};
163  QLabel * navigation_feedback_indicator_{nullptr};
164  QLabel * waypoint_status_indicator_{nullptr};
165  QLabel * number_of_loops_{nullptr};
166 
167  QLineEdit * nr_of_loops_{nullptr};
168 
169  QStateMachine state_machine_;
170  InitialThread * initial_thread_;
171 
172  QState * pre_initial_{nullptr};
173  QState * initial_{nullptr};
174  QState * idle_{nullptr};
175  QState * reset_{nullptr};
176  QState * paused_{nullptr};
177  QState * resumed_{nullptr};
178  QState * paused_wp_{nullptr};
179  QState * resumed_wp_{nullptr};
180 
181  QLabel * imgDisplayLabel_{nullptr};
182 
183  // The following states are added to allow for the state of the button to only expose reset
184  // while the NavigateToPoses action is not active. While running, the user will be allowed to
185  // cancel the action. The ROSActionTransition allows for the state of the action to be detected
186  // and the button state to change automatically.
187  QState * running_{nullptr};
188  QState * canceled_{nullptr};
189  // The following states are added to allow to collect several poses to perform a waypoint-mode
190  // navigation or navigate through poses mode.
191  QState * accumulating_{nullptr};
192  QState * accumulated_wp_{nullptr};
193  QState * accumulated_nav_through_poses_{nullptr};
194 
195  std::vector<geometry_msgs::msg::PoseStamped> acummulated_poses_;
196  std::vector<geometry_msgs::msg::PoseStamped> store_poses_;
197 
198  // Publish the visual markers with the waypoints
199  void updateWpNavigationMarkers();
200 
201  // Create unique id numbers for markers
202  int getUniqueId();
203 
204  void resetUniqueId();
205 
206  // create label string from feedback msg
207  static inline QString getNavToPoseFeedbackLabel(
208  nav2_msgs::action::NavigateToPose::Feedback msg =
209  nav2_msgs::action::NavigateToPose::Feedback());
210  static inline QString getNavThroughPosesFeedbackLabel(
211  nav2_msgs::action::NavigateThroughPoses::Feedback =
212  nav2_msgs::action::NavigateThroughPoses::Feedback());
213  template<typename T>
214  static inline std::string toLabel(T & msg);
215 
216  // round off double to the specified precision and convert to string
217  static inline std::string toString(double val, int precision = 0);
218 
219  // Waypoint navigation visual markers publisher
220  rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr wp_navigation_markers_pub_;
221 };
222 
223 class InitialThread : public QThread
224 {
225  Q_OBJECT
226 
227 public:
228  using SystemStatus = nav2_lifecycle_manager::SystemStatus;
229 
230  explicit InitialThread(
231  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_nav,
232  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_loc)
233  : client_nav_(client_nav), client_loc_(client_loc)
234  {}
235 
236  void run() override
237  {
238  SystemStatus status_nav = SystemStatus::TIMEOUT;
239  SystemStatus status_loc = SystemStatus::TIMEOUT;
240 
241  while (status_nav == SystemStatus::TIMEOUT) {
242  if (status_nav == SystemStatus::TIMEOUT) {
243  status_nav = client_nav_->is_active(std::chrono::seconds(1));
244  }
245  }
246 
247  // try to communicate twice, might not actually be up if in SLAM mode
248  bool tried_loc_bringup_once = false;
249  while (status_loc == SystemStatus::TIMEOUT) {
250  status_loc = client_loc_->is_active(std::chrono::seconds(1));
251  if (tried_loc_bringup_once) {
252  break;
253  }
254  tried_loc_bringup_once = true;
255  }
256 
257  if (status_nav == SystemStatus::ACTIVE) {
258  emit navigationActive();
259  } else {
260  emit navigationInactive();
261  }
262 
263  if (status_loc == SystemStatus::ACTIVE) {
264  emit localizationActive();
265  } else {
266  emit localizationInactive();
267  }
268  }
269 
270 signals:
271  void navigationActive();
272  void navigationInactive();
273  void localizationActive();
274  void localizationInactive();
275 
276 private:
277  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
278  std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
279 };
280 
281 } // namespace nav2_rviz_plugins
282 
283 #endif // NAV2_RVIZ_PLUGINS__NAV2_PANEL_HPP_
Panel to interface to the nav2 stack.
Definition: nav2_panel.hpp:50
void load(const rviz_common::Config &config) override
Load and save configuration data.