6 #include <QtWidgets/QWidget> 7 #include <QtWidgets/QPushButton> 11 #include "ui_rsm_controls.h" 12 #include <std_srvs/SetBool.h> 13 #include <std_srvs/Trigger.h> 14 #include <std_msgs/String.h> 15 #include <rsm_msgs/OperationMode.h> 16 #include <rsm_msgs/SetWaypointFollowingMode.h> 17 #include <rsm_msgs/AddWaypoint.h> 18 #include <rsm_msgs/GetWaypointRoutines.h> 19 #include <rsm_msgs/GetRobotPose.h> 20 #include <rsm_msgs/SetOperationMode.h> 21 #include <std_srvs/SetBool.h> 22 #include <std_msgs/Bool.h> 116 const rsm_msgs::OperationMode::ConstPtr& operation_mode);
ros::ServiceClient _set_waypoint_following_mode_client
ros::ServiceClient _state_info_client
void setExplorationMode()
ros::ServiceClient _start_stop_waypoint_following_client
ros::ServiceClient _waypoint_reset_client
ros::ServiceClient _set_reverse_mode_client
void updateOperationModeGUI()
void reverseModeCallback(const std_msgs::Bool::ConstPtr &reverse_mode)
ros::ServiceClient _add_waypoint_client
void startStopWaypointFollowing()
virtual void restoreSettings(const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings)
virtual void saveSettings(qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const
ros::Subscriber _state_info_subscriber
bool _exploration_running
Is the exploration currently running.
ros::ServiceClient _set_operation_mode_client
ros::Subscriber _reverse_mode_subscriber
void startStopExploration()
void setWaypointFollowingMode()
void stateInfoCallback(const std_msgs::String::ConstPtr &state_info)
ros::ServiceClient _set_exploration_mode_client
void setAutonomyOperation()
ros::ServiceClient _get_robot_pose_client
bool _operation_mode_button_pushed
Was an operation mode button just pushed.
void initRoutineComboBox()
virtual ~RSMControlPanel()
void callSetOperationMode()
virtual void shutdownPlugin()
ros::Subscriber _operation_mode_subcriber
bool _waypoint_following_running
Is waypoint following currently running.
ros::ServiceClient _stop_2d_nav_goal_client
ros::Subscriber _exploration_mode_subscriber
bool _emergency_stop_active
void operationModeCallback(const rsm_msgs::OperationMode::ConstPtr &operation_mode)
std::vector< std::string > _waypoint_routines
ros::ServiceClient _start_stop_exploration_client
void initCommunications()
ros::ServiceClient _get_waypoint_routines_client
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
Plugin for rqt which adds buttons to interface the rsm.