7 setObjectName(
"RSM Controls");
14 QStringList argv = context.
argv();
15 _gui =
new Ui::rsm_controls;
33 "startStopExploration");
35 "setExplorationMode");
38 "startStopWaypointFollowing");
42 rsm_msgs::SetWaypointFollowingMode>(
"setWaypointFollowingMode");
62 rsm_msgs::GetWaypointRoutines>(
"getWaypointRoutines");
72 connect(
_gui->reset_waypoints_button, SIGNAL(clicked(
bool)),
this, SLOT(
resetWaypoints()));
74 connect(
_gui->set_waypoint_button, SIGNAL(clicked(
bool)),
this, SLOT(
addWaypoint()));
78 connect(
_gui->emergency_stop_button, SIGNAL(clicked(
bool)),
this, SLOT(
emergencyStop()));
79 connect(
_gui->stopped_radio_button, SIGNAL(clicked(
bool)),
this, SLOT(
stopOperation()));
81 connect(
_gui->teleoperation_radio_button, SIGNAL(clicked(
bool)),
this, SLOT(
setTeleoperation()));
83 connect(
_gui->stop_2d_nav_goal_button, SIGNAL(clicked(
bool)),
this, SLOT(
stop2dNavGoal()));
87 std_srvs::SetBool srv;
89 srv.request.data =
false;
91 srv.request.data =
true;
95 if (srv.response.success) {
97 _gui->start_exploration_button->setText(
"Start");
99 _gui->exploration_info_text->setText(
"Exploration stopped");
100 _gui->exploration_mode_box->setEnabled(
true);
102 _gui->start_exploration_button->setText(
"Stop");
104 _gui->exploration_info_text->setText(
"Exploration running");
106 _gui->exploration_mode_box->setEnabled(
false);
109 QString text = QString(
"Call unsuccessful: %1").arg(
110 srv.response.message.c_str());
111 _gui->exploration_info_text->setText(text);
114 ROS_ERROR(
"Failed to call service Start/Stop Exploration");
115 _gui->exploration_info_text->setText(
"Exploration service not available");
120 std_srvs::SetBool srv;
122 srv.request.data =
false;
124 srv.request.data =
true;
128 if (srv.response.success) {
130 _gui->start_waypoint_following_button->setText(
"Start");
132 _gui->waypoint_following_info_text->setText(
133 "Waypoint following stopped");
134 _gui->reset_waypoints_button->setEnabled(
true);
135 _gui->mode_box->setEnabled(
true);
137 _gui->start_waypoint_following_button->setText(
"Stop");
139 _gui->waypoint_following_info_text->setText(
"Waypoint running");
140 _gui->reset_waypoints_button->setEnabled(
false);
141 _gui->mode_box->setEnabled(
false);
145 QString text = QString(
"Call unsuccessful: %1").arg(
146 srv.response.message.c_str());
147 _gui->waypoint_following_info_text->setText(text);
150 ROS_ERROR(
"Failed to call service Start/Stop Waypoint Following");
151 _gui->waypoint_following_info_text->setText(
152 "Waypoint Following service not available");
157 std_srvs::Trigger srv;
160 if (srv.response.success) {
161 _gui->waypoint_following_info_text->setText(
"Waypoints reset");
163 QString text = QString(
"Reset unsuccessful: %1").arg(
164 srv.response.message.c_str());
165 _gui->waypoint_following_info_text->setText(text);
168 ROS_ERROR(
"Failed to call service Reset Waypoints");
169 _gui->waypoint_following_info_text->setText(
170 "Reset Waypoints service not available");
175 rsm_msgs::GetRobotPose srv;
177 ROS_ERROR(
"Failed to call Get Robot Pose service");
178 _gui->waypoint_following_info_text->setText(
179 "Get Robot Pose service not available");
181 rsm_msgs::AddWaypoint srv2;
182 rsm_msgs::Waypoint waypoint;
183 waypoint.pose = srv.response.pose;
184 if (
_gui->routine_combo_box->currentIndex() == 0) {
185 waypoint.routine =
"";
188 _gui->routine_combo_box->currentText().toUtf8().constData();
190 srv2.request.waypoint = waypoint;
191 srv2.request.position = -1;
193 ROS_ERROR(
"Failed to call Add Waypoint service");
194 _gui->waypoint_following_info_text->setText(
195 "Add Waypoint service not available");
201 std_srvs::SetBool srv;
204 if (srv.response.success) {
208 _gui->movement_label->setText(
"Control: Failed to change reverse mode");
211 ROS_ERROR(
"Failed to call Set Reverse Mode service");
212 _gui->movement_label->setText(
213 "Control: Set Reverse Mode service not available");
245 std_srvs::Trigger srv;
247 ROS_ERROR(
"Failed to call Stop 2D Nav Goal service");
248 _gui->movement_label->setText(
249 "Control: Stop 2D Nav Goal service not available");
254 rsm_msgs::SetOperationMode srv;
261 ROS_ERROR(
"Failed to call service Set Operation Mode");
262 _gui->control_label->setText(
263 "Control: Set Operation Mode service not available");
268 ROS_INFO(
"set waypoint following mode");
269 rsm_msgs::SetWaypointFollowingMode srv;
270 srv.request.mode =
_gui->mode_box->currentIndex();
272 if (!srv.response.success) {
274 QString(
"Set Waypoint Following Mode unsuccessful: %1").arg(
275 srv.response.message.c_str());
276 _gui->waypoint_following_info_text->setText(text);
280 ROS_ERROR(
"Failed to call service Set Waypoint Following Mode");
281 _gui->waypoint_following_info_text->setText(
282 "Set Waypoint Following Mode service not available");
287 std_srvs::SetBool srv;
288 srv.request.data =
_gui->exploration_mode_box->currentIndex();
290 ROS_ERROR(
"Failed to call service Set Operation Mode");
291 _gui->exploration_info_text->setText(
292 "Set Exploration Mode service not available");
297 const std_msgs::String::ConstPtr& state_info) {
298 QString text = QString(
"Current state: %1").arg(state_info->data.c_str());
299 _gui->current_state_text->setText(text);
300 if (state_info->data.rfind(
"E:") == 0) {
302 _gui->start_exploration_button->setText(
"Stop");
304 _gui->exploration_info_text->setText(
"Exploration running");
305 _gui->exploration_mode_box->setEnabled(
false);
307 }
else if (state_info->data.rfind(
"W:") == 0) {
309 _gui->start_waypoint_following_button->setText(
"Stop");
311 _gui->waypoint_following_info_text->setText(
312 "Waypoint Following running");
315 _gui->start_exploration_button->setText(
"Start");
317 _gui->exploration_info_text->setText(
"");
318 _gui->exploration_mode_box->setEnabled(
true);
319 _gui->start_waypoint_following_button->setText(
"Start");
320 _gui->reset_waypoints_button->setEnabled(
true);
321 _gui->mode_box->setEnabled(
true);
323 _gui->waypoint_following_info_text->setText(
"");
328 const std_msgs::Bool::ConstPtr& reverse_mode) {
334 const rsm_msgs::OperationMode::ConstPtr& operation_mode) {
347 rsm_msgs::GetWaypointRoutines srv;
351 list.append(it.c_str());
354 ROS_ERROR(
"Failed to call Get Waypoint Routines service");
356 _gui->routine_combo_box->addItems(list);
360 std_srvs::Trigger srv;
362 QString text = QString(
"Current state: %1").arg(
363 srv.response.message.c_str());
364 _gui->current_state_text->setText(text);
366 ROS_ERROR(
"Failed to call State Info service");
375 _gui->emergency_stop_button->setStyleSheet(
376 "background-color: rgba(150,75,75,1);color: rgba(0,0,0,1);");
377 _gui->autonomy_radio_button->setEnabled(
false);
378 _gui->teleoperation_radio_button->setEnabled(
false);
380 _gui->emergency_stop_button->setStyleSheet(
381 "background-color: rgba(150,0,0,1);color: rgba(255,255,255,1);");
382 _gui->autonomy_radio_button->setEnabled(
true);
383 _gui->teleoperation_radio_button->setEnabled(
true);
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
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
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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 call(MReq &req, MRes &res)
bool _exploration_running
Is the exploration currently running.
ros::ServiceClient _set_operation_mode_client
void addWidget(QWidget *widget)
ros::Subscriber _reverse_mode_subscriber
void startStopExploration()
void setWaypointFollowingMode()
void stateInfoCallback(const std_msgs::String::ConstPtr &state_info)
ros::ServiceClient _set_exploration_mode_client
const QStringList & argv() const
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
ROSCPP_DECL void shutdown()
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
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
Plugin for rqt which adds buttons to interface the rsm.