40 #include <boost/algorithm/string/replace.hpp>
41 #include <boost/algorithm/string/split.hpp>
42 #include <boost/algorithm/string/join.hpp>
43 #include <boost/date_time/posix_time/posix_time.hpp>
44 #include <boost/filesystem.hpp>
45 #include <boost/make_shared.hpp>
48 #include <opencv2/core/core.hpp>
49 #include <opencv2/imgproc/imgproc.hpp>
51 #if CV_MAJOR_VERSION > 2
52 #include <opencv2/imgcodecs/imgcodecs.hpp>
53 #include <opencv2/videoio/videoio.hpp>
57 #if QT_VERSION >= 0x050000
58 #include <QtWidgets/QApplication>
60 #include <QtGui/QApplication>
62 #include <QFileDialog>
63 #include <QActionGroup>
64 #include <QColorDialog>
66 #include <QMessageBox>
67 #include <QProcessEnvironment>
69 #include <QListWidgetItem>
70 #include <QMutexLocker>
77 #include <QtGui/QtGui>
87 Mapviz::Mapviz(
bool is_standalone,
int argc,
char** argv, QWidget *parent, Qt::WindowFlags flags) :
88 QMainWindow(parent, flags),
89 xy_pos_label_(new QLabel(
"fixed: 0.0,0.0")),
90 lat_lon_pos_label_(new QLabel(
"lat/lon: 0.0,0.0")),
93 is_standalone_(is_standalone),
98 background_(Qt::gray),
99 capture_directory_(
"~"),
101 updating_frames_(false),
134 rec_button_->setIcon(QIcon(
":/images/media-record.png"));
137 rec_button_->setToolTip(
"Start recording video of display canvas");
143 stop_button_->setIcon(QIcon(
":/images/media-playback-stop.png"));
144 stop_button_->setToolTip(
"Stop recording video of display canvas");
158 recenter_button_->setToolTip(
"Reset the viewport to the default location and zoom level");
162 ui_.statusbar->setVisible(
true);
164 QActionGroup* group =
new QActionGroup(
this);
166 ui_.actionForce_720p->setActionGroup(group);
167 ui_.actionForce_480p->setActionGroup(group);
168 ui_.actionResizable->setActionGroup(group);
170 ui_.targetframe->addItem(
"<none>");
175 connect(
canvas_, SIGNAL(
Hover(
double,
double,
double)),
this, SLOT(
Hover(
double,
double,
double)));
177 connect(
ui_.actionExit, SIGNAL(triggered()),
this, SLOT(close()));
178 connect(
ui_.actionClear, SIGNAL(triggered()),
this, SLOT(
ClearConfig()));
185 connect(
ui_.actionClear_History, SIGNAL(triggered()),
this, SLOT(
ClearHistory()));
252 for (std::vector<std::string>::iterator iter = transports.begin(); iter != transports.end(); iter++)
254 QString transport = QString::fromStdString(*iter).replace(
257 action->setCheckable(
true);
258 group->addAction(action);
261 connect(group, SIGNAL(triggered(QAction*)),
this, SLOT(
SetImageTransport(QAction*)));
263 tf_ = boost::make_shared<tf::TransformListener>();
264 tf_manager_ = boost::make_shared<swri_transform_util::TransformManager>();
268 "mapviz",
"mapviz::MapvizPlugin");
270 std::vector<std::string> plugins =
loader_->getDeclaredClasses();
271 for (
unsigned int i = 0; i < plugins.size(); i++)
273 ROS_INFO(
"Found mapviz plugin: %s", plugins[i].c_str());
284 QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
285 QString default_path = QDir::homePath();
294 default_path = ws_path;
298 ROS_WARN(
"Could not load config file from ROS_WORKSPACE at %s; trying home directory...",
299 ws_path.toStdString().c_str());
306 priv.
param(
"config",
config, default_path.toStdString());
309 priv.
param(
"auto_save_backup", auto_save,
true);
325 bool print_profile_data;
326 priv.
param(
"print_profile_data", print_profile_data,
false);
327 if (print_profile_data)
349 QApplication::exit();
355 std::vector<std::string> frames;
356 tf_->getFrameStrings(frames);
357 std::sort(frames.begin(), frames.end());
359 if (
ui_.fixedframe->count() >= 0 &&
360 static_cast<size_t>(
ui_.fixedframe->count()) == frames.size())
362 bool changed =
false;
363 for (
size_t i = 0; i < frames.size(); i++)
365 if (frames[i] !=
ui_.fixedframe->itemText(i).toStdString())
377 std::string current_fixed =
ui_.fixedframe->currentText().toStdString();
379 ui_.fixedframe->clear();
380 for (
size_t i = 0; i < frames.size(); i++)
382 ui_.fixedframe->addItem(frames[i].c_str());
385 if (current_fixed !=
"")
387 int index =
ui_.fixedframe->findText(current_fixed.c_str());
390 ui_.fixedframe->addItem(current_fixed.c_str());
393 index =
ui_.fixedframe->findText(current_fixed.c_str());
394 ui_.fixedframe->setCurrentIndex(index);
397 std::string current_target =
ui_.targetframe->currentText().toStdString();
399 ui_.targetframe->clear();
400 ui_.targetframe->addItem(
"<none>");
401 for (
size_t i = 0; i < frames.size(); i++)
403 ui_.targetframe->addItem(frames[i].c_str());
406 if (current_target !=
"")
408 int index =
ui_.targetframe->findText(current_target.c_str());
411 ui_.targetframe->addItem(current_target.c_str());
414 index =
ui_.targetframe->findText(current_target.c_str());
415 ui_.targetframe->setCurrentIndex(index);
420 if (current_target !=
ui_.targetframe->currentText().toStdString())
425 if (current_fixed !=
ui_.fixedframe->currentText().toStdString())
481 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred));
482 setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred));
484 this->setMinimumSize(QSize(100, 100));
485 this->setMaximumSize(QSize(10000, 10000));
489 canvas_->setMinimumSize(1280, 720);
490 canvas_->setMaximumSize(1280, 720);
491 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
493 this->setMaximumSize(this->sizeHint());
494 this->setMinimumSize(this->sizeHint());
495 setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
499 canvas_->setMinimumSize(640, 480);
500 canvas_->setMaximumSize(640, 480);
501 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
503 this->setMaximumSize(this->sizeHint());
504 this->setMinimumSize(this->sizeHint());
505 setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
511 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
513 this->setMaximumSize(this->sizeHint());
514 this->setMinimumSize(this->sizeHint());
515 setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
519 canvas_->setMinimumSize(100, 100);
520 canvas_->setMaximumSize(10000, 10000);
526 ROS_INFO(
"Loading configuration from: %s", filename.c_str());
530 size_t last_slash = filename.find_last_of(
'/');
531 if (last_slash != std::string::npos && last_slash != filename.size() - 1)
533 title = filename.substr(last_slash + 1) +
" (" +
534 filename.substr(0, last_slash + 1) +
")";
541 title +=
" - mapviz";
542 setWindowTitle(QString::fromStdString(title));
547 ROS_ERROR(
"Failed to load file: %s", filename.c_str());
551 std::vector<std::string> failed_plugins;
555 boost::filesystem::path filepath(filename);
556 std::string config_path = filepath.parent_path().string();
567 std::string fixed_frame;
568 doc[
"fixed_frame"] >> fixed_frame;
569 ui_.fixedframe->setEditText(fixed_frame.c_str());
574 std::string target_frame;
575 doc[
"target_frame"] >> target_frame;
576 ui_.targetframe->setEditText(target_frame.c_str());
581 bool fix_orientation =
false;
582 doc[
"fix_orientation"] >> fix_orientation;
583 ui_.actionFix_Orientation->setChecked(fix_orientation);
588 bool rotate_90 =
false;
589 doc[
"rotate_90"] >> rotate_90;
590 ui_.actionRotate_90->setChecked(rotate_90);
595 bool enable_antialiasing =
true;
596 doc[
"enable_antialiasing"] >> enable_antialiasing;
597 ui_.actionEnable_Antialiasing->setChecked(enable_antialiasing);
602 bool show_displays =
false;
603 doc[
"show_displays"] >> show_displays;
604 ui_.actionConfig_Dock->setChecked(show_displays);
609 bool show_capture_tools =
false;
610 doc[
"show_capture_tools"] >> show_capture_tools;
611 ui_.actionShow_Capture_Tools->setChecked(show_capture_tools);
616 bool show_status_bar =
false;
617 doc[
"show_status_bar"] >> show_status_bar;
618 ui_.actionShow_Status_Bar->setChecked(show_status_bar);
623 bool show_capture_tools =
false;
624 doc[
"show_capture_tools"] >> show_capture_tools;
625 ui_.actionShow_Capture_Tools->setChecked(show_capture_tools);
630 int window_width = 0;
631 doc[
"window_width"] >> window_width;
632 resize(window_width, height());
637 int window_height = 0;
638 doc[
"window_height"] >> window_height;
639 resize(width(), window_height);
645 doc[
"view_scale"] >> scale;
652 doc[
"offset_x"] >> x;
659 doc[
"offset_y"] >> y;
666 doc[
"force_720p"] >> force_720p;
670 ui_.actionForce_720p->setChecked(
true);
677 doc[
"force_480p"] >> force_480p;
681 ui_.actionForce_480p->setChecked(
true);
696 doc[
"background"] >> color;
704 const YAML::Node& displays = doc[
"displays"];
705 for (uint32_t i = 0; i < displays.size(); i++)
707 std::string type,
name;
708 displays[i][
"type"] >> type;
709 displays[i][
"name"] >>
name;
711 const YAML::Node&
config = displays[i][
"config"];
713 bool visible =
false;
714 config[
"visible"] >> visible;
716 bool collapsed =
false;
717 config[
"collapsed"] >> collapsed;
723 plugin->LoadConfig(
config, config_path);
728 failed_plugins.push_back(type);
734 catch (
const YAML::ParserException& e)
739 catch (
const YAML::Exception& e)
745 if (!failed_plugins.empty())
747 std::stringstream message;
748 message <<
"The following plugin(s) failed to load:" << std::endl;
749 std::string failures = boost::algorithm::join(failed_plugins,
"\n");
750 message << failures << std::endl << std::endl <<
"Check the ROS log for more details.";
752 QMessageBox::warning(
this,
"Failed to load plugins", QString::fromStdString(message.str()));
758 std::ofstream fout(filename.c_str());
761 ROS_ERROR(
"Failed to open file: %s", filename.c_str());
765 boost::filesystem::path filepath(filename);
766 std::string config_path = filepath.parent_path().string();
770 out << YAML::BeginMap;
772 out << YAML::Key <<
"fixed_frame" << YAML::Value <<
ui_.fixedframe->currentText().toStdString();
773 out << YAML::Key <<
"target_frame" << YAML::Value <<
ui_.targetframe->currentText().toStdString();
774 out << YAML::Key <<
"fix_orientation" << YAML::Value <<
ui_.actionFix_Orientation->isChecked();
775 out << YAML::Key <<
"rotate_90" << YAML::Value <<
ui_.actionRotate_90->isChecked();
776 out << YAML::Key <<
"enable_antialiasing" << YAML::Value <<
ui_.actionEnable_Antialiasing->isChecked();
777 out << YAML::Key <<
"show_displays" << YAML::Value <<
ui_.actionConfig_Dock->isChecked();
778 out << YAML::Key <<
"show_status_bar" << YAML::Value <<
ui_.actionShow_Status_Bar->isChecked();
779 out << YAML::Key <<
"show_capture_tools" << YAML::Value <<
ui_.actionShow_Capture_Tools->isChecked();
780 out << YAML::Key <<
"window_width" << YAML::Value << width();
781 out << YAML::Key <<
"window_height" << YAML::Value << height();
783 out << YAML::Key <<
"offset_x" << YAML::Value <<
canvas_->
OffsetX();
784 out << YAML::Key <<
"offset_y" << YAML::Value <<
canvas_->
OffsetY();
785 out << YAML::Key <<
"background" << YAML::Value <<
background_.name().toStdString();
794 out << YAML::Key <<
"force_720p" << YAML::Value <<
force_720p_;
799 out << YAML::Key <<
"force_480p" << YAML::Value <<
force_480p_;
802 if (
ui_.configs->count() > 0)
804 out << YAML::Key <<
"displays"<< YAML::Value << YAML::BeginSeq;
806 for (
int i = 0; i <
ui_.configs->count(); i++)
808 out << YAML::BeginMap;
809 out << YAML::Key <<
"type" << YAML::Value <<
plugins_[
ui_.configs->item(i)]->Type();
810 out << YAML::Key <<
"name" << YAML::Value << (static_cast<ConfigItem*>(
ui_.configs->itemWidget(
ui_.configs->item(i))))->Name().toStdString();
811 out << YAML::Key <<
"config" << YAML::Value;
812 out << YAML::BeginMap;
814 out << YAML::Key <<
"visible" << YAML::Value <<
plugins_[
ui_.configs->item(i)]->Visible();
815 out << YAML::Key <<
"collapsed" << YAML::Value << (static_cast<ConfigItem*>(
ui_.configs->itemWidget(
ui_.configs->item(i))))->Collapsed();
817 plugins_[
ui_.configs->item(i)]->SaveConfig(out, config_path);
834 QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
835 QString default_path = QDir::homePath();
844 QFileInfo file_info(ws_file);
845 QFileInfo dir_info(ws_path);
846 if ((!file_info.exists() && dir_info.isWritable()) ||
847 file_info.isWritable())
852 default_path = ws_path;
856 ROS_WARN(
"Could not write config file to %s. Trying home directory.",
863 Save(default_path.toStdString());
868 QFileDialog dialog(
this,
"Select Config File");
869 dialog.setFileMode(QFileDialog::ExistingFile);
870 dialog.setNameFilter(tr(
"Mapviz Config Files (*.mvc)"));
872 dialog.setDirectory(QString(directory.c_str()));
876 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
878 std::string path = dialog.selectedFiles().first().toStdString();
901 QFileDialog dialog(
this,
"Save Config File");
902 dialog.setFileMode(QFileDialog::AnyFile);
903 dialog.setAcceptMode(QFileDialog::AcceptSave);
904 dialog.setNameFilter(tr(
"Mapviz Config Files (*.mvc)"));
905 dialog.setDefaultSuffix(
"mvc");
907 dialog.setDirectory(QString(directory.c_str()));
910 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
912 std::string path = dialog.selectedFiles().first().toStdString();
915 size_t last_slash = path.find_last_of(
'/');
916 if (last_slash != std::string::npos && last_slash != path.size() - 1)
918 title = path.substr(last_slash + 1) +
" (" +
919 path.substr(0, last_slash + 1) +
")";
925 title +=
" - mapviz";
926 setWindowTitle(QString::fromStdString(title));
937 plugin.second->ClearHistory();
948 std::vector<std::string> plugins =
loader_->getDeclaredClasses();
949 std::map<std::string, std::string> plugin_types;
950 for (
size_t i = 0; i < plugins.size(); i++)
952 QString type(plugins[i].c_str());
953 type = type.split(
'/').last();
954 ui.displaylist->addItem(type);
955 plugin_types[type.toStdString()] = plugins[i];
957 ui.displaylist->setCurrentRow(0);
961 if (dialog.result() == QDialog::Accepted)
963 std::string type_name = ui.displaylist->selectedItems().first()->text().toStdString();
964 std::string type = plugin_types[type_name];
965 std::string
name =
"new display";
972 std::stringstream message;
973 message <<
"Unable to load " << type <<
"." << std::endl <<
"Check the ROS log for more details.";
974 QMessageBox::warning(
this,
"Plugin failed to load", QString::fromStdString(message.str()));
981 AddMapvizDisplay::Request& req,
982 AddMapvizDisplay::Response& resp)
984 std::map<std::string, std::string> properties;
985 for (
auto& property: req.properties)
987 properties[
property.key] =
property.value;
993 ROS_ERROR(
"Failed to parse properties into YAML.");
1005 if (plugin->Name() == req.name && plugin->Type() ==req.type)
1007 plugin->LoadConfig(
config,
"");
1008 plugin->SetVisible(req.visible);
1010 if (req.draw_order > 0)
1012 display.first->setData(Qt::UserRole, QVariant(req.draw_order - 1.1));
1013 ui_.configs->sortItems();
1017 else if (req.draw_order < 0)
1019 display.first->setData(Qt::UserRole, QVariant(
ui_.configs->count() + req.draw_order + 0.1));
1020 ui_.configs->sortItems();
1025 resp.success =
true;
1035 plugin->LoadConfig(
config,
"");
1037 resp.success =
true;
1042 resp.success =
false;
1043 resp.message =
"Failed to load display plug-in.";
1051 if (
ui_.statusbar->isVisible())
1060 int32_t precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / scale))));
1062 QString text =
ui_.fixedframe->currentText();
1063 if (text.isEmpty() || text ==
"/")
1069 std::ostringstream x_ss;
1070 x_ss << std::fixed << std::setprecision(precision);
1072 text += x_ss.str().c_str();
1076 std::ostringstream y_ss;
1077 y_ss << std::fixed << std::setprecision(precision);
1079 text += y_ss.str().c_str();
1088 ui_.fixedframe->currentText().toStdString()) &&
1091 ui_.fixedframe->currentText().toStdString(),
1094 tf::Vector3 point(x, y, 0);
1095 point = transform * point;
1097 QString lat_lon_text =
"lat/lon: ";
1099 double lat_scale = (1.0 / 111111.0) * scale;
1100 int32_t lat_precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / lat_scale))));
1102 std::ostringstream lat_ss;
1103 lat_ss << std::fixed << std::setprecision(lat_precision);
1104 lat_ss << point.y();
1105 lat_lon_text += lat_ss.str().c_str();
1107 lat_lon_text +=
", ";
1110 int32_t lon_precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / lon_scale))));
1112 std::ostringstream lon_ss;
1113 lon_ss << std::fixed << std::setprecision(lon_precision);
1114 lon_ss << point.x();
1115 lat_lon_text += lon_ss.str().c_str();
1129 const std::string& name,
1130 const std::string& type,
1139 std::string real_type = type;
1140 if (real_type ==
"mapviz_plugins/mutlires_image")
1145 real_type =
"mapviz_plugins/multires_image";
1149 ROS_INFO(
"creating: %s", real_type.c_str());
1153 config_item->
SetWidget(plugin->GetConfigWidget(
this));
1154 plugin->SetIcon(config_item->
ui_.icon);
1156 plugin->SetType(real_type.c_str());
1157 plugin->SetName(
name);
1158 plugin->SetNode(*
node_);
1159 plugin->SetVisible(visible);
1161 if (draw_order == 0)
1163 plugin->SetDrawOrder(
ui_.configs->count());
1165 else if (draw_order > 0)
1167 plugin->SetDrawOrder(std::min(
ui_.configs->count(), draw_order - 1));
1169 else if (draw_order < 0)
1171 plugin->SetDrawOrder(std::max(0,
ui_.configs->count() + draw_order + 1));
1174 QString pretty_type(real_type.c_str());
1175 pretty_type = pretty_type.split(
'/').last();
1176 config_item->
SetType(pretty_type);
1179 item->setSizeHint(config_item->sizeHint());
1180 connect(config_item, SIGNAL(UpdateSizeHint()),
this, SLOT(
UpdateSizeHints()));
1181 connect(config_item, SIGNAL(ToggledDraw(QListWidgetItem*,
bool)),
this, SLOT(
ToggleShowPlugin(QListWidgetItem*,
bool)));
1182 connect(config_item, SIGNAL(RemoveRequest(QListWidgetItem*)),
this, SLOT(
RemoveDisplay(QListWidgetItem*)));
1183 connect(plugin.get(), SIGNAL(VisibleChanged(
bool)), config_item, SLOT(ToggleDraw(
bool)));
1184 connect(plugin.get(), SIGNAL(SizeChanged()),
this, SLOT(
UpdateSizeHints()));
1186 if (real_type ==
"mapviz_plugins/image")
1193 plugin.get(), SLOT(Resubscribe()));
1196 if (draw_order == 0)
1198 ui_.configs->addItem(item);
1202 ui_.configs->insertItem(plugin->DrawOrder(), item);
1205 ui_.configs->setItemWidget(item, config_item);
1206 ui_.configs->UpdateIndices();
1209 plugin->SetTargetFrame(
ui_.fixedframe->currentText().toStdString());
1216 config_item->
Hide();
1229 plugins_[item]->SetVisible(visible);
1238 ROS_INFO(
"Fixed frame selected: %s", text.toStdString().c_str());
1250 ROS_INFO(
"Target frame selected: %s", text.toStdString().c_str());
1278 ui_.configdock->show();
1282 ui_.configdock->hide();
1290 ui_.statusbar->setVisible(on);
1299 ui_.actionShow_Status_Bar->setChecked(
true);
1316 rec_button_->setIcon(QIcon(
":/images/media-playback-pause.png"));
1317 rec_button_->setToolTip(
"Pause recording video of display canvas");
1325 std::string posix_time = boost::posix_time::to_iso_string(
ros::WallTime::now().toBoost());
1326 boost::replace_all(posix_time,
".",
"_");
1328 boost::replace_all(filename,
"~", getenv(
"HOME"));
1333 ROS_ERROR(
"Failed to open video file for writing.");
1338 ROS_INFO(
"Writing video to: %s", filename.c_str());
1339 ui_.statusbar->showMessage(
"Recording video to " + QString::fromStdString(filename));
1348 rec_button_->setIcon(QIcon(
":/images/media-record.png"));
1349 rec_button_->setToolTip(
"Continue recording video of display canvas");
1356 std::string transport = transport_action->text().toStdString();
1367 std::string current_transport;
1369 Q_FOREACH(QAction* action, actions)
1371 if (action->text() == QString::fromStdString(current_transport))
1373 action->setChecked(
true);
1378 ROS_WARN(
"%s param was set to an unrecognized value: %s",
1390 QImage frame(
canvas_->width(),
canvas_->height(), QImage::Format_ARGB32);
1397 ROS_ERROR(
"Failed to get capture buffer");
1418 ui_.statusbar->showMessage(QString(
""));
1419 rec_button_->setToolTip(
"Start recording video of display canvas");
1428 std::vector<uint8_t> frame;
1431 cv::Mat image(
canvas_->height(),
canvas_->width(), CV_8UC4, &frame[0]);
1433 cvtColor(image, screenshot, cv::COLOR_BGRA2BGR);
1435 cv::flip(screenshot, screenshot, 0);
1437 std::string posix_time = boost::posix_time::to_iso_string(
ros::WallTime::now().toBoost());
1438 boost::replace_all(posix_time,
".",
"_");
1440 boost::replace_all(filename,
"~", getenv(
"HOME"));
1442 ROS_INFO(
"Writing screenshot to: %s", filename.c_str());
1443 ui_.statusbar->showMessage(
"Saved image to " + QString::fromStdString(filename));
1445 cv::imwrite(filename, screenshot);
1449 ROS_ERROR(
"Failed to take screenshot.");
1455 for (
int i = 0; i <
ui_.configs->count(); i++)
1457 QListWidgetItem* item =
ui_.configs->item(i);
1463 item->setSizeHint(widget->sizeHint());
1470 QListWidgetItem* item =
ui_.configs->takeItem(
ui_.configs->currentRow());
1489 while (
ui_.configs->count() > 0)
1493 QListWidgetItem* item =
ui_.configs->takeItem(0);
1505 for (
int i = 0; i <
ui_.configs->count(); i++)
1520 QFileDialog dialog(
this,
"Select Capture Directory");
1521 dialog.setFileMode(QFileDialog::DirectoryOnly);
1525 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
1540 plugin->PrintMeasurements();