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>();
265 tf_manager_->Initialize(
tf_);
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);
693 bool use_latest_transforms =
true;
696 doc[
"use_latest_transforms"] >> use_latest_transforms;
698 ui_.uselatesttransforms->setChecked(use_latest_transforms);
704 doc[
"background"] >> color;
712 const YAML::Node& displays = doc[
"displays"];
713 for (uint32_t i = 0; i < displays.size(); i++)
715 std::string type,
name;
716 displays[i][
"type"] >> type;
717 displays[i][
"name"] >> name;
719 const YAML::Node&
config = displays[i][
"config"];
721 bool visible =
false;
722 config[
"visible"] >> visible;
724 bool collapsed =
false;
725 config[
"collapsed"] >> collapsed;
731 plugin->LoadConfig(config, config_path);
736 failed_plugins.push_back(type);
742 catch (
const YAML::ParserException& e)
747 catch (
const YAML::Exception& e)
753 if (!failed_plugins.empty())
755 std::stringstream message;
756 message <<
"The following plugin(s) failed to load:" << std::endl;
757 std::string failures = boost::algorithm::join(failed_plugins,
"\n");
758 message << failures << std::endl << std::endl <<
"Check the ROS log for more details.";
760 QMessageBox::warning(
this,
"Failed to load plugins", QString::fromStdString(message.str()));
766 std::ofstream fout(filename.c_str());
769 ROS_ERROR(
"Failed to open file: %s", filename.c_str());
773 boost::filesystem::path filepath(filename);
774 std::string config_path = filepath.parent_path().string();
778 out << YAML::BeginMap;
780 out << YAML::Key <<
"fixed_frame" << YAML::Value <<
ui_.fixedframe->currentText().toStdString();
781 out << YAML::Key <<
"target_frame" << YAML::Value <<
ui_.targetframe->currentText().toStdString();
782 out << YAML::Key <<
"fix_orientation" << YAML::Value <<
ui_.actionFix_Orientation->isChecked();
783 out << YAML::Key <<
"rotate_90" << YAML::Value <<
ui_.actionRotate_90->isChecked();
784 out << YAML::Key <<
"enable_antialiasing" << YAML::Value <<
ui_.actionEnable_Antialiasing->isChecked();
785 out << YAML::Key <<
"show_displays" << YAML::Value <<
ui_.actionConfig_Dock->isChecked();
786 out << YAML::Key <<
"show_status_bar" << YAML::Value <<
ui_.actionShow_Status_Bar->isChecked();
787 out << YAML::Key <<
"show_capture_tools" << YAML::Value <<
ui_.actionShow_Capture_Tools->isChecked();
788 out << YAML::Key <<
"window_width" << YAML::Value << width();
789 out << YAML::Key <<
"window_height" << YAML::Value << height();
791 out << YAML::Key <<
"offset_x" << YAML::Value <<
canvas_->
OffsetX();
792 out << YAML::Key <<
"offset_y" << YAML::Value <<
canvas_->
OffsetY();
793 out << YAML::Key <<
"use_latest_transforms" << YAML::Value <<
ui_.uselatesttransforms->isChecked();
794 out << YAML::Key <<
"background" << YAML::Value <<
background_.name().toStdString();
803 out << YAML::Key <<
"force_720p" << YAML::Value <<
force_720p_;
808 out << YAML::Key <<
"force_480p" << YAML::Value <<
force_480p_;
811 if (
ui_.configs->count() > 0)
813 out << YAML::Key <<
"displays"<< YAML::Value << YAML::BeginSeq;
815 for (
int i = 0; i <
ui_.configs->count(); i++)
817 out << YAML::BeginMap;
818 out << YAML::Key <<
"type" << YAML::Value <<
plugins_[
ui_.configs->item(i)]->Type();
819 out << YAML::Key <<
"name" << YAML::Value << (static_cast<ConfigItem*>(
ui_.configs->itemWidget(
ui_.configs->item(i))))->Name().toStdString();
820 out << YAML::Key <<
"config" << YAML::Value;
821 out << YAML::BeginMap;
823 out << YAML::Key <<
"visible" << YAML::Value <<
plugins_[
ui_.configs->item(i)]->Visible();
824 out << YAML::Key <<
"collapsed" << YAML::Value << (static_cast<ConfigItem*>(
ui_.configs->itemWidget(
ui_.configs->item(i))))->Collapsed();
826 plugins_[
ui_.configs->item(i)]->SaveConfig(out, config_path);
843 QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
844 QString default_path = QDir::homePath();
853 QFileInfo file_info(ws_file);
854 QFileInfo dir_info(ws_path);
855 if ((!file_info.exists() && dir_info.isWritable()) ||
856 file_info.isWritable())
861 default_path = ws_path;
865 ROS_WARN(
"Could not write config file to %s. Trying home directory.",
866 (ws_path + MAPVIZ_CONFIG_FILE).toStdString().c_str());
872 Save(default_path.toStdString());
877 QFileDialog dialog(
this,
"Select Config File");
878 dialog.setFileMode(QFileDialog::ExistingFile);
879 dialog.setNameFilter(tr(
"Mapviz Config Files (*.mvc)"));
881 dialog.setDirectory(QString(directory.c_str()));
885 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
887 std::string path = dialog.selectedFiles().first().toStdString();
910 QFileDialog dialog(
this,
"Save Config File");
911 dialog.setFileMode(QFileDialog::AnyFile);
912 dialog.setAcceptMode(QFileDialog::AcceptSave);
913 dialog.setNameFilter(tr(
"Mapviz Config Files (*.mvc)"));
914 dialog.setDefaultSuffix(
"mvc");
916 dialog.setDirectory(QString(directory.c_str()));
919 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
921 std::string path = dialog.selectedFiles().first().toStdString();
924 size_t last_slash = path.find_last_of(
'/');
925 if (last_slash != std::string::npos && last_slash != path.size() - 1)
927 title = path.substr(last_slash + 1) +
" (" +
928 path.substr(0, last_slash + 1) +
")";
934 title +=
" - mapviz";
935 setWindowTitle(QString::fromStdString(title));
946 plugin.second->ClearHistory();
957 std::vector<std::string> plugins =
loader_->getDeclaredClasses();
958 std::map<std::string, std::string> plugin_types;
959 for (
size_t i = 0; i < plugins.size(); i++)
961 QString type(plugins[i].c_str());
962 type = type.split(
'/').last();
963 ui.displaylist->addItem(type);
964 plugin_types[type.toStdString()] = plugins[i];
966 ui.displaylist->setCurrentRow(0);
970 if (dialog.result() == QDialog::Accepted)
972 std::string type_name = ui.displaylist->selectedItems().first()->text().toStdString();
973 std::string type = plugin_types[type_name];
974 std::string
name =
"new display";
981 std::stringstream message;
982 message <<
"Unable to load " << type <<
"." << std::endl <<
"Check the ROS log for more details.";
983 QMessageBox::warning(
this,
"Plugin failed to load", QString::fromStdString(message.str()));
990 AddMapvizDisplay::Request& req,
991 AddMapvizDisplay::Response& resp)
993 std::map<std::string, std::string> properties;
994 for (
auto& property: req.properties)
996 properties[
property.key] =
property.value;
1002 ROS_ERROR(
"Failed to parse properties into YAML.");
1014 if (plugin->Name() == req.name && plugin->Type() ==req.type)
1016 plugin->LoadConfig(config,
"");
1017 plugin->SetVisible(req.visible);
1019 if (req.draw_order > 0)
1021 display.first->setData(Qt::UserRole, QVariant(req.draw_order - 1.1));
1022 ui_.configs->sortItems();
1026 else if (req.draw_order < 0)
1028 display.first->setData(Qt::UserRole, QVariant(
ui_.configs->count() + req.draw_order + 0.1));
1029 ui_.configs->sortItems();
1034 resp.success =
true;
1044 plugin->LoadConfig(config,
"");
1046 resp.success =
true;
1051 resp.success =
false;
1052 resp.message =
"Failed to load display plug-in.";
1060 if (
ui_.statusbar->isVisible())
1069 int32_t precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / scale))));
1071 QString text =
ui_.fixedframe->currentText();
1072 if (text.isEmpty() || text ==
"/")
1078 std::ostringstream x_ss;
1079 x_ss << std::fixed << std::setprecision(precision);
1081 text += x_ss.str().c_str();
1085 std::ostringstream y_ss;
1086 y_ss << std::fixed << std::setprecision(precision);
1088 text += y_ss.str().c_str();
1097 ui_.fixedframe->currentText().toStdString()) &&
1100 ui_.fixedframe->currentText().toStdString(),
1104 point = transform * point;
1106 QString lat_lon_text =
"lat/lon: ";
1108 double lat_scale = (1.0 / 111111.0) * scale;
1109 int32_t lat_precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / lat_scale))));
1111 std::ostringstream lat_ss;
1112 lat_ss << std::fixed << std::setprecision(lat_precision);
1113 lat_ss << point.y();
1114 lat_lon_text += lat_ss.str().c_str();
1116 lat_lon_text +=
", ";
1119 int32_t lon_precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / lon_scale))));
1121 std::ostringstream lon_ss;
1122 lon_ss << std::fixed << std::setprecision(lon_precision);
1123 lon_ss << point.x();
1124 lat_lon_text += lon_ss.str().c_str();
1138 const std::string& name,
1139 const std::string& type,
1146 config_item->
SetName(name.c_str());
1148 std::string real_type = type;
1149 if (real_type ==
"mapviz_plugins/mutlires_image")
1154 real_type =
"mapviz_plugins/multires_image";
1158 ROS_INFO(
"creating: %s", real_type.c_str());
1162 config_item->
SetWidget(plugin->GetConfigWidget(
this));
1163 plugin->SetIcon(config_item->
ui_.icon);
1165 plugin->SetType(real_type.c_str());
1166 plugin->SetName(name);
1167 plugin->SetNode(*
node_);
1168 plugin->SetVisible(visible);
1170 if (draw_order == 0)
1172 plugin->SetDrawOrder(
ui_.configs->count());
1174 else if (draw_order > 0)
1176 plugin->SetDrawOrder(std::min(
ui_.configs->count(), draw_order - 1));
1178 else if (draw_order < 0)
1180 plugin->SetDrawOrder(std::max(0,
ui_.configs->count() + draw_order + 1));
1183 QString pretty_type(real_type.c_str());
1184 pretty_type = pretty_type.split(
'/').last();
1185 config_item->
SetType(pretty_type);
1188 item->setSizeHint(config_item->sizeHint());
1189 connect(config_item, SIGNAL(UpdateSizeHint()),
this, SLOT(
UpdateSizeHints()));
1190 connect(config_item, SIGNAL(ToggledDraw(QListWidgetItem*,
bool)),
this, SLOT(
ToggleShowPlugin(QListWidgetItem*,
bool)));
1191 connect(config_item, SIGNAL(RemoveRequest(QListWidgetItem*)),
this, SLOT(
RemoveDisplay(QListWidgetItem*)));
1192 connect(plugin.get(), SIGNAL(VisibleChanged(
bool)), config_item, SLOT(ToggleDraw(
bool)));
1193 connect(plugin.get(), SIGNAL(SizeChanged()),
this, SLOT(
UpdateSizeHints()));
1195 if (real_type ==
"mapviz_plugins/image")
1202 plugin.get(), SLOT(Resubscribe()));
1205 if (draw_order == 0)
1207 ui_.configs->addItem(item);
1211 ui_.configs->insertItem(plugin->DrawOrder(), item);
1214 ui_.configs->setItemWidget(item, config_item);
1215 ui_.configs->UpdateIndices();
1218 plugin->SetTargetFrame(
ui_.fixedframe->currentText().toStdString());
1219 plugin->SetUseLatestTransforms(
ui_.uselatesttransforms->isChecked());
1226 config_item->
Hide();
1239 plugins_[item]->SetVisible(visible);
1248 ROS_INFO(
"Fixed frame selected: %s", text.toStdString().c_str());
1260 ROS_INFO(
"Target frame selected: %s", text.toStdString().c_str());
1293 ui_.configdock->show();
1297 ui_.configdock->hide();
1305 ui_.statusbar->setVisible(on);
1314 ui_.actionShow_Status_Bar->setChecked(
true);
1331 rec_button_->setIcon(QIcon(
":/images/media-playback-pause.png"));
1332 rec_button_->setToolTip(
"Pause recording video of display canvas");
1340 std::string posix_time = boost::posix_time::to_iso_string(
ros::WallTime::now().toBoost());
1341 boost::replace_all(posix_time,
".",
"_");
1343 boost::replace_all(filename,
"~", getenv(
"HOME"));
1348 ROS_ERROR(
"Failed to open video file for writing.");
1353 ROS_INFO(
"Writing video to: %s", filename.c_str());
1354 ui_.statusbar->showMessage(
"Recording video to " + QString::fromStdString(filename));
1363 rec_button_->setIcon(QIcon(
":/images/media-record.png"));
1364 rec_button_->setToolTip(
"Continue recording video of display canvas");
1371 std::string transport = transport_action->text().toStdString();
1382 std::string current_transport;
1384 Q_FOREACH(QAction*
action, actions)
1386 if (action->text() == QString::fromStdString(current_transport))
1388 action->setChecked(
true);
1393 ROS_WARN(
"%s param was set to an unrecognized value: %s",
1394 IMAGE_TRANSPORT_PARAM.c_str(), current_transport.c_str());
1405 QImage frame(
canvas_->width(),
canvas_->height(), QImage::Format_ARGB32);
1412 ROS_ERROR(
"Failed to get capture buffer");
1433 ui_.statusbar->showMessage(QString(
""));
1434 rec_button_->setToolTip(
"Start recording video of display canvas");
1443 std::vector<uint8_t> frame;
1446 cv::Mat image(
canvas_->height(),
canvas_->width(), CV_8UC4, &frame[0]);
1448 cvtColor(image, screenshot, cv::COLOR_BGRA2BGR);
1450 cv::flip(screenshot, screenshot, 0);
1452 std::string posix_time = boost::posix_time::to_iso_string(
ros::WallTime::now().toBoost());
1453 boost::replace_all(posix_time,
".",
"_");
1455 boost::replace_all(filename,
"~", getenv(
"HOME"));
1457 ROS_INFO(
"Writing screenshot to: %s", filename.c_str());
1458 ui_.statusbar->showMessage(
"Saved image to " + QString::fromStdString(filename));
1460 cv::imwrite(filename, screenshot);
1464 ROS_ERROR(
"Failed to take screenshot.");
1470 for (
int i = 0; i <
ui_.configs->count(); i++)
1472 QListWidgetItem* item =
ui_.configs->item(i);
1478 item->setSizeHint(widget->sizeHint());
1485 QListWidgetItem* item =
ui_.configs->takeItem(
ui_.configs->currentRow());
1504 while (
ui_.configs->count() > 0)
1508 QListWidgetItem* item =
ui_.configs->takeItem(0);
1520 for (
int i = 0; i <
ui_.configs->count(); i++)
1535 QFileDialog dialog(
this,
"Select Capture Directory");
1536 dialog.setFileMode(QFileDialog::DirectoryOnly);
1540 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
1555 plugin->PrintMeasurements();
void SetWidget(QWidget *widget)
VideoWriter * vid_writer_
std::vector< std::string > getLoadableTransports() const
void ToggleShowPlugin(QListWidgetItem *item, bool visible)
void CaptureFrames(bool enabled)
void FixedFrameSelected(const QString &text)
static const long double _deg_2_rad
void FrameGrabbed(QImage)
bool LoadFile(const std::string &path, YAML::Node &yaml)
void HandleProfileTimer()
void RemovePlugin(MapvizPluginPtr plugin)
QPushButton * stop_button_
void printInfo(const std::string &name) const
void ToggleUseLatestTransforms(bool on)
bool LoadMap(const std::map< std::string, std::string > &dict, YAML::Node &yaml)
void CaptureFrame(bool force=false)
bool initializeWriter(const std::string &directory, int width, int height)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void InitializeTf(boost::shared_ptr< tf::TransformListener > tf)
void ToggleEnableAntialiasing(bool on)
void SetFixedFrame(const std::string &frame)
QPushButton * recenter_button_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void ToggleRecord(bool on)
void ToggleCaptureTools(bool on)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void SetBackground(const QColor &color)
void UpdateImageTransportMenu()
virtual void closeEvent(QCloseEvent *event)
pluginlib::ClassLoader< MapvizPlugin > * loader_
void ToggleEnableAntialiasing(bool on)
MapvizPluginPtr CreateNewDisplay(const std::string &name, const std::string &type, bool visible, bool collapsed, int draw_order=0)
void ToggleDraw(bool toggled)
virtual void showEvent(QShowEvent *event)
std::map< QListWidgetItem *, MapvizPluginPtr > plugins_
void ToggleRotate90(bool on)
swri_transform_util::TransformManagerPtr tf_manager_
ros::ServiceServer add_display_srv_
void ImageTransportChanged()
void SetResizable(bool on)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
bool FindValue(const YAML::Node &node, const std::string &name)
void Save(const std::string &filename)
void ToggleConfigPanel(bool on)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void SetName(QString name)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void ToggleRotate90(bool on)
static const std::string IMAGE_TRANSPORT_PARAM
boost::shared_ptr< tf::TransformListener > tf_
void TargetFrameSelected(const QString &text)
std::string capture_directory_
void ToggleFixOrientation(bool on)
Mapviz(bool is_standalone, int argc, char **argv, QWidget *parent=0, Qt::WindowFlags flags=0)
QLabel * lat_lon_pos_label_
void SetListItem(QListWidgetItem *item)
void SelectBackgroundColor(const QColor &color)
void Open(const std::string &filename)
static const QString MAPVIZ_CONFIG_FILE
static const QString ROS_WORKSPACE_VAR
QPushButton * rec_button_
bool CopyCaptureBuffer(uchar *buffer)
bool AddDisplay(AddMapvizDisplay::Request &req, AddMapvizDisplay::Response &resp)
void ToggleUseLatestTransforms(bool on)
void SetType(QString type)
void SetTargetFrame(const std::string &frame)
bool getParam(const std::string &key, std::string &s) const
void SetCaptureDirectory()
void Hover(double x, double y, double scale)
void ToggleFixOrientation(bool on)
void SetImageTransport(QAction *transport_action)
void SetViewScale(float scale)
ROSCPP_DECL void spinOnce()
void AddPlugin(MapvizPluginPtr plugin, int order)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
QPushButton * screenshot_button_
std::string save_location_
void ToggleStatusBar(bool on)
QMenu * image_transport_menu_