15 #ifndef NAV2_RVIZ_PLUGINS__SELECTOR_HPP_
16 #define NAV2_RVIZ_PLUGINS__SELECTOR_HPP_
20 #include <QGridLayout>
21 #include <QScrollArea>
22 #include <QToolButton>
25 #include "rclcpp/rclcpp.hpp"
26 #include "rviz_common/panel.hpp"
30 #include "std_msgs/msg/string.hpp"
34 namespace nav2_rviz_plugins
41 explicit Selector(QWidget * parent = 0);
47 rclcpp::Node::SharedPtr client_node_;
48 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_controller_;
49 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_planner_;
50 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_goal_checker_;
51 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_smoother_;
52 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_progress_checker_;
54 bool plugins_loaded_ =
false;
55 bool server_failed_ =
false;
57 std::thread load_plugins_thread_;
59 QVBoxLayout * main_layout_;
60 QHBoxLayout * row_1_layout_;
61 QHBoxLayout * row_2_layout_;
62 QHBoxLayout * row_3_layout_;
63 QHBoxLayout * row_1_label_layout_;
64 QHBoxLayout * row_2_label_layout_;
65 QHBoxLayout * row_3_label_layout_;
66 QComboBox * controller_;
68 QComboBox * goal_checker_;
69 QComboBox * smoother_;
70 QComboBox * progress_checker_;
74 void setGoalChecker();
76 void setProgressChecker();
84 QComboBox * combo_box,
85 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher);
88 QVBoxLayout * layout1 =
new QVBoxLayout;