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 "rviz_common/ros_integration/ros_node_abstraction_iface.hpp"
35 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
36 #include "visualization_msgs/msg/marker_array.hpp"
37 #include "nav2_util/geometry_utils.hpp"
38 #include "tf2_ros/transform_listener.h"
39 #include "tf2_ros/create_timer_ros.h"
40 #include "tf2_ros/buffer.h"
44 namespace nav2_rviz_plugins
58 void onInitialize()
override;
61 void load(
const rviz_common::Config & config)
override;
62 void save(rviz_common::Config config)
const override;
72 void onAccumulatedWp();
73 void onAccumulatedNTP();
74 void onAccumulating();
75 void onNewGoal(
double x,
double y,
double theta, QString frame);
76 void handleGoalSaver();
77 void handleGoalLoader();
79 void initialStateHandler();
83 void onCancelButtonPressed();
84 void timerEvent(QTimerEvent * event)
override;
85 bool isLoopValueValid(std::string & loop);
90 bool store_initial_pose_ =
false;
91 bool initial_pose_stored_ =
false;
92 bool loop_counter_stop_ =
true;
93 std::string loop_no_ =
"0";
94 std::string base_frame_;
97 std::shared_ptr<rviz_common::ros_integration::RosNodeAbstractionIface> node_ptr_;
100 geometry_msgs::msg::PoseStamped convert_to_msg(
101 std::vector<double> pose,
102 std::vector<double> orientation);
103 void startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> poses);
104 void startNavigation(geometry_msgs::msg::PoseStamped);
105 void startNavThroughPoses(nav_msgs::msg::Goals poses);
106 using NavigationGoalHandle =
107 rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>;
108 using WaypointFollowerGoalHandle =
109 rclcpp_action::ClientGoalHandle<nav2_msgs::action::FollowWaypoints>;
110 using NavThroughPosesGoalHandle =
111 rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateThroughPoses>;
114 rclcpp::Node::SharedPtr client_node_;
117 std::chrono::milliseconds server_timeout_;
123 rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SharedPtr navigation_action_client_;
124 rclcpp_action::Client<nav2_msgs::action::FollowWaypoints>::SharedPtr
125 waypoint_follower_action_client_;
126 rclcpp_action::Client<nav2_msgs::action::NavigateThroughPoses>::SharedPtr
127 nav_through_poses_action_client_;
130 rclcpp::Subscription<nav2_msgs::action::NavigateToPose::Impl::FeedbackMessage>::SharedPtr
131 navigation_feedback_sub_;
132 rclcpp::Subscription<nav2_msgs::action::NavigateThroughPoses::Impl::FeedbackMessage>::SharedPtr
133 nav_through_poses_feedback_sub_;
134 rclcpp::Subscription<nav2_msgs::action::NavigateToPose::Impl::GoalStatusMessage>::SharedPtr
135 navigation_goal_status_sub_;
136 rclcpp::Subscription<nav2_msgs::action::NavigateThroughPoses::Impl::GoalStatusMessage>::SharedPtr
137 nav_through_poses_goal_status_sub_;
140 std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
141 std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
144 nav2_msgs::action::NavigateToPose::Goal navigation_goal_;
145 nav2_msgs::action::FollowWaypoints::Goal waypoint_follower_goal_;
146 nav2_msgs::action::NavigateThroughPoses::Goal nav_through_poses_goal_;
147 NavigationGoalHandle::SharedPtr navigation_goal_handle_;
148 WaypointFollowerGoalHandle::SharedPtr waypoint_follower_goal_handle_;
149 NavThroughPosesGoalHandle::SharedPtr nav_through_poses_goal_handle_;
152 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
153 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
155 QCheckBox * store_initial_pose_checkbox_{
nullptr};
157 QPushButton * start_reset_button_{
nullptr};
158 QPushButton * pause_resume_button_{
nullptr};
159 QPushButton * navigation_mode_button_{
nullptr};
160 QPushButton * save_waypoints_button_{
nullptr};
161 QPushButton * load_waypoints_button_{
nullptr};
162 QPushButton * pause_waypoint_button_{
nullptr};
164 QLabel * navigation_status_indicator_{
nullptr};
165 QLabel * localization_status_indicator_{
nullptr};
166 QLabel * navigation_goal_status_indicator_{
nullptr};
167 QLabel * navigation_feedback_indicator_{
nullptr};
168 QLabel * waypoint_status_indicator_{
nullptr};
169 QLabel * number_of_loops_{
nullptr};
171 QLineEdit * nr_of_loops_{
nullptr};
173 QStateMachine state_machine_;
176 QState * pre_initial_{
nullptr};
177 QState * initial_{
nullptr};
178 QState * idle_{
nullptr};
179 QState * reset_{
nullptr};
180 QState * paused_{
nullptr};
181 QState * resumed_{
nullptr};
182 QState * paused_wp_{
nullptr};
183 QState * resumed_wp_{
nullptr};
185 QLabel * imgDisplayLabel_{
nullptr};
191 QState * running_{
nullptr};
192 QState * canceled_{
nullptr};
195 QState * accumulating_{
nullptr};
196 QState * accumulated_wp_{
nullptr};
197 QState * accumulated_nav_through_poses_{
nullptr};
199 nav_msgs::msg::Goals acummulated_poses_;
200 nav_msgs::msg::Goals store_poses_;
203 void updateWpNavigationMarkers();
208 void resetUniqueId();
211 static inline QString getNavToPoseFeedbackLabel(
212 nav2_msgs::action::NavigateToPose::Feedback msg =
213 nav2_msgs::action::NavigateToPose::Feedback());
214 static inline QString getNavThroughPosesFeedbackLabel(
215 nav2_msgs::action::NavigateThroughPoses::Feedback =
216 nav2_msgs::action::NavigateThroughPoses::Feedback());
218 static inline std::string toLabel(T & msg);
221 static inline std::string toString(
double val,
int precision = 0);
224 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr wp_navigation_markers_pub_;
232 using SystemStatus = nav2_lifecycle_manager::SystemStatus;
235 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_nav,
236 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_loc)
237 : client_nav_(client_nav), client_loc_(client_loc)
242 SystemStatus status_nav = SystemStatus::TIMEOUT;
243 SystemStatus status_loc = SystemStatus::TIMEOUT;
245 while (status_nav == SystemStatus::TIMEOUT) {
246 if (status_nav == SystemStatus::TIMEOUT) {
247 status_nav = client_nav_->is_active(std::chrono::seconds(1));
252 bool tried_loc_bringup_once =
false;
253 while (status_loc == SystemStatus::TIMEOUT) {
254 status_loc = client_loc_->is_active(std::chrono::seconds(1));
255 if (tried_loc_bringup_once) {
258 tried_loc_bringup_once =
true;
261 if (status_nav == SystemStatus::ACTIVE) {
262 emit navigationActive();
264 emit navigationInactive();
267 if (status_loc == SystemStatus::ACTIVE) {
268 emit localizationActive();
270 emit localizationInactive();
275 void navigationActive();
276 void navigationInactive();
277 void localizationActive();
278 void localizationInactive();
281 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
282 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.