15 #ifndef NAV2_RVIZ_PLUGINS__NAV2_PANEL_HPP_
16 #define NAV2_RVIZ_PLUGINS__NAV2_PANEL_HPP_
19 #include <QBasicTimer>
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"
43 namespace nav2_rviz_plugins
57 void onInitialize()
override;
60 void load(
const rviz_common::Config & config)
override;
61 void save(rviz_common::Config config)
const override;
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();
78 void initialStateHandler();
82 void onCancelButtonPressed();
83 void timerEvent(QTimerEvent * event)
override;
84 bool isLoopValueValid(std::string & loop);
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_;
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>;
110 rclcpp::Node::SharedPtr client_node_;
113 std::chrono::milliseconds server_timeout_;
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_;
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_;
136 std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
137 std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
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_;
148 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
149 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
151 QCheckBox * store_initial_pose_checkbox_{
nullptr};
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};
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};
167 QLineEdit * nr_of_loops_{
nullptr};
169 QStateMachine state_machine_;
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};
181 QLabel * imgDisplayLabel_{
nullptr};
187 QState * running_{
nullptr};
188 QState * canceled_{
nullptr};
191 QState * accumulating_{
nullptr};
192 QState * accumulated_wp_{
nullptr};
193 QState * accumulated_nav_through_poses_{
nullptr};
195 std::vector<geometry_msgs::msg::PoseStamped> acummulated_poses_;
196 std::vector<geometry_msgs::msg::PoseStamped> store_poses_;
199 void updateWpNavigationMarkers();
204 void resetUniqueId();
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());
214 static inline std::string toLabel(T & msg);
217 static inline std::string toString(
double val,
int precision = 0);
220 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr wp_navigation_markers_pub_;
228 using SystemStatus = nav2_lifecycle_manager::SystemStatus;
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)
238 SystemStatus status_nav = SystemStatus::TIMEOUT;
239 SystemStatus status_loc = SystemStatus::TIMEOUT;
241 while (status_nav == SystemStatus::TIMEOUT) {
242 if (status_nav == SystemStatus::TIMEOUT) {
243 status_nav = client_nav_->is_active(std::chrono::seconds(1));
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) {
254 tried_loc_bringup_once =
true;
257 if (status_nav == SystemStatus::ACTIVE) {
258 emit navigationActive();
260 emit navigationInactive();
263 if (status_loc == SystemStatus::ACTIVE) {
264 emit localizationActive();
266 emit localizationInactive();
271 void navigationActive();
272 void navigationInactive();
273 void localizationActive();
274 void localizationInactive();
277 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
278 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
Panel to interface to the nav2 stack.
void load(const rviz_common::Config &config) override
Load and save configuration data.