22 #include <QPushButton> 26 #include <QVBoxLayout> 27 #include <QHBoxLayout> 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);
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();
72 QFrame*
_line =
new QFrame();
73 _line->setFrameShape(QFrame::HLine);
74 _line->setFrameShadow(QFrame::Sunken);
86 _button4->setText(
"Clear Measurement Queue");
98 _button8->setText(
"Deserialize Map");
102 _label1->setText(
"Interactive Mode");
104 _label2->setText(
"Accept New Scans");
106 _label4->setText(
"Merge Map Tool");
107 _label4->setAlignment(Qt::AlignCenter);
109 _label5->setText(
"Create Map Tool");
110 _label5->setAlignment(Qt::AlignCenter);
113 _label6->setAlignment(Qt::AlignCenter);
116 _label7->setAlignment(Qt::AlignCenter);
119 _label8->setAlignment(Qt::AlignCenter);
122 _check1->setChecked(interactive);
125 _check2->setChecked(!paused_measure);
127 _radio1 =
new QRadioButton(tr(
"Start At Dock"));
129 _radio2 =
new QRadioButton(tr(
"Start At Pose Est."));
130 _radio3 =
new QRadioButton(tr(
"Start At Curr. Odom"));
131 _radio4 =
new QRadioButton(tr(
"Localize"));
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);
210 _vbox->addWidget(_line);
234 slam_toolbox_msgs::SerializePoseGraph msg;
235 msg.request.filename =
_line3->text().toStdString();
238 ROS_WARN(
"SlamToolbox: Failed to serialize pose graph to file, is service running?");
246 typedef slam_toolbox_msgs::DeserializePoseGraph::Request
procType;
248 slam_toolbox_msgs::DeserializePoseGraph msg;
249 msg.request.filename =
_line4->text().toStdString();
252 msg.request.match_type = procType::START_AT_FIRST_NODE;
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());
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());
270 ROS_WARN(
"No match type selected, cannot send request.");
275 ROS_WARN(
"SlamToolbox: Failed to deserialize mapper object " 276 "from file, is service running?");
284 slam_toolbox_msgs::AddSubmap msg;
285 msg.request.filename =
_line2->text().toStdString();
288 ROS_WARN(
"MergeMaps: Failed to load pose graph from file, is service running?");
295 slam_toolbox_msgs::MergeMaps msg;
298 ROS_WARN(
"MergeMaps: Failed to merge maps, is service running?");
306 slam_toolbox_msgs::Clear msg;
309 ROS_WARN(
"SlamToolbox: Failed to clear changes, is service running?");
317 slam_toolbox_msgs::LoopClosure msg;
321 ROS_WARN(
"SlamToolbox: Failed to save changes, is service running?");
329 slam_toolbox_msgs::SaveMap msg;
330 msg.request.name.data =
_line1->text().toStdString();
333 ROS_WARN(
"SlamToolbox: Failed to save map as %s, is service running?",
334 msg.request.name.data.c_str());
342 slam_toolbox_msgs::ClearQueue msg;
345 ROS_WARN(
"Failed to clear queue, is service running?");
353 slam_toolbox_msgs::ToggleInteractive msg;
356 ROS_WARN(
"SlamToolbox: Failed to toggle interactive mode, is service running?");
364 slam_toolbox_msgs::Pause msg;
367 ROS_WARN(
"SlamToolbox: Failed to toggle pause measurements, is service running?");
375 if (
_radio1->isChecked() == Qt::Unchecked)
382 ROS_INFO(
"Processing at first node selected.");
390 if (
_radio2->isChecked() == Qt::Unchecked)
397 ROS_INFO(
"Processing at current pose estimate selected.");
405 if (
_radio3->isChecked() == Qt::Unchecked)
412 ROS_INFO(
"Processing at current odometry selected.");
421 if (
_radio4->isChecked() == Qt::Unchecked)
428 ROS_INFO(
"Processing localization selected.");
439 bool paused_measure =
false, interactive =
false;
442 nh.
getParam(
"/slam_toolbox/paused_new_measurements", paused_measure);
443 nh.
getParam(
"/slam_toolbox/interactive_mode", interactive);
445 bool oldState =
_check1->blockSignals(
true);
446 _check1->setChecked(interactive);
447 _check1->blockSignals(oldState);
449 oldState =
_check2->blockSignals(
true);
450 _check2->setChecked(!paused_measure);
451 _check2->blockSignals(oldState);
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool call(MReq &req, MRes &res)
bool getParam(const std::string &key, std::string &s) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)