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"
40 namespace nav2_rviz_plugins
54 void onInitialize()
override;
57 void load(
const rviz_common::Config & config)
override;
58 void save(rviz_common::Config config)
const override;
67 void onAccumulatedWp();
68 void onAccumulatedNTP();
69 void onAccumulating();
70 void onNewGoal(
double x,
double y,
double theta, QString frame);
74 void onCancelButtonPressed();
75 void timerEvent(QTimerEvent * event)
override;
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>;
91 rclcpp::Node::SharedPtr client_node_;
94 std::chrono::milliseconds server_timeout_;
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_;
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_;
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_;
125 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
126 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
128 QPushButton * start_reset_button_{
nullptr};
129 QPushButton * pause_resume_button_{
nullptr};
130 QPushButton * navigation_mode_button_{
nullptr};
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};
137 QStateMachine state_machine_;
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};
150 QState * running_{
nullptr};
151 QState * canceled_{
nullptr};
154 QState * accumulating_{
nullptr};
155 QState * accumulated_wp_{
nullptr};
156 QState * accumulated_nav_through_poses_{
nullptr};
158 std::vector<geometry_msgs::msg::PoseStamped> acummulated_poses_;
161 void updateWpNavigationMarkers();
166 void resetUniqueId();
169 static inline QString getGoalStatusLabel(
170 int8_t status = action_msgs::msg::GoalStatus::STATUS_UNKNOWN);
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());
180 static inline std::string toLabel(T & msg);
183 static inline std::string toString(
double val,
int precision = 0);
186 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr wp_navigation_markers_pub_;
194 using SystemStatus = nav2_lifecycle_manager::SystemStatus;
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)
204 SystemStatus status_nav = SystemStatus::TIMEOUT;
205 SystemStatus status_loc = SystemStatus::TIMEOUT;
207 while (status_nav == SystemStatus::TIMEOUT) {
208 if (status_nav == SystemStatus::TIMEOUT) {
209 status_nav = client_nav_->is_active(std::chrono::seconds(1));
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) {
220 tried_loc_bringup_once =
true;
223 if (status_nav == SystemStatus::ACTIVE) {
224 emit navigationActive();
226 emit navigationInactive();
229 if (status_loc == SystemStatus::ACTIVE) {
230 emit localizationActive();
232 emit localizationInactive();
237 void navigationActive();
238 void navigationInactive();
239 void localizationActive();
240 void localizationInactive();
243 std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
244 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.