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.hpp> 49 #include <opencv2/imgcodecs.hpp> 50 #include <opencv2/imgproc.hpp> 51 #include <opencv2/videoio.hpp> 54 #include <QtWidgets/QApplication> 55 #include <QFileDialog> 56 #include <QActionGroup> 57 #include <QColorDialog> 59 #include <QMessageBox> 60 #include <QProcessEnvironment> 62 #include <QListWidgetItem> 63 #include <QMutexLocker> 70 #include <QtGui/QtGui> 80 Mapviz::Mapviz(
bool is_standalone,
int argc,
char** argv, QWidget *parent, Qt::WindowFlags flags) :
81 QMainWindow(parent, flags),
82 xy_pos_label_(new QLabel(
"fixed: 0.0,0.0")),
83 lat_lon_pos_label_(new QLabel(
"lat/lon: 0.0,0.0")),
86 is_standalone_(is_standalone),
91 background_(Qt::gray),
92 capture_directory_(
"~"),
94 updating_frames_(false),
127 rec_button_->setIcon(QIcon(
":/images/media-record.png"));
130 rec_button_->setToolTip(
"Start recording video of display canvas");
136 stop_button_->setIcon(QIcon(
":/images/media-playback-stop.png"));
137 stop_button_->setToolTip(
"Stop recording video of display canvas");
151 recenter_button_->setToolTip(
"Reset the viewport to the default location and zoom level");
155 ui_.statusbar->setVisible(
true);
157 QActionGroup* group =
new QActionGroup(
this);
159 ui_.actionForce_720p->setActionGroup(group);
160 ui_.actionForce_480p->setActionGroup(group);
161 ui_.actionResizable->setActionGroup(group);
163 ui_.targetframe->addItem(
"<none>");
168 connect(
canvas_, SIGNAL(
Hover(
double,
double,
double)),
this, SLOT(
Hover(
double,
double,
double)));
170 connect(
ui_.actionExit, SIGNAL(triggered()),
this, SLOT(close()));
177 connect(
ui_.actionClear_History, SIGNAL(triggered()),
this, SLOT(
ClearHistory()));
244 for (std::vector<std::string>::iterator iter = transports.begin(); iter != transports.end(); iter++)
246 QString transport = QString::fromStdString(*iter).replace(
249 action->setCheckable(
true);
250 group->addAction(action);
253 connect(group, SIGNAL(triggered(QAction*)),
this, SLOT(
SetImageTransport(QAction*)));
255 tf_ = boost::make_shared<tf::TransformListener>();
259 "mapviz",
"mapviz::MapvizPlugin");
261 std::vector<std::string> plugins =
loader_->getDeclaredClasses();
262 for (
unsigned int i = 0; i < plugins.size(); i++)
264 ROS_INFO(
"Found mapviz plugin: %s", plugins[i].c_str());
275 QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
276 QString default_path = QDir::homePath();
285 default_path = ws_path;
289 ROS_WARN(
"Could not load config file from ROS_WORKSPACE at %s; trying home directory...",
290 ws_path.toStdString().c_str());
297 priv.
param(
"config", config, default_path.toStdString());
300 priv.
param(
"auto_save_backup", auto_save,
true);
316 bool print_profile_data;
317 priv.
param(
"print_profile_data", print_profile_data,
false);
318 if (print_profile_data)
338 QApplication::exit();
344 std::vector<std::string> frames;
345 tf_->getFrameStrings(frames);
346 std::sort(frames.begin(), frames.end());
348 if (
ui_.fixedframe->count() >= 0 &&
349 static_cast<size_t>(
ui_.fixedframe->count()) == frames.size())
351 bool changed =
false;
352 for (
size_t i = 0; i < frames.size(); i++)
354 if (frames[i] !=
ui_.fixedframe->itemText(i).toStdString())
366 std::string current_fixed =
ui_.fixedframe->currentText().toStdString();
368 ui_.fixedframe->clear();
369 for (
size_t i = 0; i < frames.size(); i++)
371 ui_.fixedframe->addItem(frames[i].c_str());
374 if (current_fixed !=
"")
376 int index =
ui_.fixedframe->findText(current_fixed.c_str());
379 ui_.fixedframe->addItem(current_fixed.c_str());
382 index =
ui_.fixedframe->findText(current_fixed.c_str());
383 ui_.fixedframe->setCurrentIndex(index);
386 std::string current_target =
ui_.targetframe->currentText().toStdString();
388 ui_.targetframe->clear();
389 ui_.targetframe->addItem(
"<none>");
390 for (
size_t i = 0; i < frames.size(); i++)
392 ui_.targetframe->addItem(frames[i].c_str());
395 if (current_target !=
"")
397 int index =
ui_.targetframe->findText(current_target.c_str());
400 ui_.targetframe->addItem(current_target.c_str());
403 index =
ui_.targetframe->findText(current_target.c_str());
404 ui_.targetframe->setCurrentIndex(index);
409 if (current_target !=
ui_.targetframe->currentText().toStdString())
414 if (current_fixed !=
ui_.fixedframe->currentText().toStdString())
470 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred));
471 setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred));
473 this->setMinimumSize(QSize(100, 100));
474 this->setMaximumSize(QSize(10000, 10000));
478 canvas_->setMinimumSize(1280, 720);
479 canvas_->setMaximumSize(1280, 720);
480 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
482 this->setMaximumSize(this->sizeHint());
483 this->setMinimumSize(this->sizeHint());
484 setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
488 canvas_->setMinimumSize(640, 480);
489 canvas_->setMaximumSize(640, 480);
490 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
492 this->setMaximumSize(this->sizeHint());
493 this->setMinimumSize(this->sizeHint());
494 setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
500 canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
502 this->setMaximumSize(this->sizeHint());
503 this->setMinimumSize(this->sizeHint());
504 setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
508 canvas_->setMinimumSize(100, 100);
509 canvas_->setMaximumSize(10000, 10000);
515 ROS_INFO(
"Loading configuration from: %s", filename.c_str());
518 size_t last_slash = filename.find_last_of(
'/');
519 if (last_slash != std::string::npos && last_slash != filename.size() - 1)
521 title = filename.substr(last_slash + 1) +
" (" +
522 filename.substr(0, last_slash + 1) +
")";
529 title +=
" - mapviz";
530 setWindowTitle(QString::fromStdString(title));
535 ROS_ERROR(
"Failed to load file: %s", filename.c_str());
539 std::vector<std::string> failed_plugins;
543 boost::filesystem::path filepath(filename);
544 std::string config_path = filepath.parent_path().string();
555 std::string fixed_frame;
556 doc[
"fixed_frame"] >> fixed_frame;
557 ui_.fixedframe->setEditText(fixed_frame.c_str());
562 std::string target_frame;
563 doc[
"target_frame"] >> target_frame;
564 ui_.targetframe->setEditText(target_frame.c_str());
569 bool fix_orientation =
false;
570 doc[
"fix_orientation"] >> fix_orientation;
571 ui_.actionFix_Orientation->setChecked(fix_orientation);
576 bool rotate_90 =
false;
577 doc[
"rotate_90"] >> rotate_90;
578 ui_.actionRotate_90->setChecked(rotate_90);
583 bool enable_antialiasing =
true;
584 doc[
"enable_antialiasing"] >> enable_antialiasing;
585 ui_.actionEnable_Antialiasing->setChecked(enable_antialiasing);
590 bool show_displays =
false;
591 doc[
"show_displays"] >> show_displays;
592 ui_.actionConfig_Dock->setChecked(show_displays);
597 bool show_capture_tools =
false;
598 doc[
"show_capture_tools"] >> show_capture_tools;
599 ui_.actionShow_Capture_Tools->setChecked(show_capture_tools);
604 bool show_status_bar =
false;
605 doc[
"show_status_bar"] >> show_status_bar;
606 ui_.actionShow_Status_Bar->setChecked(show_status_bar);
611 bool show_capture_tools =
false;
612 doc[
"show_capture_tools"] >> show_capture_tools;
613 ui_.actionShow_Capture_Tools->setChecked(show_capture_tools);
618 int window_width = 0;
619 doc[
"window_width"] >> window_width;
620 resize(window_width, height());
625 int window_height = 0;
626 doc[
"window_height"] >> window_height;
627 resize(width(), window_height);
633 doc[
"view_scale"] >> scale;
640 doc[
"offset_x"] >> x;
647 doc[
"offset_y"] >> y;
654 doc[
"force_720p"] >> force_720p;
658 ui_.actionForce_720p->setChecked(
true);
665 doc[
"force_480p"] >> force_480p;
669 ui_.actionForce_480p->setChecked(
true);
681 bool use_latest_transforms =
true;
684 doc[
"use_latest_transforms"] >> use_latest_transforms;
686 ui_.uselatesttransforms->setChecked(use_latest_transforms);
692 doc[
"background"] >> color;
700 const YAML::Node& displays = doc[
"displays"];
701 for (uint32_t i = 0; i < displays.size(); i++)
703 std::string type,
name;
704 displays[i][
"type"] >> type;
705 displays[i][
"name"] >> name;
707 const YAML::Node&
config = displays[i][
"config"];
709 bool visible =
false;
710 config[
"visible"] >> visible;
712 bool collapsed =
false;
713 config[
"collapsed"] >> collapsed;
719 plugin->LoadConfig(config, config_path);
724 failed_plugins.push_back(type);
730 catch (
const YAML::ParserException& e)
735 catch (
const YAML::Exception& e)
741 if (!failed_plugins.empty())
743 std::stringstream message;
744 message <<
"The following plugin(s) failed to load:" << std::endl;
745 std::string failures = boost::algorithm::join(failed_plugins,
"\n");
746 message << failures << std::endl << std::endl <<
"Check the ROS log for more details.";
748 QMessageBox::warning(
this,
"Failed to load plugins", QString::fromStdString(message.str()));
754 std::ofstream fout(filename.c_str());
757 ROS_ERROR(
"Failed to open file: %s", filename.c_str());
761 boost::filesystem::path filepath(filename);
762 std::string config_path = filepath.parent_path().string();
766 out << YAML::BeginMap;
768 out << YAML::Key <<
"fixed_frame" << YAML::Value <<
ui_.fixedframe->currentText().toStdString();
769 out << YAML::Key <<
"target_frame" << YAML::Value <<
ui_.targetframe->currentText().toStdString();
770 out << YAML::Key <<
"fix_orientation" << YAML::Value <<
ui_.actionFix_Orientation->isChecked();
771 out << YAML::Key <<
"rotate_90" << YAML::Value <<
ui_.actionRotate_90->isChecked();
772 out << YAML::Key <<
"enable_antialiasing" << YAML::Value <<
ui_.actionEnable_Antialiasing->isChecked();
773 out << YAML::Key <<
"show_displays" << YAML::Value <<
ui_.actionConfig_Dock->isChecked();
774 out << YAML::Key <<
"show_status_bar" << YAML::Value <<
ui_.actionShow_Status_Bar->isChecked();
775 out << YAML::Key <<
"show_capture_tools" << YAML::Value <<
ui_.actionShow_Capture_Tools->isChecked();
776 out << YAML::Key <<
"window_width" << YAML::Value << width();
777 out << YAML::Key <<
"window_height" << YAML::Value << height();
779 out << YAML::Key <<
"offset_x" << YAML::Value <<
canvas_->
OffsetX();
780 out << YAML::Key <<
"offset_y" << YAML::Value <<
canvas_->
OffsetY();
781 out << YAML::Key <<
"use_latest_transforms" << YAML::Value <<
ui_.uselatesttransforms->isChecked();
782 out << YAML::Key <<
"background" << YAML::Value <<
background_.name().toStdString();
791 out << YAML::Key <<
"force_720p" << YAML::Value <<
force_720p_;
796 out << YAML::Key <<
"force_480p" << YAML::Value <<
force_480p_;
799 if (
ui_.configs->count() > 0)
801 out << YAML::Key <<
"displays"<< YAML::Value << YAML::BeginSeq;
803 for (
int i = 0; i <
ui_.configs->count(); i++)
805 out << YAML::BeginMap;
806 out << YAML::Key <<
"type" << YAML::Value <<
plugins_[
ui_.configs->item(i)]->Type();
807 out << YAML::Key <<
"name" << YAML::Value << (static_cast<ConfigItem*>(
ui_.configs->itemWidget(
ui_.configs->item(i))))->Name().toStdString();
808 out << YAML::Key <<
"config" << YAML::Value;
809 out << YAML::BeginMap;
811 out << YAML::Key <<
"visible" << YAML::Value <<
plugins_[
ui_.configs->item(i)]->Visible();
812 out << YAML::Key <<
"collapsed" << YAML::Value << (static_cast<ConfigItem*>(
ui_.configs->itemWidget(
ui_.configs->item(i))))->Collapsed();
814 plugins_[
ui_.configs->item(i)]->SaveConfig(out, config_path);
831 QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
832 QString default_path = QDir::homePath();
841 QFileInfo file_info(ws_file);
842 QFileInfo dir_info(ws_path);
843 if ((!file_info.exists() && dir_info.isWritable()) ||
844 file_info.isWritable())
849 default_path = ws_path;
853 ROS_WARN(
"Could not write config file to %s. Trying home directory.",
854 (ws_path + MAPVIZ_CONFIG_FILE).toStdString().c_str());
860 Save(default_path.toStdString());
865 QFileDialog dialog(
this,
"Select Config File");
866 dialog.setFileMode(QFileDialog::ExistingFile);
867 dialog.setNameFilter(tr(
"Mapviz Config Files (*.mvc)"));
871 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
873 std::string path = dialog.selectedFiles().first().toStdString();
880 QFileDialog dialog(
this,
"Save Config File");
881 dialog.setFileMode(QFileDialog::AnyFile);
882 dialog.setAcceptMode(QFileDialog::AcceptSave);
883 dialog.setNameFilter(tr(
"Mapviz Config Files (*.mvc)"));
887 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
889 std::string path = dialog.selectedFiles().first().toStdString();
892 size_t last_slash = path.find_last_of(
'/');
893 if (last_slash != std::string::npos && last_slash != path.size() - 1)
895 title = path.substr(last_slash + 1) +
" (" +
896 path.substr(0, last_slash + 1) +
")";
903 title +=
" - mapviz";
905 setWindowTitle(QString::fromStdString(title));
915 plugin.second->ClearHistory();
926 std::vector<std::string> plugins =
loader_->getDeclaredClasses();
927 std::map<std::string, std::string> plugin_types;
928 for (
size_t i = 0; i < plugins.size(); i++)
930 QString type(plugins[i].c_str());
931 type = type.split(
'/').last();
932 ui.displaylist->addItem(type);
933 plugin_types[type.toStdString()] = plugins[i];
935 ui.displaylist->setCurrentRow(0);
939 if (dialog.result() == QDialog::Accepted)
941 std::string type_name = ui.displaylist->selectedItems().first()->text().toStdString();
942 std::string type = plugin_types[type_name];
943 std::string
name =
"new display";
950 std::stringstream message;
951 message <<
"Unable to load " << type <<
"." << std::endl <<
"Check the ROS log for more details.";
952 QMessageBox::warning(
this,
"Plugin failed to load", QString::fromStdString(message.str()));
959 AddMapvizDisplay::Request& req,
960 AddMapvizDisplay::Response& resp)
962 std::map<std::string, std::string> properties;
963 for (
auto& property: req.properties)
965 properties[
property.key] =
property.value;
971 ROS_ERROR(
"Failed to parse properties into YAML.");
983 if (plugin->Name() == req.name && plugin->Type() ==req.type)
985 plugin->LoadConfig(config,
"");
986 plugin->SetVisible(req.visible);
988 if (req.draw_order > 0)
990 display.first->setData(Qt::UserRole, QVariant(req.draw_order - 1.1));
991 ui_.configs->sortItems();
995 else if (req.draw_order < 0)
997 display.first->setData(Qt::UserRole, QVariant(
ui_.configs->count() + req.draw_order + 0.1));
998 ui_.configs->sortItems();
1003 resp.success =
true;
1013 plugin->LoadConfig(config,
"");
1015 resp.success =
true;
1020 resp.success =
false;
1021 resp.message =
"Failed to load display plug-in.";
1029 if (
ui_.statusbar->isVisible())
1038 int32_t precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / scale))));
1040 QString text =
ui_.fixedframe->currentText();
1041 if (text.isEmpty() || text ==
"/")
1047 std::ostringstream x_ss;
1048 x_ss << std::fixed << std::setprecision(precision);
1050 text += x_ss.str().c_str();
1054 std::ostringstream y_ss;
1055 y_ss << std::fixed << std::setprecision(precision);
1057 text += y_ss.str().c_str();
1066 ui_.fixedframe->currentText().toStdString()) &&
1069 ui_.fixedframe->currentText().toStdString(),
1073 point = transform * point;
1075 QString lat_lon_text =
"lat/lon: ";
1077 double lat_scale = (1.0 / 111111.0) * scale;
1078 int32_t lat_precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / lat_scale))));
1080 std::ostringstream lat_ss;
1081 lat_ss << std::fixed << std::setprecision(lat_precision);
1082 lat_ss << point.y();
1083 lat_lon_text += lat_ss.str().c_str();
1085 lat_lon_text +=
", ";
1088 int32_t lon_precision =
static_cast<int32_t
>(std::ceil(std::max(0.0, std::log10(1.0 / lon_scale))));
1090 std::ostringstream lon_ss;
1091 lon_ss << std::fixed << std::setprecision(lon_precision);
1092 lon_ss << point.x();
1093 lat_lon_text += lon_ss.str().c_str();
1107 const std::string& name,
1108 const std::string& type,
1115 config_item->
SetName(name.c_str());
1117 std::string real_type = type;
1118 if (real_type ==
"mapviz_plugins/mutlires_image")
1123 real_type =
"mapviz_plugins/multires_image";
1127 ROS_INFO(
"creating: %s", real_type.c_str());
1131 config_item->
SetWidget(plugin->GetConfigWidget(
this));
1132 plugin->SetIcon(config_item->
ui_.icon);
1135 plugin->SetType(real_type.c_str());
1136 plugin->SetName(name);
1137 plugin->SetNode(*
node_);
1138 plugin->SetVisible(visible);
1140 if (draw_order == 0)
1142 plugin->SetDrawOrder(
ui_.configs->count());
1144 else if (draw_order > 0)
1146 plugin->SetDrawOrder(std::min(
ui_.configs->count(), draw_order - 1));
1148 else if (draw_order < 0)
1150 plugin->SetDrawOrder(std::max(0,
ui_.configs->count() + draw_order + 1));
1153 QString pretty_type(real_type.c_str());
1154 pretty_type = pretty_type.split(
'/').last();
1155 config_item->
SetType(pretty_type);
1158 item->setSizeHint(config_item->sizeHint());
1159 connect(config_item, SIGNAL(UpdateSizeHint()),
this, SLOT(
UpdateSizeHints()));
1160 connect(config_item, SIGNAL(ToggledDraw(QListWidgetItem*,
bool)),
this, SLOT(
ToggleShowPlugin(QListWidgetItem*,
bool)));
1161 connect(config_item, SIGNAL(RemoveRequest(QListWidgetItem*)),
this, SLOT(
RemoveDisplay(QListWidgetItem*)));
1162 connect(plugin.get(), SIGNAL(VisibleChanged(
bool)), config_item, SLOT(ToggleDraw(
bool)));
1163 connect(plugin.get(), SIGNAL(SizeChanged()),
this, SLOT(
UpdateSizeHints()));
1165 if (real_type ==
"mapviz_plugins/image")
1172 plugin.get(), SLOT(Resubscribe()));
1175 if (draw_order == 0)
1177 ui_.configs->addItem(item);
1181 ui_.configs->insertItem(plugin->DrawOrder(), item);
1184 ui_.configs->setItemWidget(item, config_item);
1185 ui_.configs->UpdateIndices();
1188 plugin->SetTargetFrame(
ui_.fixedframe->currentText().toStdString());
1189 plugin->SetUseLatestTransforms(
ui_.uselatesttransforms->isChecked());
1196 config_item->
Hide();
1209 plugins_[item]->SetVisible(visible);
1218 ROS_INFO(
"Fixed frame selected: %s", text.toStdString().c_str());
1230 ROS_INFO(
"Target frame selected: %s", text.toStdString().c_str());
1263 ui_.configdock->show();
1267 ui_.configdock->hide();
1275 ui_.statusbar->setVisible(on);
1284 ui_.actionShow_Status_Bar->setChecked(
true);
1301 rec_button_->setIcon(QIcon(
":/images/media-playback-pause.png"));
1302 rec_button_->setToolTip(
"Pause recording video of display canvas");
1310 std::string posix_time = boost::posix_time::to_iso_string(
ros::WallTime::now().toBoost());
1311 boost::replace_all(posix_time,
".",
"_");
1313 boost::replace_all(filename,
"~", getenv(
"HOME"));
1318 ROS_ERROR(
"Failed to open video file for writing.");
1323 ROS_INFO(
"Writing video to: %s", filename.c_str());
1324 ui_.statusbar->showMessage(
"Recording video to " + QString::fromStdString(filename));
1333 rec_button_->setIcon(QIcon(
":/images/media-record.png"));
1334 rec_button_->setToolTip(
"Continue recording video of display canvas");
1341 std::string transport = transport_action->text().toStdString();
1352 std::string current_transport;
1354 Q_FOREACH(QAction*
action, actions)
1356 if (action->text() == QString::fromStdString(current_transport))
1358 action->setChecked(
true);
1363 ROS_WARN(
"%s param was set to an unrecognized value: %s",
1364 IMAGE_TRANSPORT_PARAM.c_str(), current_transport.c_str());
1375 QImage frame(
canvas_->width(),
canvas_->height(), QImage::Format_ARGB32);
1382 ROS_ERROR(
"Failed to get capture buffer");
1403 ui_.statusbar->showMessage(QString(
""));
1404 rec_button_->setToolTip(
"Start recording video of display canvas");
1413 std::vector<uint8_t> frame;
1416 cv::Mat image(
canvas_->height(),
canvas_->width(), CV_8UC4, &frame[0]);
1418 cvtColor(image, screenshot, CV_BGRA2BGR);
1420 cv::flip(screenshot, screenshot, 0);
1422 std::string posix_time = boost::posix_time::to_iso_string(
ros::WallTime::now().toBoost());
1423 boost::replace_all(posix_time,
".",
"_");
1425 boost::replace_all(filename,
"~", getenv(
"HOME"));
1427 ROS_INFO(
"Writing screenshot to: %s", filename.c_str());
1428 ui_.statusbar->showMessage(
"Saved image to " + QString::fromStdString(filename));
1430 cv::imwrite(filename, screenshot);
1434 ROS_ERROR(
"Failed to take screenshot.");
1440 for (
int i = 0; i <
ui_.configs->count(); i++)
1442 QListWidgetItem* item =
ui_.configs->item(i);
1448 item->setSizeHint(widget->sizeHint());
1455 QListWidgetItem* item =
ui_.configs->takeItem(
ui_.configs->currentRow());
1474 while (
ui_.configs->count() > 0)
1478 QListWidgetItem* item =
ui_.configs->takeItem(0);
1490 for (
int i = 0; i <
ui_.configs->count(); i++)
1505 QFileDialog dialog(
this,
"Select Capture Directory");
1506 dialog.setFileMode(QFileDialog::DirectoryOnly);
1510 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
1525 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)
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)
boost::shared_ptr< MapvizPlugin > MapvizPluginPtr
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)
swri_transform_util::TransformManager tf_manager_
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_
void ToggleStatusBar(bool on)
QMenu * image_transport_menu_