RSMControls.cpp
Go to the documentation of this file.
1 #include "RSMControls.h"
2 
3 namespace rsm {
4 
6  rqt_gui_cpp::Plugin(), _widget_main(NULL), _gui(NULL) {
7  setObjectName("RSM Controls");
8 }
9 
11 }
12 
14  QStringList argv = context.argv();
15  _gui = new Ui::rsm_controls;
16  _widget_main = new QWidget();
17  _gui->setupUi(_widget_main);
18  context.addWidget(_widget_main);
20  connectSlots();
22  _exploration_running = false;
24  _emergency_stop_active = false;
25  _operation_mode = rsm_msgs::OperationMode::STOPPED;
27  getStateInfo();
28 }
29 
31  ros::NodeHandle nh("rsm");
32  _start_stop_exploration_client = nh.serviceClient<std_srvs::SetBool>(
33  "startStopExploration");
34  _set_exploration_mode_client = nh.serviceClient<std_srvs::SetBool>(
35  "setExplorationMode");
36 
38  "startStopWaypointFollowing");
39  _waypoint_reset_client = nh.serviceClient<std_srvs::Trigger>(
40  "resetWaypoints");
42  rsm_msgs::SetWaypointFollowingMode>("setWaypointFollowingMode");
43 
44  _state_info_subscriber = nh.subscribe("stateInfo", 10,
46  _state_info_client = nh.serviceClient<std_srvs::Trigger>("stateInfo");
47  _set_operation_mode_client = nh.serviceClient<rsm_msgs::SetOperationMode>(
48  "setOperationMode");
49  _operation_mode_subcriber = nh.subscribe<rsm_msgs::OperationMode>(
50  "operationMode", 1, &RSMControlPanel::operationModeCallback, this);
51 
52  _set_reverse_mode_client = nh.serviceClient<std_srvs::SetBool>(
53  "setReverseMode");
54  _reverse_mode_subscriber = nh.subscribe<std_msgs::Bool>("reverseMode", 10,
56  _stop_2d_nav_goal_client = nh.serviceClient<std_srvs::Trigger>(
57  "stop2DNavGoal");
58 
59  _add_waypoint_client = nh.serviceClient<rsm_msgs::AddWaypoint>(
60  "addWaypoint");
62  rsm_msgs::GetWaypointRoutines>("getWaypointRoutines");
63 
64  _get_robot_pose_client = nh.serviceClient<rsm_msgs::GetRobotPose>(
65  "getRobotPose");
66 }
67 
69 connect(_gui->start_exploration_button, SIGNAL(clicked(bool)), this, SLOT(startStopExploration()));
70 
71 connect(_gui->start_waypoint_following_button, SIGNAL(clicked(bool)), this, SLOT(startStopWaypointFollowing()));
72 connect(_gui->reset_waypoints_button, SIGNAL(clicked(bool)), this, SLOT(resetWaypoints()));
73 
74 connect(_gui->set_waypoint_button, SIGNAL(clicked(bool)), this, SLOT(addWaypoint()));
75 
76 connect(_gui->reverse_checkbox, SIGNAL(clicked(bool)), this, SLOT(setReverseMode()));
77 
78 connect(_gui->emergency_stop_button, SIGNAL(clicked(bool)), this, SLOT(emergencyStop()));
79 connect(_gui->stopped_radio_button, SIGNAL(clicked(bool)), this, SLOT(stopOperation()));
80 connect(_gui->autonomy_radio_button, SIGNAL(clicked(bool)), this, SLOT(setAutonomyOperation()));
81 connect(_gui->teleoperation_radio_button, SIGNAL(clicked(bool)), this, SLOT(setTeleoperation()));
82 
83 connect(_gui->stop_2d_nav_goal_button, SIGNAL(clicked(bool)), this, SLOT(stop2dNavGoal()));
84 }
85 
87 std_srvs::SetBool srv;
89  srv.request.data = false;
90 } else {
91  srv.request.data = true;
92 }
94  //ROS_INFO("State was changed: %s -> message: %s", srv.response.success ? "true" : "false", srv.response.message.c_str() );
95  if (srv.response.success) {
97  _gui->start_exploration_button->setText("Start");
98  _exploration_running = false;
99  _gui->exploration_info_text->setText("Exploration stopped");
100  _gui->exploration_mode_box->setEnabled(true);
101  } else {
102  _gui->start_exploration_button->setText("Stop");
103  _exploration_running = true;
104  _gui->exploration_info_text->setText("Exploration running");
106  _gui->exploration_mode_box->setEnabled(false);
107  }
108  } else {
109  QString text = QString("Call unsuccessful: %1").arg(
110  srv.response.message.c_str());
111  _gui->exploration_info_text->setText(text);
112  }
113 } else {
114  ROS_ERROR("Failed to call service Start/Stop Exploration");
115  _gui->exploration_info_text->setText("Exploration service not available");
116 }
117 }
118 
120 std_srvs::SetBool srv;
122  srv.request.data = false;
123 } else {
124  srv.request.data = true;
125 }
127  //ROS_INFO("State was changed: %s -> message: %s", srv.response.success ? "true" : "false", srv.response.message.c_str() );
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);
136  } else {
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);
143  }
144  } else {
145  QString text = QString("Call unsuccessful: %1").arg(
146  srv.response.message.c_str());
147  _gui->waypoint_following_info_text->setText(text);
148  }
149 } else {
150  ROS_ERROR("Failed to call service Start/Stop Waypoint Following");
151  _gui->waypoint_following_info_text->setText(
152  "Waypoint Following service not available");
153 }
154 }
155 
157 std_srvs::Trigger srv;
158 if (_waypoint_reset_client.call(srv)) {
159  //ROS_INFO("State was changed: %s -> message: %s", srv.response.success ? "true" : "false", srv.response.message.c_str() );
160  if (srv.response.success) {
161  _gui->waypoint_following_info_text->setText("Waypoints reset");
162  } else {
163  QString text = QString("Reset unsuccessful: %1").arg(
164  srv.response.message.c_str());
165  _gui->waypoint_following_info_text->setText(text);
166  }
167 } else {
168  ROS_ERROR("Failed to call service Reset Waypoints");
169  _gui->waypoint_following_info_text->setText(
170  "Reset Waypoints service not available");
171 }
172 }
173 
175 rsm_msgs::GetRobotPose srv;
176 if (!_get_robot_pose_client.call(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");
180 } else {
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 = "";
186  } else {
187  waypoint.routine =
188  _gui->routine_combo_box->currentText().toUtf8().constData();
189  }
190  srv2.request.waypoint = waypoint;
191  srv2.request.position = -1;
192  if (!_add_waypoint_client.call(srv2)) {
193  ROS_ERROR("Failed to call Add Waypoint service");
194  _gui->waypoint_following_info_text->setText(
195  "Add Waypoint service not available");
196  }
197 }
198 }
199 
201 std_srvs::SetBool srv;
202 srv.request.data = !_reverse_mode;
203 if (_set_reverse_mode_client.call(srv)) {
204  if (srv.response.success) {
206  _gui->reverse_checkbox->setChecked(_reverse_mode);
207  } else {
208  _gui->movement_label->setText("Control: Failed to change reverse mode");
209  }
210 } else {
211  ROS_ERROR("Failed to call Set Reverse Mode service");
212  _gui->movement_label->setText(
213  "Control: Set Reverse Mode service not available");
214 }
215 }
216 
219 _operation_mode = rsm_msgs::OperationMode::STOPPED;
221 }
222 
224 if (_operation_mode != rsm_msgs::OperationMode::STOPPED) {
225  _operation_mode = rsm_msgs::OperationMode::STOPPED;
227 }
228 }
229 
231 if (_operation_mode != rsm_msgs::OperationMode::AUTONOMOUS) {
232  _operation_mode = rsm_msgs::OperationMode::AUTONOMOUS;
234 }
235 }
236 
238 if (_operation_mode != rsm_msgs::OperationMode::TELEOPERATION) {
239  _operation_mode = rsm_msgs::OperationMode::TELEOPERATION;
241 }
242 }
243 
245 std_srvs::Trigger srv;
246 if (!_stop_2d_nav_goal_client.call(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");
250 }
251 }
252 
254 rsm_msgs::SetOperationMode srv;
255 srv.request.operationMode.emergencyStop = _emergency_stop_active;
256 srv.request.operationMode.mode = _operation_mode;
260 } else {
261  ROS_ERROR("Failed to call service Set Operation Mode");
262  _gui->control_label->setText(
263  "Control: Set Operation Mode service not available");
264 }
265 }
266 
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) {
273  QString text =
274  QString("Set Waypoint Following Mode unsuccessful: %1").arg(
275  srv.response.message.c_str());
276  _gui->waypoint_following_info_text->setText(text);
277  }
278 
279 } else {
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");
283 }
284 }
285 
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");
293 }
294 }
295 
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) {
301  if (!_exploration_running) {
302  _gui->start_exploration_button->setText("Stop");
303  _exploration_running = true;
304  _gui->exploration_info_text->setText("Exploration running");
305  _gui->exploration_mode_box->setEnabled(false);
306  }
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");
313  }
314 } else {
315  _gui->start_exploration_button->setText("Start");
316  _exploration_running = false;
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("");
324 }
325 }
326 
328  const std_msgs::Bool::ConstPtr& reverse_mode) {
329 _reverse_mode = reverse_mode->data;
330 _gui->reverse_checkbox->setChecked(_reverse_mode);
331 }
332 
334  const rsm_msgs::OperationMode::ConstPtr& operation_mode) {
337 } else {
338  _emergency_stop_active = operation_mode->emergencyStop;
339  _operation_mode = operation_mode->mode;
341 }
342 }
343 
345 QStringList list;
346 list.append("None");
347 rsm_msgs::GetWaypointRoutines srv;
349  _waypoint_routines = srv.response.waypointRoutines;
350  for (auto it : _waypoint_routines) {
351  list.append(it.c_str());
352  }
353 } else {
354  ROS_ERROR("Failed to call Get Waypoint Routines service");
355 }
356 _gui->routine_combo_box->addItems(list);
357 }
358 
360 std_srvs::Trigger srv;
361 if (_state_info_client.call(srv)) {
362  QString text = QString("Current state: %1").arg(
363  srv.response.message.c_str());
364  _gui->current_state_text->setText(text);
365 } else {
366  ROS_ERROR("Failed to call State Info service");
367 }
368 }
369 
371 _gui->stopped_radio_button->setChecked(_operation_mode == 0);
372 _gui->autonomy_radio_button->setChecked(_operation_mode == 1);
373 _gui->teleoperation_radio_button->setChecked(_operation_mode == 2);
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);
379 } else {
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);
384 }
385 }
386 
388 ros::shutdown();
389 }
390 
392  qt_gui_cpp::Settings& instance_settings) const {
393 
394 }
395 
397  const qt_gui_cpp::Settings& plugin_settings,
398  const qt_gui_cpp::Settings& instance_settings) {
399 
400 }
401 
402 } /* namespace rsm */
403 
405 
#define NULL
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::ServiceClient _set_waypoint_following_mode_client
Definition: RSMControls.h:65
ros::ServiceClient _state_info_client
Definition: RSMControls.h:72
QWidget * _widget_main
Definition: RSMControls.h:57
ros::ServiceClient _start_stop_waypoint_following_client
Definition: RSMControls.h:63
ros::ServiceClient _waypoint_reset_client
Definition: RSMControls.h:64
ros::ServiceClient _set_reverse_mode_client
Definition: RSMControls.h:68
void reverseModeCallback(const std_msgs::Bool::ConstPtr &reverse_mode)
ros::ServiceClient _add_waypoint_client
Definition: RSMControls.h:66
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
Definition: RSMControls.h:74
bool call(MReq &req, MRes &res)
bool _exploration_running
Is the exploration currently running.
Definition: RSMControls.h:86
ros::ServiceClient _set_operation_mode_client
Definition: RSMControls.h:70
void addWidget(QWidget *widget)
ros::Subscriber _reverse_mode_subscriber
Definition: RSMControls.h:75
void stateInfoCallback(const std_msgs::String::ConstPtr &state_info)
ros::ServiceClient _set_exploration_mode_client
Definition: RSMControls.h:71
const QStringList & argv() const
#define ROS_INFO(...)
ros::ServiceClient _get_robot_pose_client
Definition: RSMControls.h:69
bool _operation_mode_button_pushed
Was an operation mode button just pushed.
Definition: RSMControls.h:82
virtual ~RSMControlPanel()
Definition: RSMControls.cpp:10
Ui::rsm_controls * _gui
Definition: RSMControls.h:58
virtual void shutdownPlugin()
ros::Subscriber _operation_mode_subcriber
Definition: RSMControls.h:76
bool _waypoint_following_running
Is waypoint following currently running.
Definition: RSMControls.h:90
ros::ServiceClient _stop_2d_nav_goal_client
Definition: RSMControls.h:73
ROSCPP_DECL void shutdown()
void operationModeCallback(const rsm_msgs::OperationMode::ConstPtr &operation_mode)
std::vector< std::string > _waypoint_routines
Definition: RSMControls.h:106
ros::ServiceClient _start_stop_exploration_client
Definition: RSMControls.h:62
ros::ServiceClient _get_waypoint_routines_client
Definition: RSMControls.h:67
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
Definition: RSMControls.cpp:13
Plugin for rqt which adds buttons to interface the rsm.
Definition: RSMControls.h:31


rsm_rqt_plugins
Author(s): Marco Steinbrink
autogenerated on Tue Mar 16 2021 02:44:37