slam_toolbox_rviz_plugin.cpp
Go to the documentation of this file.
1 /*
2  * slam_toolbox
3  * Copyright (c) 2018, Simbe Robotics, Inc.
4  *
5  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9  *
10  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13  * CONDITIONS.
14  *
15  */
16 
17 /* Author: Steven Macenski */
18 
19 // Header
21 // QT
22 #include <QPushButton>
23 #include <QCheckBox>
24 #include <QLineEdit>
25 #include <QComboBox>
26 #include <QVBoxLayout>
27 #include <QHBoxLayout>
28 #include <QtGui>
29 #include <QLabel>
30 #include <QFrame>
31 
34 
35 namespace slam_toolbox
36 {
37 
38 /*****************************************************************************/
40  rviz::Panel(parent),
41  _thread(NULL),
42  _match_type(PROCESS_FIRST_NODE_CMT)
43 /*****************************************************************************/
44 {
45  ros::NodeHandle nh;
46  bool paused_measure = false, interactive = false;
47  nh.getParam("/slam_toolbox/paused_new_measurements", paused_measure);
48  nh.getParam("/slam_toolbox/interactive_mode", interactive);
49  _serialize = nh.serviceClient<slam_toolbox_msgs::SerializePoseGraph>("/slam_toolbox/serialize_map");
50  _load_map = nh.serviceClient<slam_toolbox_msgs::DeserializePoseGraph>("/slam_toolbox/deserialize_map");
51  _clearChanges = nh.serviceClient<slam_toolbox_msgs::Clear>("/slam_toolbox/clear_changes");
52  _saveChanges = nh.serviceClient<slam_toolbox_msgs::LoopClosure>("/slam_toolbox/manual_loop_closure");
53  _saveMap = nh.serviceClient<slam_toolbox_msgs::SaveMap>("/slam_toolbox/save_map");
54  _clearQueue = nh.serviceClient<slam_toolbox_msgs::ClearQueue>("/slam_toolbox/clear_queue");
55  _interactive = nh.serviceClient<slam_toolbox_msgs::ToggleInteractive>("/slam_toolbox/toggle_interactive_mode");
56  _pause_measurements = nh.serviceClient<slam_toolbox_msgs::Pause>("/slam_toolbox/pause_new_measurements");
57  _load_submap_for_merging = nh.serviceClient<slam_toolbox_msgs::AddSubmap>("/map_merging/add_submap");
58  _merge = nh.serviceClient<slam_toolbox_msgs::MergeMaps>("/map_merging/merge_submaps");
59 
60  _vbox = new QVBoxLayout();
61  _hbox1 = new QHBoxLayout();
62  _hbox2 = new QHBoxLayout();
63  _hbox3 = new QHBoxLayout();
64  _hbox4 = new QHBoxLayout();
65  _hbox5 = new QHBoxLayout();
66  _hbox6 = new QHBoxLayout();
67  _hbox7 = new QHBoxLayout();
68  _hbox8 = new QHBoxLayout();
69  _hbox9 = new QHBoxLayout();
70  _hbox10 = new QHBoxLayout();
71 
72  QFrame* _line = new QFrame();
73  _line->setFrameShape(QFrame::HLine);
74  _line->setFrameShadow(QFrame::Sunken);
75 
76  _button1 = new QPushButton(this);
77  _button1->setText("Clear Changes");
78  connect(_button1, SIGNAL(clicked()), this, SLOT(ClearChanges()));
79  _button2 = new QPushButton(this);
80  _button2->setText("Save Changes");
81  connect(_button2, SIGNAL(clicked()), this, SLOT(SaveChanges()));
82  _button3 = new QPushButton(this);
83  _button3->setText("Save Map");
84  connect(_button3, SIGNAL(clicked()), this, SLOT(SaveMap()));
85  _button4 = new QPushButton(this);
86  _button4->setText("Clear Measurement Queue");
87  connect(_button4, SIGNAL(clicked()), this, SLOT(ClearQueue()));
88  _button5 = new QPushButton(this);
89  _button5->setText("Add Submap");
90  connect(_button5, SIGNAL(clicked()), this, SLOT(LoadSubmap()));
91  _button6 = new QPushButton(this);
92  _button6->setText("Generate Map");
93  connect(_button6, SIGNAL(clicked()), this, SLOT(GenerateMap()));
94  _button7 = new QPushButton(this);
95  _button7->setText("Serialize Map");
96  connect(_button7, SIGNAL(clicked()), this, SLOT(SerializeMap()));
97  _button8 = new QPushButton(this);
98  _button8->setText("Deserialize Map");
99  connect(_button8, SIGNAL(clicked()), this, SLOT(DeserializeMap()));
100 
101  _label1 = new QLabel(this);
102  _label1->setText("Interactive Mode");
103  _label2 = new QLabel(this);
104  _label2->setText("Accept New Scans");
105  _label4 = new QLabel(this);
106  _label4->setText("Merge Map Tool");
107  _label4->setAlignment(Qt::AlignCenter);
108  _label5 = new QLabel(this);
109  _label5->setText("Create Map Tool");
110  _label5->setAlignment(Qt::AlignCenter);
111  _label6 = new QLabel(this);
112  _label6->setText("X");
113  _label6->setAlignment(Qt::AlignCenter);
114  _label7 = new QLabel(this);
115  _label7->setText("Y");
116  _label7->setAlignment(Qt::AlignCenter);
117  _label8 = new QLabel(this);
118  _label8->setText("θ");
119  _label8->setAlignment(Qt::AlignCenter);
120 
121  _check1 = new QCheckBox();
122  _check1->setChecked(interactive);
123  connect(_check1, SIGNAL(stateChanged(int)), this, SLOT(InteractiveCb(int)));
124  _check2 = new QCheckBox();
125  _check2->setChecked(!paused_measure);
126  connect(_check2, SIGNAL(stateChanged(int)), this, SLOT(PauseMeasurementsCb(int)));
127  _radio1 = new QRadioButton(tr("Start At Dock"));
128  _radio1->setChecked(true);
129  _radio2 = new QRadioButton(tr("Start At Pose Est."));
130  _radio3 = new QRadioButton(tr("Start At Curr. Odom"));
131  _radio4 = new QRadioButton(tr("Localize"));
132 
133  connect(_radio1, SIGNAL(clicked()), this, SLOT(FirstNodeMatchCb()));
134  connect(_radio2, SIGNAL(clicked()), this, SLOT(PoseEstMatchCb()));
135  connect(_radio3, SIGNAL(clicked()), this, SLOT(CurEstMatchCb()));
136  connect(_radio4, SIGNAL(clicked()), this, SLOT(LocalizeCb()));
137 
138  _line1 = new QLineEdit();
139  _line2 = new QLineEdit();
140  _line3 = new QLineEdit();
141  _line4 = new QLineEdit();
142  _line5 = new QLineEdit();
143  _line6 = new QLineEdit();
144  _line7 = new QLineEdit();
145 
146  _button1->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
147  _button2->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
148  _button3->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
149  _button4->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
150  _button5->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
151  _button6->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
152  _button7->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
153  _button8->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
154  _check1->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
155  _check2->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
156  _line1->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
157  _line2->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
158  _line3->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
159  _line4->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
160  _line5->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
161  _line6->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
162  _line7->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
163 
164  _hbox1->addWidget(_check1);
165  _hbox1->addWidget(_label1);
166  _hbox1->addWidget(_check2);
167  _hbox1->addWidget(_label2);
168 
169  _hbox2->addWidget(_button1);
170  _hbox2->addWidget(_button2);
171 
172  _hbox3->addWidget(_button3);
173  _hbox3->addWidget(_line1);
174 
175  _hbox4->addWidget(_button4);
176 
177  _hbox5->addWidget(_button5);
178  _hbox5->addWidget(_line2);
179 
180  _hbox6->addWidget(_button6);
181 
182  _hbox7->addWidget(_button7);
183  _hbox7->addWidget(_line3);
184 
185  _hbox8->addWidget(_button8);
186  _hbox8->addWidget(_line4);
187 
188  _hbox9->addWidget(_radio1);
189  _hbox9->addWidget(_radio2);
190  _hbox9->addWidget(_radio3);
191  _hbox9->addWidget(_radio4);
192  _hbox9->addStretch(1);
193 
194  _hbox10->addWidget(_label6);
195  _hbox10->addWidget(_line5);
196  _hbox10->addWidget(_label7);
197  _hbox10->addWidget(_line6);
198  _hbox10->addWidget(_label8);
199  _hbox10->addWidget(_line7);
200 
201  _vbox->addWidget(_label5);
202  _vbox->addLayout(_hbox1);
203  _vbox->addLayout(_hbox2);
204  _vbox->addLayout(_hbox3);
205  _vbox->addLayout(_hbox7);
206  _vbox->addLayout(_hbox8);
207  _vbox->addLayout(_hbox9);
208  _vbox->addLayout(_hbox10);
209  _vbox->addLayout(_hbox4);
210  _vbox->addWidget(_line);
211  _vbox->addWidget(_label4);
212  _vbox->addLayout(_hbox5);
213  _vbox->addLayout(_hbox6);
214 
215  setLayout(_vbox);
216 
218 }
219 
220 /*****************************************************************************/
222 /*****************************************************************************/
223 {
224  if (_thread)
225  {
226  delete _thread;
227  }
228 }
229 
230 /*****************************************************************************/
232 /*****************************************************************************/
233 {
234  slam_toolbox_msgs::SerializePoseGraph msg;
235  msg.request.filename = _line3->text().toStdString();
236  if (!_serialize.call(msg))
237  {
238  ROS_WARN("SlamToolbox: Failed to serialize pose graph to file, is service running?");
239  }
240 }
241 
242 /*****************************************************************************/
244 /*****************************************************************************/
245 {
246  typedef slam_toolbox_msgs::DeserializePoseGraph::Request procType;
247 
248  slam_toolbox_msgs::DeserializePoseGraph msg;
249  msg.request.filename = _line4->text().toStdString();
251  {
252  msg.request.match_type = procType::START_AT_FIRST_NODE;
253  }
255  {
256  msg.request.match_type = procType::START_AT_GIVEN_POSE;
257  msg.request.initial_pose.x = std::stod(_line5->text().toStdString());
258  msg.request.initial_pose.y = std::stod(_line6->text().toStdString());
259  msg.request.initial_pose.theta = std::stod(_line7->text().toStdString());
260  }
261  else if (_match_type == LOCALIZE_CMT)
262  {
263  msg.request.match_type = procType::LOCALIZE_AT_POSE;
264  msg.request.initial_pose.x = std::stod(_line5->text().toStdString());
265  msg.request.initial_pose.y = std::stod(_line6->text().toStdString());
266  msg.request.initial_pose.theta = std::stod(_line7->text().toStdString());
267  }
268  else
269  {
270  ROS_WARN("No match type selected, cannot send request.");
271  return;
272  }
273  if (!_load_map.call(msg))
274  {
275  ROS_WARN("SlamToolbox: Failed to deserialize mapper object "
276  "from file, is service running?");
277  }
278 }
279 
280 /*****************************************************************************/
282 /*****************************************************************************/
283 {
284  slam_toolbox_msgs::AddSubmap msg;
285  msg.request.filename = _line2->text().toStdString();
286  if (!_load_submap_for_merging.call(msg))
287  {
288  ROS_WARN("MergeMaps: Failed to load pose graph from file, is service running?");
289  }
290 }
291 /*****************************************************************************/
293 /*****************************************************************************/
294 {
295  slam_toolbox_msgs::MergeMaps msg;
296  if (!_merge.call(msg))
297  {
298  ROS_WARN("MergeMaps: Failed to merge maps, is service running?");
299  }
300 }
301 
302 /*****************************************************************************/
304 /*****************************************************************************/
305 {
306  slam_toolbox_msgs::Clear msg;
307  if (!_clearChanges.call(msg))
308  {
309  ROS_WARN("SlamToolbox: Failed to clear changes, is service running?");
310  }
311 }
312 
313 /*****************************************************************************/
315 /*****************************************************************************/
316 {
317  slam_toolbox_msgs::LoopClosure msg;
318 
319  if (!_saveChanges.call(msg))
320  {
321  ROS_WARN("SlamToolbox: Failed to save changes, is service running?");
322  }
323 }
324 
325 /*****************************************************************************/
327 /*****************************************************************************/
328 {
329  slam_toolbox_msgs::SaveMap msg;
330  msg.request.name.data = _line1->text().toStdString();
331  if (!_saveMap.call(msg))
332  {
333  ROS_WARN("SlamToolbox: Failed to save map as %s, is service running?",
334  msg.request.name.data.c_str());
335  }
336 }
337 
338 /*****************************************************************************/
340 /*****************************************************************************/
341 {
342  slam_toolbox_msgs::ClearQueue msg;
343  if (!_clearQueue.call(msg))
344  {
345  ROS_WARN("Failed to clear queue, is service running?");
346  }
347 }
348 
349 /*****************************************************************************/
351 /*****************************************************************************/
352 {
353  slam_toolbox_msgs::ToggleInteractive msg;
354  if (!_interactive.call(msg))
355  {
356  ROS_WARN("SlamToolbox: Failed to toggle interactive mode, is service running?");
357  }
358 }
359 
360 /*****************************************************************************/
362 /*****************************************************************************/
363 {
364  slam_toolbox_msgs::Pause msg;
365  if (!_pause_measurements.call(msg))
366  {
367  ROS_WARN("SlamToolbox: Failed to toggle pause measurements, is service running?");
368  }
369 }
370 
371 /*****************************************************************************/
373 /*****************************************************************************/
374 {
375  if (_radio1->isChecked() == Qt::Unchecked)
376  {
377  return;
378  }
379  else
380  {
382  ROS_INFO("Processing at first node selected.");
383  }
384 }
385 
386 /*****************************************************************************/
388 /*****************************************************************************/
389 {
390  if (_radio2->isChecked() == Qt::Unchecked)
391  {
392  return;
393  }
394  else
395  {
397  ROS_INFO("Processing at current pose estimate selected.");
398  }
399 }
400 
401 /*****************************************************************************/
403 /*****************************************************************************/
404 {
405  if (_radio3->isChecked() == Qt::Unchecked)
406  {
407  return;
408  }
409  else
410  {
412  ROS_INFO("Processing at current odometry selected.");
413  }
414 }
415 
416 
417 /*****************************************************************************/
419 /*****************************************************************************/
420 {
421  if (_radio4->isChecked() == Qt::Unchecked)
422  {
423  return;
424  }
425  else
426  {
428  ROS_INFO("Processing localization selected.");
429  }
430 }
431 
432 
433 /*****************************************************************************/
435 /*****************************************************************************/
436 {
437  ros::Rate r(1); //1 hz
438  ros::NodeHandle nh;
439  bool paused_measure = false, interactive = false;
440  while (ros::ok())
441  {
442  nh.getParam("/slam_toolbox/paused_new_measurements", paused_measure);
443  nh.getParam("/slam_toolbox/interactive_mode", interactive);
444 
445  bool oldState = _check1->blockSignals(true);
446  _check1->setChecked(interactive);
447  _check1->blockSignals(oldState);
448 
449  oldState = _check2->blockSignals(true);
450  _check2->setChecked(!paused_measure);
451  _check2->blockSignals(oldState);
452 
453  r.sleep();
454  }
455 }
456 
457 } // end namespace
#define NULL
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool call(MReq &req, MRes &res)
#define ROS_WARN(...)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
ROSCPP_DECL bool ok()
slam_toolbox_msgs::DeserializePoseGraph::Request procType
bool sleep()
r
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:49