mapviz.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #include <mapviz/mapviz.h>
31 
32 // C++ standard libraries
33 #include <cmath>
34 #include <cstdlib>
35 #include <algorithm>
36 #include <fstream>
37 #include <sstream>
38 
39 // Boost libraries
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>
46 
47 // OpenCV libraries
48 #include <opencv2/core.hpp>
49 #include <opencv2/imgcodecs.hpp>
50 #include <opencv2/imgproc.hpp>
51 #include <opencv2/videoio.hpp>
52 
53 // QT libraries
54 #include <QtWidgets/QApplication>
55 #include <QFileDialog>
56 #include <QActionGroup>
57 #include <QColorDialog>
58 #include <QLabel>
59 #include <QMessageBox>
60 #include <QProcessEnvironment>
61 #include <QFileInfo>
62 #include <QListWidgetItem>
63 #include <QMutexLocker>
64 
68 
69 #include <mapviz/config_item.h>
70 #include <QtGui/QtGui>
71 
73 
74 namespace mapviz
75 {
76 const QString Mapviz::ROS_WORKSPACE_VAR = "ROS_WORKSPACE";
77 const QString Mapviz::MAPVIZ_CONFIG_FILE = "/.mapviz_config";
78 const std::string Mapviz::IMAGE_TRANSPORT_PARAM = "image_transport";
79 
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")),
84  argc_(argc),
85  argv_(argv),
86  is_standalone_(is_standalone),
87  initialized_(false),
88  force_720p_(false),
89  force_480p_(false),
90  resizable_(true),
91  background_(Qt::gray),
92  capture_directory_("~"),
93  vid_writer_(NULL),
94  updating_frames_(false),
95  node_(NULL),
96  canvas_(NULL)
97 {
98  ui_.setupUi(this);
99 
100  xy_pos_label_->setVisible(false);
101  lat_lon_pos_label_->setVisible(false);
102 
103  ui_.statusbar->addPermanentWidget(xy_pos_label_);
104  ui_.statusbar->addPermanentWidget(lat_lon_pos_label_);
105 
106  spacer1_ = new QWidget(ui_.statusbar);
107  spacer1_->setMaximumSize(22,22);
108  spacer1_->setMinimumSize(22,22);
109  ui_.statusbar->addPermanentWidget(spacer1_);
110 
111  screenshot_button_ = new QPushButton();
112  screenshot_button_->setMinimumSize(22, 22);
113  screenshot_button_->setMaximumSize(22,22);
114  screenshot_button_->setIcon(QIcon(":/images/image-x-generic.png"));
115  screenshot_button_->setFlat(true);
116  screenshot_button_->setToolTip("Capture screenshot of display canvas");
117  ui_.statusbar->addPermanentWidget(screenshot_button_);
118 
119  spacer2_ = new QWidget(ui_.statusbar);
120  spacer2_->setMaximumSize(22,22);
121  spacer2_->setMinimumSize(22,22);
122  ui_.statusbar->addPermanentWidget(spacer2_);
123 
124  rec_button_ = new QPushButton();
125  rec_button_->setMinimumSize(22, 22);
126  rec_button_->setMaximumSize(22,22);
127  rec_button_->setIcon(QIcon(":/images/media-record.png"));
128  rec_button_->setCheckable(true);
129  rec_button_->setFlat(true);
130  rec_button_->setToolTip("Start recording video of display canvas");
131  ui_.statusbar->addPermanentWidget(rec_button_);
132 
133  stop_button_ = new QPushButton();
134  stop_button_->setMinimumSize(22, 22);
135  stop_button_->setMaximumSize(22,22);
136  stop_button_->setIcon(QIcon(":/images/media-playback-stop.png"));
137  stop_button_->setToolTip("Stop recording video of display canvas");
138  stop_button_->setEnabled(false);
139  stop_button_->setFlat(true);
140  ui_.statusbar->addPermanentWidget(stop_button_);
141 
142  spacer3_ = new QWidget(ui_.statusbar);
143  spacer3_->setMaximumSize(22,22);
144  spacer3_->setMinimumSize(22,22);
145  ui_.statusbar->addPermanentWidget(spacer3_);
146 
147  recenter_button_ = new QPushButton();
148  recenter_button_->setMinimumSize(22, 22);
149  recenter_button_->setMaximumSize(22, 22);
150  recenter_button_->setIcon(QIcon(":/images/arrow_in.png"));
151  recenter_button_->setToolTip("Reset the viewport to the default location and zoom level");
152  recenter_button_->setFlat(true);
153  ui_.statusbar->addPermanentWidget(recenter_button_);
154 
155  ui_.statusbar->setVisible(true);
156 
157  QActionGroup* group = new QActionGroup(this);
158 
159  ui_.actionForce_720p->setActionGroup(group);
160  ui_.actionForce_480p->setActionGroup(group);
161  ui_.actionResizable->setActionGroup(group);
162 
163  ui_.targetframe->addItem("<none>");
164 
165  canvas_ = new MapCanvas(this);
166  setCentralWidget(canvas_);
167 
168  connect(canvas_, SIGNAL(Hover(double,double,double)), this, SLOT(Hover(double,double,double)));
169  connect(ui_.configs, SIGNAL(ItemsMoved()), this, SLOT(ReorderDisplays()));
170  connect(ui_.actionExit, SIGNAL(triggered()), this, SLOT(close()));
171  connect(ui_.bg_color, SIGNAL(colorEdited(const QColor &)), this, SLOT(SelectBackgroundColor(const QColor &)));
172 
173  connect(recenter_button_, SIGNAL(clicked()), this, SLOT(Recenter()));
174  connect(rec_button_, SIGNAL(toggled(bool)), this, SLOT(ToggleRecord(bool)));
175  connect(stop_button_, SIGNAL(clicked()), this, SLOT(StopRecord()));
176  connect(screenshot_button_, SIGNAL(clicked()), this, SLOT(Screenshot()));
177  connect(ui_.actionClear_History, SIGNAL(triggered()), this, SLOT(ClearHistory()));
178 
179  // Use a separate thread for writing video files so that it won't cause
180  // lag on the main thread.
181  // It's ok for the video writer to be a pointer that we intantiate here and
182  // then forget about; the worker thread will delete it when the thread exits.
183  vid_writer_ = new VideoWriter();
184  vid_writer_->moveToThread(&video_thread_);
185  connect(&video_thread_, SIGNAL(finished()), vid_writer_, SLOT(deleteLater()));
186  connect(this, SIGNAL(FrameGrabbed(QImage)), vid_writer_, SLOT(processFrame(QImage)));
187  video_thread_.start();
188 
189  image_transport_menu_ = new QMenu("Default Image Transport", ui_.menu_View);
190  ui_.menu_View->addMenu(image_transport_menu_);
191 
192  connect(image_transport_menu_, SIGNAL(aboutToShow()), this, SLOT(UpdateImageTransportMenu()));
193 
194  ui_.bg_color->setColor(background_);
196 }
197 
199 {
200  video_thread_.quit();
201  video_thread_.wait();
202  delete node_;
203 }
204 
205 void Mapviz::showEvent(QShowEvent* event)
206 {
207  Initialize();
208 }
209 
210 void Mapviz::closeEvent(QCloseEvent* event)
211 {
212  AutoSave();
213 
214  for (auto& display: plugins_)
215  {
216  MapvizPluginPtr plugin = display.second;
217  canvas_->RemovePlugin(plugin);
218  }
219 
220  plugins_.clear();
221 }
222 
224 {
225  if (!initialized_)
226  {
227  if (is_standalone_)
228  {
229  // If this Mapviz is running as a standalone application, it needs to init
230  // ROS and start spinning. If it's running as an rqt plugin, rqt will
231  // take care of that.
233 
234  spin_timer_.start(30);
235  connect(&spin_timer_, SIGNAL(timeout()), this, SLOT(SpinOnce()));
236  }
237 
238  node_ = new ros::NodeHandle("~");
239 
240  // Create a sub-menu that lists all available Image Transports
242  std::vector<std::string> transports = it.getLoadableTransports();
243  QActionGroup* group = new QActionGroup(image_transport_menu_);
244  for (std::vector<std::string>::iterator iter = transports.begin(); iter != transports.end(); iter++)
245  {
246  QString transport = QString::fromStdString(*iter).replace(
247  QString::fromStdString(IMAGE_TRANSPORT_PARAM) + "/", "");
248  QAction* action = image_transport_menu_->addAction(transport);
249  action->setCheckable(true);
250  group->addAction(action);
251  }
252 
253  connect(group, SIGNAL(triggered(QAction*)), this, SLOT(SetImageTransport(QAction*)));
254 
255  tf_ = boost::make_shared<tf::TransformListener>();
257 
259  "mapviz", "mapviz::MapvizPlugin");
260 
261  std::vector<std::string> plugins = loader_->getDeclaredClasses();
262  for (unsigned int i = 0; i < plugins.size(); i++)
263  {
264  ROS_INFO("Found mapviz plugin: %s", plugins[i].c_str());
265  }
266 
268  canvas_->SetFixedFrame(ui_.fixedframe->currentText().toStdString());
269  canvas_->SetTargetFrame(ui_.targetframe->currentText().toStdString());
270 
271  ros::NodeHandle priv("~");
272 
273  add_display_srv_ = node_->advertiseService("add_mapviz_display", &Mapviz::AddDisplay, this);
274 
275  QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
276  QString default_path = QDir::homePath();
277  if (env.contains(ROS_WORKSPACE_VAR))
278  {
279  // If the ROS_WORKSPACE environment variable is defined, try to read our
280  // config file out of that. If we can't read it, fall back to trying to
281  // read one from the user's home directory.
282  QString ws_path = env.value(ROS_WORKSPACE_VAR, default_path);
283  if (QFileInfo(ws_path + MAPVIZ_CONFIG_FILE).isReadable())
284  {
285  default_path = ws_path;
286  }
287  else
288  {
289  ROS_WARN("Could not load config file from ROS_WORKSPACE at %s; trying home directory...",
290  ws_path.toStdString().c_str());
291  }
292  }
293  default_path += MAPVIZ_CONFIG_FILE;
294 
295 
296  std::string config;
297  priv.param("config", config, default_path.toStdString());
298 
299  bool auto_save;
300  priv.param("auto_save_backup", auto_save, true);
301 
302  Open(config);
303 
304  UpdateFrames();
305  frame_timer_.start(1000);
306  connect(&frame_timer_, SIGNAL(timeout()), this, SLOT(UpdateFrames()));
307 
308  if (auto_save)
309  {
310  save_timer_.start(10000);
311  connect(&save_timer_, SIGNAL(timeout()), this, SLOT(AutoSave()));
312  }
313 
314  connect(&record_timer_, SIGNAL(timeout()), this, SLOT(CaptureVideoFrame()));
315 
316  bool print_profile_data;
317  priv.param("print_profile_data", print_profile_data, false);
318  if (print_profile_data)
319  {
320  profile_timer_.start(2000);
321  connect(&profile_timer_, SIGNAL(timeout()), this, SLOT(HandleProfileTimer()));
322  }
323 
324  initialized_ = true;
325  }
326 }
327 
329 {
330  if (ros::ok())
331  {
332  meas_spin_.start();
333  ros::spinOnce();
334  meas_spin_.stop();
335  }
336  else
337  {
338  QApplication::exit();
339  }
340 }
341 
343 {
344  std::vector<std::string> frames;
345  tf_->getFrameStrings(frames);
346  std::sort(frames.begin(), frames.end());
347 
348  if (ui_.fixedframe->count() >= 0 &&
349  static_cast<size_t>(ui_.fixedframe->count()) == frames.size())
350  {
351  bool changed = false;
352  for (size_t i = 0; i < frames.size(); i++)
353  {
354  if (frames[i] != ui_.fixedframe->itemText(i).toStdString())
355  {
356  changed = true;
357  }
358  }
359 
360  if (!changed)
361  return;
362  }
363 
364  updating_frames_ = true;
365 
366  std::string current_fixed = ui_.fixedframe->currentText().toStdString();
367 
368  ui_.fixedframe->clear();
369  for (size_t i = 0; i < frames.size(); i++)
370  {
371  ui_.fixedframe->addItem(frames[i].c_str());
372  }
373 
374  if (current_fixed != "")
375  {
376  int index = ui_.fixedframe->findText(current_fixed.c_str());
377  if (index < 0)
378  {
379  ui_.fixedframe->addItem(current_fixed.c_str());
380  }
381 
382  index = ui_.fixedframe->findText(current_fixed.c_str());
383  ui_.fixedframe->setCurrentIndex(index);
384  }
385 
386  std::string current_target = ui_.targetframe->currentText().toStdString();
387 
388  ui_.targetframe->clear();
389  ui_.targetframe->addItem("<none>");
390  for (size_t i = 0; i < frames.size(); i++)
391  {
392  ui_.targetframe->addItem(frames[i].c_str());
393  }
394 
395  if (current_target != "")
396  {
397  int index = ui_.targetframe->findText(current_target.c_str());
398  if (index < 0)
399  {
400  ui_.targetframe->addItem(current_target.c_str());
401  }
402 
403  index = ui_.targetframe->findText(current_target.c_str());
404  ui_.targetframe->setCurrentIndex(index);
405  }
406 
407  updating_frames_ = false;
408 
409  if (current_target != ui_.targetframe->currentText().toStdString())
410  {
411  TargetFrameSelected(ui_.targetframe->currentText());
412  }
413 
414  if (current_fixed != ui_.fixedframe->currentText().toStdString())
415  {
416  FixedFrameSelected(ui_.fixedframe->currentText());
417  }
418 }
419 
420 void Mapviz::Force720p(bool on)
421 {
422  if (force_720p_ != on)
423  {
424  force_720p_ = on;
425 
426  if (force_720p_)
427  {
428  force_480p_ = false;
429  resizable_ = false;
430  }
431 
433  }
434 }
435 
436 void Mapviz::Force480p(bool on)
437 {
438  if (force_480p_ != on)
439  {
440  force_480p_ = on;
441 
442  if (force_480p_)
443  {
444  force_720p_ = false;
445  resizable_ = false;
446  }
447 
449  }
450 }
451 
452 void Mapviz::SetResizable(bool on)
453 {
454  if (resizable_ != on)
455  {
456  resizable_ = on;
457 
458  if (resizable_)
459  {
460  force_720p_ = false;
461  force_480p_ = false;
462  }
463 
465  }
466 }
467 
469 {
470  canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred));
471  setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred));
472 
473  this->setMinimumSize(QSize(100, 100));
474  this->setMaximumSize(QSize(10000, 10000));
475 
476  if (force_720p_)
477  {
478  canvas_->setMinimumSize(1280, 720);
479  canvas_->setMaximumSize(1280, 720);
480  canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
481  adjustSize();
482  this->setMaximumSize(this->sizeHint());
483  this->setMinimumSize(this->sizeHint());
484  setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
485  }
486  else if (force_480p_)
487  {
488  canvas_->setMinimumSize(640, 480);
489  canvas_->setMaximumSize(640, 480);
490  canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
491  adjustSize();
492  this->setMaximumSize(this->sizeHint());
493  this->setMinimumSize(this->sizeHint());
494  setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
495  }
496  else if (stop_button_->isEnabled())
497  {
498  canvas_->setMinimumSize(canvas_->width(), canvas_->height());
499  canvas_->setMaximumSize(canvas_->width(), canvas_->height());
500  canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
501  adjustSize();
502  this->setMaximumSize(this->sizeHint());
503  this->setMinimumSize(this->sizeHint());
504  setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
505  }
506  else
507  {
508  canvas_->setMinimumSize(100, 100);
509  canvas_->setMaximumSize(10000, 10000);
510  }
511 }
512 
513 void Mapviz::Open(const std::string& filename)
514 {
515  ROS_INFO("Loading configuration from: %s", filename.c_str());
516 
517  std::string title;
518  size_t last_slash = filename.find_last_of('/');
519  if (last_slash != std::string::npos && last_slash != filename.size() - 1)
520  {
521  title = filename.substr(last_slash + 1) + " (" +
522  filename.substr(0, last_slash + 1) + ")";
523  }
524  else
525  {
526  title = filename;
527  }
528 
529  title += " - mapviz";
530  setWindowTitle(QString::fromStdString(title));
531 
532  YAML::Node doc;
533  if (!swri_yaml_util::LoadFile(filename, doc))
534  {
535  ROS_ERROR("Failed to load file: %s", filename.c_str());
536  return;
537  }
538 
539  std::vector<std::string> failed_plugins;
540 
541  try
542  {
543  boost::filesystem::path filepath(filename);
544  std::string config_path = filepath.parent_path().string();
545 
546  ClearDisplays();
547 
548  if (swri_yaml_util::FindValue(doc, "capture_directory"))
549  {
550  doc["capture_directory"] >> capture_directory_;
551  }
552 
553  if (swri_yaml_util::FindValue(doc, "fixed_frame"))
554  {
555  std::string fixed_frame;
556  doc["fixed_frame"] >> fixed_frame;
557  ui_.fixedframe->setEditText(fixed_frame.c_str());
558  }
559 
560  if (swri_yaml_util::FindValue(doc, "target_frame"))
561  {
562  std::string target_frame;
563  doc["target_frame"] >> target_frame;
564  ui_.targetframe->setEditText(target_frame.c_str());
565  }
566 
567  if (swri_yaml_util::FindValue(doc, "fix_orientation"))
568  {
569  bool fix_orientation = false;
570  doc["fix_orientation"] >> fix_orientation;
571  ui_.actionFix_Orientation->setChecked(fix_orientation);
572  }
573 
574  if (swri_yaml_util::FindValue(doc, "rotate_90"))
575  {
576  bool rotate_90 = false;
577  doc["rotate_90"] >> rotate_90;
578  ui_.actionRotate_90->setChecked(rotate_90);
579  }
580 
581  if (swri_yaml_util::FindValue(doc, "enable_antialiasing"))
582  {
583  bool enable_antialiasing = true;
584  doc["enable_antialiasing"] >> enable_antialiasing;
585  ui_.actionEnable_Antialiasing->setChecked(enable_antialiasing);
586  }
587 
588  if (swri_yaml_util::FindValue(doc, "show_displays"))
589  {
590  bool show_displays = false;
591  doc["show_displays"] >> show_displays;
592  ui_.actionConfig_Dock->setChecked(show_displays);
593  }
594 
595  if (swri_yaml_util::FindValue(doc, "show_capture_tools"))
596  {
597  bool show_capture_tools = false;
598  doc["show_capture_tools"] >> show_capture_tools;
599  ui_.actionShow_Capture_Tools->setChecked(show_capture_tools);
600  }
601 
602  if (swri_yaml_util::FindValue(doc, "show_status_bar"))
603  {
604  bool show_status_bar = false;
605  doc["show_status_bar"] >> show_status_bar;
606  ui_.actionShow_Status_Bar->setChecked(show_status_bar);
607  }
608 
609  if (swri_yaml_util::FindValue(doc, "show_capture_tools"))
610  {
611  bool show_capture_tools = false;
612  doc["show_capture_tools"] >> show_capture_tools;
613  ui_.actionShow_Capture_Tools->setChecked(show_capture_tools);
614  }
615 
616  if (swri_yaml_util::FindValue(doc, "window_width"))
617  {
618  int window_width = 0;
619  doc["window_width"] >> window_width;
620  resize(window_width, height());
621  }
622 
623  if (swri_yaml_util::FindValue(doc, "window_height"))
624  {
625  int window_height = 0;
626  doc["window_height"] >> window_height;
627  resize(width(), window_height);
628  }
629 
630  if (swri_yaml_util::FindValue(doc, "view_scale"))
631  {
632  float scale = 0;
633  doc["view_scale"] >> scale;
634  canvas_->SetViewScale(scale);
635  }
636 
637  if (swri_yaml_util::FindValue(doc, "offset_x"))
638  {
639  float x = 0;
640  doc["offset_x"] >> x;
641  canvas_->SetOffsetX(x);
642  }
643 
644  if (swri_yaml_util::FindValue(doc, "offset_x"))
645  {
646  float y = 0;
647  doc["offset_y"] >> y;
648  canvas_->SetOffsetY(y);
649  }
650 
651  if (swri_yaml_util::FindValue(doc, "force_720p"))
652  {
653  bool force_720p;
654  doc["force_720p"] >> force_720p;
655 
656  if (force_720p)
657  {
658  ui_.actionForce_720p->setChecked(true);
659  }
660  }
661 
662  if (swri_yaml_util::FindValue(doc, "force_480p"))
663  {
664  bool force_480p;
665  doc["force_480p"] >> force_480p;
666 
667  if (force_480p)
668  {
669  ui_.actionForce_480p->setChecked(true);
670  }
671  }
672 
674  {
675  std::string image_transport;
676  doc[IMAGE_TRANSPORT_PARAM] >> image_transport;
677 
678  node_->setParam(IMAGE_TRANSPORT_PARAM, image_transport);
679  }
680 
681  bool use_latest_transforms = true;
682  if (swri_yaml_util::FindValue(doc, "use_latest_transforms"))
683  {
684  doc["use_latest_transforms"] >> use_latest_transforms;
685  }
686  ui_.uselatesttransforms->setChecked(use_latest_transforms);
687  canvas_->ToggleUseLatestTransforms(use_latest_transforms);
688 
689  if (swri_yaml_util::FindValue(doc, "background"))
690  {
691  std::string color;
692  doc["background"] >> color;
693  background_ = QColor(color.c_str());
694  ui_.bg_color->setColor(background_);
696  }
697 
698  if (swri_yaml_util::FindValue(doc, "displays"))
699  {
700  const YAML::Node& displays = doc["displays"];
701  for (uint32_t i = 0; i < displays.size(); i++)
702  {
703  std::string type, name;
704  displays[i]["type"] >> type;
705  displays[i]["name"] >> name;
706 
707  const YAML::Node& config = displays[i]["config"];
708 
709  bool visible = false;
710  config["visible"] >> visible;
711 
712  bool collapsed = false;
713  config["collapsed"] >> collapsed;
714 
715  try
716  {
717  MapvizPluginPtr plugin =
718  CreateNewDisplay(name, type, visible, collapsed);
719  plugin->LoadConfig(config, config_path);
720  plugin->DrawIcon();
721  }
722  catch (const pluginlib::LibraryLoadException& e)
723  {
724  failed_plugins.push_back(type);
725  ROS_ERROR("%s", e.what());
726  }
727  }
728  }
729  }
730  catch (const YAML::ParserException& e)
731  {
732  ROS_ERROR("%s", e.what());
733  return;
734  }
735  catch (const YAML::Exception& e)
736  {
737  ROS_ERROR("%s", e.what());
738  return;
739  }
740 
741  if (!failed_plugins.empty())
742  {
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.";
747 
748  QMessageBox::warning(this, "Failed to load plugins", QString::fromStdString(message.str()));
749  }
750 }
751 
752 void Mapviz::Save(const std::string& filename)
753 {
754  std::ofstream fout(filename.c_str());
755  if (fout.fail())
756  {
757  ROS_ERROR("Failed to open file: %s", filename.c_str());
758  return;
759  }
760 
761  boost::filesystem::path filepath(filename);
762  std::string config_path = filepath.parent_path().string();
763 
764  YAML::Emitter out;
765 
766  out << YAML::BeginMap;
767  out << YAML::Key << "capture_directory" << YAML::Value << capture_directory_;
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();
778  out << YAML::Key << "view_scale" << YAML::Value << canvas_->ViewScale();
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();
783  std::string image_transport;
784  if (node_->getParam(IMAGE_TRANSPORT_PARAM, image_transport))
785  {
786  out << YAML::Key << IMAGE_TRANSPORT_PARAM << YAML::Value << image_transport;
787  }
788 
789  if (force_720p_)
790  {
791  out << YAML::Key << "force_720p" << YAML::Value << force_720p_;
792  }
793 
794  if (force_480p_)
795  {
796  out << YAML::Key << "force_480p" << YAML::Value << force_480p_;
797  }
798 
799  if (ui_.configs->count() > 0)
800  {
801  out << YAML::Key << "displays"<< YAML::Value << YAML::BeginSeq;
802 
803  for (int i = 0; i < ui_.configs->count(); i++)
804  {
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;
810 
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();
813 
814  plugins_[ui_.configs->item(i)]->SaveConfig(out, config_path);
815 
816  out << YAML::EndMap;
817  out << YAML::EndMap;
818  }
819 
820  out << YAML::EndSeq;
821  }
822 
823  out << YAML::EndMap;
824 
825  fout << out.c_str();
826  fout.close();
827 }
828 
830 {
831  QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
832  QString default_path = QDir::homePath();
833 
834  if (env.contains(ROS_WORKSPACE_VAR))
835  {
836  // Try to save our config in the ROS_WORKSPACE directory, but if we can't write
837  // to that -- probably because it is read-only -- try to use the home directory
838  // instead.
839  QString ws_path = env.value(ROS_WORKSPACE_VAR, default_path);
840  QString ws_file = ws_path + MAPVIZ_CONFIG_FILE;
841  QFileInfo file_info(ws_file);
842  QFileInfo dir_info(ws_path);
843  if ((!file_info.exists() && dir_info.isWritable()) ||
844  file_info.isWritable())
845  {
846  // Note that FileInfo::isWritable will return false if a file does not exist, so
847  // we need to check both if the target file is writable and if the target dir is
848  // writable if the file doesn't exist.
849  default_path = ws_path;
850  }
851  else
852  {
853  ROS_WARN("Could not write config file to %s. Trying home directory.",
854  (ws_path + MAPVIZ_CONFIG_FILE).toStdString().c_str());
855  }
856  }
857  default_path += MAPVIZ_CONFIG_FILE;
858 
859 
860  Save(default_path.toStdString());
861 }
862 
864 {
865  QFileDialog dialog(this, "Select Config File");
866  dialog.setFileMode(QFileDialog::ExistingFile);
867  dialog.setNameFilter(tr("Mapviz Config Files (*.mvc)"));
868 
869  dialog.exec();
870 
871  if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
872  {
873  std::string path = dialog.selectedFiles().first().toStdString();
874  Open(path);
875  }
876 }
877 
879 {
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)"));
884 
885  dialog.exec();
886 
887  if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
888  {
889  std::string path = dialog.selectedFiles().first().toStdString();
890 
891  std::string title;
892  size_t last_slash = path.find_last_of('/');
893  if (last_slash != std::string::npos && last_slash != path.size() - 1)
894  {
895  title = path.substr(last_slash + 1) + " (" +
896  path.substr(0, last_slash + 1) + ")";
897  }
898  else
899  {
900  title = path;
901  }
902 
903  title += " - mapviz";
904 
905  setWindowTitle(QString::fromStdString(title));
906 
907  Save(path);
908  }
909 }
910 
912 {
913  for (auto& plugin: plugins_)
914  {
915  plugin.second->ClearHistory();
916  }
917 }
918 
920 {
921  ROS_INFO("Select new display ...");
922  QDialog dialog;
923  Ui::pluginselect ui;
924  ui.setupUi(&dialog);
925 
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++)
929  {
930  QString type(plugins[i].c_str());
931  type = type.split('/').last();
932  ui.displaylist->addItem(type);
933  plugin_types[type.toStdString()] = plugins[i];
934  }
935  ui.displaylist->setCurrentRow(0);
936 
937  dialog.exec();
938 
939  if (dialog.result() == QDialog::Accepted)
940  {
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";
944  try
945  {
946  CreateNewDisplay(name, type, true, false);
947  }
948  catch (const pluginlib::LibraryLoadException& e)
949  {
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()));
953  ROS_ERROR("%s", e.what());
954  }
955  }
956 }
957 
959  AddMapvizDisplay::Request& req,
960  AddMapvizDisplay::Response& resp)
961 {
962  std::map<std::string, std::string> properties;
963  for (auto& property: req.properties)
964  {
965  properties[property.key] = property.value;
966  }
967 
968  YAML::Node config;
969  if (!swri_yaml_util::LoadMap(properties, config))
970  {
971  ROS_ERROR("Failed to parse properties into YAML.");
972  return false;
973  }
974 
975  for (auto& display: plugins_)
976  {
977  MapvizPluginPtr plugin = display.second;
978  if (!plugin)
979  {
980  ROS_ERROR("Invalid plugin ptr.");
981  continue;
982  }
983  if (plugin->Name() == req.name && plugin->Type() ==req.type)
984  {
985  plugin->LoadConfig(config, "");
986  plugin->SetVisible(req.visible);
987 
988  if (req.draw_order > 0)
989  {
990  display.first->setData(Qt::UserRole, QVariant(req.draw_order - 1.1));
991  ui_.configs->sortItems();
992 
993  ReorderDisplays();
994  }
995  else if (req.draw_order < 0)
996  {
997  display.first->setData(Qt::UserRole, QVariant(ui_.configs->count() + req.draw_order + 0.1));
998  ui_.configs->sortItems();
999 
1000  ReorderDisplays();
1001  }
1002 
1003  resp.success = true;
1004 
1005  return true;
1006  }
1007  }
1008 
1009  try
1010  {
1011  MapvizPluginPtr plugin =
1012  CreateNewDisplay(req.name, req.type, req.visible, false, req.draw_order);
1013  plugin->LoadConfig(config, "");
1014  plugin->DrawIcon();
1015  resp.success = true;
1016  }
1017  catch (const pluginlib::LibraryLoadException& e)
1018  {
1019  ROS_ERROR("%s", e.what());
1020  resp.success = false;
1021  resp.message = "Failed to load display plug-in.";
1022  }
1023 
1024  return true;
1025 }
1026 
1027 void Mapviz::Hover(double x, double y, double scale)
1028 {
1029  if (ui_.statusbar->isVisible())
1030  {
1031  if (scale == 0)
1032  {
1033  xy_pos_label_->setVisible(false);
1034  lat_lon_pos_label_->setVisible(false);
1035  return;
1036  }
1037 
1038  int32_t precision = static_cast<int32_t>(std::ceil(std::max(0.0, std::log10(1.0 / scale))));
1039 
1040  QString text = ui_.fixedframe->currentText();
1041  if (text.isEmpty() || text == "/")
1042  {
1043  text = "fixed";
1044  }
1045  text += ": ";
1046 
1047  std::ostringstream x_ss;
1048  x_ss << std::fixed << std::setprecision(precision);
1049  x_ss << x;
1050  text += x_ss.str().c_str();
1051 
1052  text += ", ";
1053 
1054  std::ostringstream y_ss;
1055  y_ss << std::fixed << std::setprecision(precision);
1056  y_ss << y;
1057  text += y_ss.str().c_str();
1058 
1059  xy_pos_label_->setText(text);
1060  xy_pos_label_->setVisible(true);
1061  xy_pos_label_->update();
1062 
1066  ui_.fixedframe->currentText().toStdString()) &&
1069  ui_.fixedframe->currentText().toStdString(),
1070  transform))
1071  {
1072  tf::Vector3 point(x, y, 0);
1073  point = transform * point;
1074 
1075  QString lat_lon_text = "lat/lon: ";
1076 
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))));
1079 
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();
1084 
1085  lat_lon_text += ", ";
1086 
1087  double lon_scale = (1.0 / (111111.0 * std::cos(point.y() * swri_math_util::_deg_2_rad))) * scale;
1088  int32_t lon_precision = static_cast<int32_t>(std::ceil(std::max(0.0, std::log10(1.0 / lon_scale))));
1089 
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();
1094 
1095  lat_lon_pos_label_->setText(lat_lon_text);
1096  lat_lon_pos_label_->setVisible(true);
1097  lat_lon_pos_label_->update();
1098  }
1099  else if (lat_lon_pos_label_->isVisible())
1100  {
1101  lat_lon_pos_label_->setVisible(false);
1102  }
1103  }
1104 }
1105 
1107  const std::string& name,
1108  const std::string& type,
1109  bool visible,
1110  bool collapsed,
1111  int draw_order)
1112 {
1113  ConfigItem* config_item = new ConfigItem();
1114 
1115  config_item->SetName(name.c_str());
1116 
1117  std::string real_type = type;
1118  if (real_type == "mapviz_plugins/mutlires_image")
1119  {
1120  // The "multires_image" plugin was originally accidentally named "mutlires_image".
1121  // Loading a mapviz config file that still has the old name would normally cause it
1122  // to crash, so this will check for and correct it.
1123  real_type = "mapviz_plugins/multires_image";
1124  }
1125 
1126 
1127  ROS_INFO("creating: %s", real_type.c_str());
1128  MapvizPluginPtr plugin = loader_->createInstance(real_type.c_str());
1129 
1130  // Setup configure widget
1131  config_item->SetWidget(plugin->GetConfigWidget(this));
1132  plugin->SetIcon(config_item->ui_.icon);
1133 
1134  plugin->Initialize(tf_, canvas_);
1135  plugin->SetType(real_type.c_str());
1136  plugin->SetName(name);
1137  plugin->SetNode(*node_);
1138  plugin->SetVisible(visible);
1139 
1140  if (draw_order == 0)
1141  {
1142  plugin->SetDrawOrder(ui_.configs->count());
1143  }
1144  else if (draw_order > 0)
1145  {
1146  plugin->SetDrawOrder(std::min(ui_.configs->count(), draw_order - 1));
1147  }
1148  else if (draw_order < 0)
1149  {
1150  plugin->SetDrawOrder(std::max(0, ui_.configs->count() + draw_order + 1));
1151  }
1152 
1153  QString pretty_type(real_type.c_str());
1154  pretty_type = pretty_type.split('/').last();
1155  config_item->SetType(pretty_type);
1156  QListWidgetItem* item = new PluginConfigListItem();
1157  config_item->SetListItem(item);
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()));
1164 
1165  if (real_type == "mapviz_plugins/image")
1166  {
1167  // This is a little kludgey because we're relying on hard-coding a
1168  // plugin type here... feel free to suggest a better way.
1169  // If the default image transport has changed, we want to notify all of our
1170  // image plugins of it so that they will resubscribe appropriately.
1171  connect(this, SIGNAL(ImageTransportChanged()),
1172  plugin.get(), SLOT(Resubscribe()));
1173  }
1174 
1175  if (draw_order == 0)
1176  {
1177  ui_.configs->addItem(item);
1178  }
1179  else
1180  {
1181  ui_.configs->insertItem(plugin->DrawOrder(), item);
1182  }
1183 
1184  ui_.configs->setItemWidget(item, config_item);
1185  ui_.configs->UpdateIndices();
1186 
1187  // Add plugin to canvas
1188  plugin->SetTargetFrame(ui_.fixedframe->currentText().toStdString());
1189  plugin->SetUseLatestTransforms(ui_.uselatesttransforms->isChecked());
1190  plugins_[item] = plugin;
1191  canvas_->AddPlugin(plugin, -1);
1192 
1193  config_item->ToggleDraw(visible);
1194 
1195  if (collapsed)
1196  config_item->Hide();
1197 
1198  ReorderDisplays();
1199 
1200  return plugin;
1201 }
1202 
1203 void Mapviz::ToggleShowPlugin(QListWidgetItem* item, bool visible)
1204 {
1205  ROS_INFO("Toggle show plugin");
1206 
1207  if (plugins_.count(item) == 1)
1208  {
1209  plugins_[item]->SetVisible(visible);
1210  }
1211  canvas_->UpdateView();
1212 }
1213 
1214 void Mapviz::FixedFrameSelected(const QString& text)
1215 {
1216  if (!updating_frames_)
1217  {
1218  ROS_INFO("Fixed frame selected: %s", text.toStdString().c_str());
1219  if (canvas_ != NULL)
1220  {
1221  canvas_->SetFixedFrame(text.toStdString().c_str());
1222  }
1223  }
1224 }
1225 
1226 void Mapviz::TargetFrameSelected(const QString& text)
1227 {
1228  if (!updating_frames_)
1229  {
1230  ROS_INFO("Target frame selected: %s", text.toStdString().c_str());
1231 
1232  if (canvas_ != NULL)
1233  {
1234  canvas_->SetTargetFrame(text.toStdString().c_str());
1235  }
1236  }
1237 }
1238 
1240 {
1242 }
1243 
1245 {
1247 }
1248 
1250 {
1251  canvas_->ToggleRotate90(on);
1252 }
1253 
1255 {
1257 }
1258 
1260 {
1261  if (on)
1262  {
1263  ui_.configdock->show();
1264  }
1265  else
1266  {
1267  ui_.configdock->hide();
1268  }
1269 
1270  AdjustWindowSize();
1271 }
1272 
1274 {
1275  ui_.statusbar->setVisible(on);
1276 
1277  AdjustWindowSize();
1278 }
1279 
1281 {
1282  if (on)
1283  {
1284  ui_.actionShow_Status_Bar->setChecked(true);
1285  }
1286 
1287  screenshot_button_->setVisible(on);
1288  rec_button_->setVisible(on);
1289  stop_button_->setVisible(on);
1290  spacer1_->setVisible(on);
1291  spacer2_->setVisible(on);
1292  spacer3_->setVisible(on);
1293 }
1294 
1296 {
1297  stop_button_->setEnabled(true);
1298 
1299  if (on)
1300  {
1301  rec_button_->setIcon(QIcon(":/images/media-playback-pause.png"));
1302  rec_button_->setToolTip("Pause recording video of display canvas");
1303  if (!vid_writer_->isRecording())
1304  {
1305  // Lock the window size.
1306  AdjustWindowSize();
1307 
1308  canvas_->CaptureFrames(true);
1309 
1310  std::string posix_time = boost::posix_time::to_iso_string(ros::WallTime::now().toBoost());
1311  boost::replace_all(posix_time, ".", "_");
1312  std::string filename = capture_directory_ + "/mapviz_" + posix_time + ".avi";
1313  boost::replace_all(filename, "~", getenv("HOME"));
1314 
1315 
1316  if (!vid_writer_->initializeWriter(filename, canvas_->width(), canvas_->height()))
1317  {
1318  ROS_ERROR("Failed to open video file for writing.");
1319  StopRecord();
1320  return;
1321  }
1322 
1323  ROS_INFO("Writing video to: %s", filename.c_str());
1324  ui_.statusbar->showMessage("Recording video to " + QString::fromStdString(filename));
1325 
1326  canvas_->updateGL();
1327  }
1328 
1329  record_timer_.start(1000.0 / 30.0);
1330  }
1331  else
1332  {
1333  rec_button_->setIcon(QIcon(":/images/media-record.png"));
1334  rec_button_->setToolTip("Continue recording video of display canvas");
1335  record_timer_.stop();
1336  }
1337 }
1338 
1339 void Mapviz::SetImageTransport(QAction* transport_action)
1340 {
1341  std::string transport = transport_action->text().toStdString();
1342  ROS_INFO("Setting %s to %s", IMAGE_TRANSPORT_PARAM.c_str(), transport.c_str());
1343  node_->setParam(IMAGE_TRANSPORT_PARAM, transport);
1344 
1345  Q_EMIT(ImageTransportChanged());
1346 }
1347 
1349 {
1350  QList<QAction*> actions = image_transport_menu_->actions();
1351 
1352  std::string current_transport;
1353  node_->param<std::string>(IMAGE_TRANSPORT_PARAM, current_transport, "raw");
1354  Q_FOREACH(QAction* action, actions)
1355  {
1356  if (action->text() == QString::fromStdString(current_transport))
1357  {
1358  action->setChecked(true);
1359  return;
1360  }
1361  }
1362 
1363  ROS_WARN("%s param was set to an unrecognized value: %s",
1364  IMAGE_TRANSPORT_PARAM.c_str(), current_transport.c_str());
1365 }
1366 
1368 {
1369  // We need to store the data inside a QImage in order to emit it as a
1370  // signal.
1371  // Note that the QImage here is set to "ARGB32", but it is actually BGRA.
1372  // Qt doesn't have a comparable BGR format, and the cv::VideoWriter this
1373  // is going to expects BGR format, but it'd be a waste for us to convert
1374  // to RGB and then back to BGR.
1375  QImage frame(canvas_->width(), canvas_->height(), QImage::Format_ARGB32);
1376  if (canvas_->CopyCaptureBuffer(frame.bits()))
1377  {
1378  Q_EMIT(FrameGrabbed(frame));
1379  }
1380  else
1381  {
1382  ROS_ERROR("Failed to get capture buffer");
1383  }
1384 }
1385 
1387 {
1389 }
1390 
1392 {
1393  rec_button_->setChecked(false);
1394  stop_button_->setEnabled(false);
1395 
1396  record_timer_.stop();
1397  if (vid_writer_)
1398  {
1399  vid_writer_->stop();
1400  }
1401  canvas_->CaptureFrames(false);
1402 
1403  ui_.statusbar->showMessage(QString(""));
1404  rec_button_->setToolTip("Start recording video of display canvas");
1405 
1406  AdjustWindowSize();
1407 }
1408 
1410 {
1411  canvas_->CaptureFrame(true);
1412 
1413  std::vector<uint8_t> frame;
1414  if (canvas_->CopyCaptureBuffer(frame))
1415  {
1416  cv::Mat image(canvas_->height(), canvas_->width(), CV_8UC4, &frame[0]);
1417  cv::Mat screenshot;
1418  cvtColor(image, screenshot, CV_BGRA2BGR);
1419 
1420  cv::flip(screenshot, screenshot, 0);
1421 
1422  std::string posix_time = boost::posix_time::to_iso_string(ros::WallTime::now().toBoost());
1423  boost::replace_all(posix_time, ".", "_");
1424  std::string filename = capture_directory_ + "/mapviz_" + posix_time + ".png";
1425  boost::replace_all(filename, "~", getenv("HOME"));
1426 
1427  ROS_INFO("Writing screenshot to: %s", filename.c_str());
1428  ui_.statusbar->showMessage("Saved image to " + QString::fromStdString(filename));
1429 
1430  cv::imwrite(filename, screenshot);
1431  }
1432  else
1433  {
1434  ROS_ERROR("Failed to take screenshot.");
1435  }
1436 }
1437 
1439 {
1440  for (int i = 0; i < ui_.configs->count(); i++)
1441  {
1442  QListWidgetItem* item = ui_.configs->item(i);
1443  ConfigItem* widget = static_cast<ConfigItem*>(ui_.configs->itemWidget(item));
1444  if (widget) {
1445  // Make sure the ConfigItem in the QListWidgetItem we're getting really
1446  // exists; if this method is called before it's been initialized, it would
1447  // cause a crash.
1448  item->setSizeHint(widget->sizeHint());
1449  }
1450  }
1451 }
1452 
1454 {
1455  QListWidgetItem* item = ui_.configs->takeItem(ui_.configs->currentRow());
1456  RemoveDisplay(item);
1457 }
1458 
1459 void Mapviz::RemoveDisplay(QListWidgetItem* item)
1460 {
1461  ROS_INFO("Remove display ...");
1462 
1463  if (item)
1464  {
1465  canvas_->RemovePlugin(plugins_[item]);
1466  plugins_[item] = MapvizPluginPtr();
1467 
1468  delete item;
1469  }
1470 }
1471 
1473 {
1474  while (ui_.configs->count() > 0)
1475  {
1476  ROS_INFO("Remove display ...");
1477 
1478  QListWidgetItem* item = ui_.configs->takeItem(0);
1479 
1480  canvas_->RemovePlugin(plugins_[item]);
1481  plugins_[item] = MapvizPluginPtr();
1482 
1483  delete item;
1484  }
1485 }
1486 
1488 {
1489  ROS_INFO("Reorder displays");
1490  for (int i = 0; i < ui_.configs->count(); i++)
1491  {
1492  plugins_[ui_.configs->item(i)]->SetDrawOrder(i);
1493  }
1495 }
1496 
1497 void Mapviz::SelectBackgroundColor(const QColor &color)
1498 {
1499  background_ = color;
1501 }
1502 
1504 {
1505  QFileDialog dialog(this, "Select Capture Directory");
1506  dialog.setFileMode(QFileDialog::DirectoryOnly);
1507 
1508  dialog.exec();
1509 
1510  if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
1511  {
1512  capture_directory_ = dialog.selectedFiles().first().toStdString();
1513  }
1514 }
1515 
1517 {
1518  ROS_INFO("Mapviz Profiling Data");
1519  meas_spin_.printInfo("ROS SpinOnce()");
1520  for (auto& display: plugins_)
1521  {
1522  MapvizPluginPtr plugin = display.second;
1523  if (plugin)
1524  {
1525  plugin->PrintMeasurements();
1526  }
1527  }
1528 }
1529 }
void SetWidget(QWidget *widget)
Definition: config_item.cpp:90
VideoWriter * vid_writer_
Definition: mapviz.h:167
std::vector< std::string > getLoadableTransports() const
void ToggleShowPlugin(QListWidgetItem *item, bool visible)
Definition: mapviz.cpp:1203
#define NULL
void CaptureFrames(bool enabled)
Definition: map_canvas.h:111
string name
bool force_480p_
Definition: mapviz.h:161
void FixedFrameSelected(const QString &text)
Definition: mapviz.cpp:1214
static const long double _deg_2_rad
filename
void AdjustWindowSize()
Definition: mapviz.cpp:468
void SpinOnce()
Definition: mapviz.cpp:328
QColor background_
Definition: mapviz.h:163
void FrameGrabbed(QImage)
MapCanvas * canvas_
Definition: mapviz.h:177
void OpenConfig()
Definition: mapviz.cpp:863
bool LoadFile(const std::string &path, YAML::Node &yaml)
bool initialized_
Definition: mapviz.h:159
void HandleProfileTimer()
Definition: mapviz.cpp:1516
static const std::string _wgs84_frame
void RemovePlugin(MapvizPluginPtr plugin)
Definition: map_canvas.cpp:463
Ui::configitem ui_
Definition: config_item.h:64
QPushButton * stop_button_
Definition: mapviz.h:152
void printInfo(const std::string &name) const
Definition: stopwatch.h:87
void ToggleUseLatestTransforms(bool on)
Definition: mapviz.cpp:1239
bool resizable_
Definition: mapviz.h:162
QLabel * xy_pos_label_
Definition: mapviz.h:144
void UpdateSizeHints()
Definition: mapviz.cpp:1438
bool LoadMap(const std::map< std::string, std::string > &dict, YAML::Node &yaml)
void CaptureFrame(bool force=false)
Definition: map_canvas.cpp:181
bool initializeWriter(const std::string &directory, int width, int height)
void Initialize(boost::shared_ptr< tf::TransformListener > tf=boost::make_shared< tf::TransformListener >())
void Recenter()
Definition: mapviz.cpp:1386
QWidget * spacer1_
Definition: mapviz.h:147
QTimer save_timer_
Definition: mapviz.h:140
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
config
void InitializeTf(boost::shared_ptr< tf::TransformListener > tf)
Definition: map_canvas.cpp:101
void CaptureVideoFrame()
Definition: mapviz.cpp:1367
void ToggleEnableAntialiasing(bool on)
Definition: map_canvas.cpp:439
void SetFixedFrame(const std::string &frame)
Definition: map_canvas.cpp:409
float OffsetX() const
Definition: map_canvas.h:84
QPushButton * recenter_button_
Definition: mapviz.h:150
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void ToggleRecord(bool on)
Definition: mapviz.cpp:1295
void ToggleCaptureTools(bool on)
Definition: mapviz.cpp:1280
void StopRecord()
Definition: mapviz.cpp:1391
void ClearDisplays()
Definition: mapviz.cpp:1472
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
void SetBackground(const QColor &color)
Definition: map_canvas.h:105
QWidget * spacer2_
Definition: mapviz.h:148
void UpdateImageTransportMenu()
Definition: mapviz.cpp:1348
virtual void closeEvent(QCloseEvent *event)
Definition: mapviz.cpp:210
pluginlib::ClassLoader< MapvizPlugin > * loader_
Definition: mapviz.h:176
void ToggleEnableAntialiasing(bool on)
Definition: mapviz.cpp:1254
void Force480p(bool on)
Definition: mapviz.cpp:436
Stopwatch meas_spin_
Definition: mapviz.h:180
MapvizPluginPtr CreateNewDisplay(const std::string &name, const std::string &type, bool visible, bool collapsed, int draw_order=0)
Definition: mapviz.cpp:1106
void ToggleDraw(bool toggled)
Definition: config_item.cpp:56
virtual void showEvent(QShowEvent *event)
Definition: mapviz.cpp:205
bool SupportsTransform(const std::string &target_frame, const std::string &source_frame) const
std::map< QListWidgetItem *, MapvizPluginPtr > plugins_
Definition: mapviz.h:178
void ToggleRotate90(bool on)
Definition: mapviz.cpp:1249
ros::ServiceServer add_display_srv_
Definition: mapviz.h:172
void ImageTransportChanged()
void SetResizable(bool on)
Definition: mapviz.cpp:452
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
void Force720p(bool on)
Definition: mapviz.cpp:420
QTimer spin_timer_
Definition: mapviz.h:139
bool FindValue(const YAML::Node &node, const std::string &name)
bool is_standalone_
Definition: mapviz.h:158
void Save(const std::string &filename)
Definition: mapviz.cpp:752
void ToggleConfigPanel(bool on)
Definition: mapviz.cpp:1259
void Screenshot()
Definition: mapviz.cpp:1409
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
QTimer profile_timer_
Definition: mapviz.h:142
char ** argv_
Definition: mapviz.h:156
void SetName(QString name)
Definition: config_item.cpp:78
QWidget * spacer3_
Definition: mapviz.h:149
ROSCPP_DECL bool ok()
void ReorderDisplays()
Definition: mapviz.cpp:1487
boost::shared_ptr< MapvizPlugin > MapvizPluginPtr
TFSIMD_FORCE_INLINE const tfScalar & x() const
void SaveConfig()
Definition: mapviz.cpp:878
void ClearHistory()
Definition: mapviz.cpp:911
void ToggleRotate90(bool on)
Definition: map_canvas.cpp:434
void SelectNewDisplay()
Definition: mapviz.cpp:919
static const std::string IMAGE_TRANSPORT_PARAM
Definition: mapviz.h:204
boost::shared_ptr< tf::TransformListener > tf_
Definition: mapviz.h:173
void TargetFrameSelected(const QString &text)
Definition: mapviz.cpp:1226
void Initialize()
Definition: mapviz.cpp:223
std::string capture_directory_
Definition: mapviz.h:165
void ToggleFixOrientation(bool on)
Definition: mapviz.cpp:1244
action
Mapviz(bool is_standalone, int argc, char **argv, QWidget *parent=0, Qt::WindowFlags flags=0)
Definition: mapviz.cpp:80
QLabel * lat_lon_pos_label_
Definition: mapviz.h:145
Ui::mapviz ui_
Definition: mapviz.h:134
void SetListItem(QListWidgetItem *item)
Definition: config_item.h:60
void SetOffsetY(float y)
Definition: map_canvas.h:99
void SelectBackgroundColor(const QColor &color)
Definition: mapviz.cpp:1497
void Open(const std::string &filename)
Definition: mapviz.cpp:513
static const QString MAPVIZ_CONFIG_FILE
Definition: mapviz.h:203
bool GetTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, Transform &transform) const
static const QString ROS_WORKSPACE_VAR
Definition: mapviz.h:202
QTimer frame_timer_
Definition: mapviz.h:138
float ViewScale() const
Definition: map_canvas.h:83
QPushButton * rec_button_
Definition: mapviz.h:151
QThread video_thread_
Definition: mapviz.h:166
bool CopyCaptureBuffer(uchar *buffer)
Definition: map_canvas.h:124
void SetOffsetX(float x)
Definition: map_canvas.h:93
bool AddDisplay(AddMapvizDisplay::Request &req, AddMapvizDisplay::Response &resp)
Definition: mapviz.cpp:958
void ToggleUseLatestTransforms(bool on)
Definition: map_canvas.cpp:449
static WallTime now()
void SetType(QString type)
Definition: config_item.cpp:84
void SetTargetFrame(const std::string &frame)
Definition: map_canvas.cpp:419
bool getParam(const std::string &key, std::string &s) const
ros::NodeHandle * node_
Definition: mapviz.h:171
void SetCaptureDirectory()
Definition: mapviz.cpp:1503
void Hover(double x, double y, double scale)
Definition: mapviz.cpp:1027
void ToggleFixOrientation(bool on)
Definition: map_canvas.cpp:429
QTimer record_timer_
Definition: mapviz.h:141
bool updating_frames_
Definition: mapviz.h:169
void SetImageTransport(QAction *transport_action)
Definition: mapviz.cpp:1339
swri_transform_util::TransformManager tf_manager_
Definition: mapviz.h:174
void RemoveDisplay()
Definition: mapviz.cpp:1453
void UpdateFrames()
Definition: mapviz.cpp:342
void SetViewScale(float scale)
Definition: map_canvas.h:87
ROSCPP_DECL void spinOnce()
void AutoSave()
Definition: mapviz.cpp:829
void AddPlugin(MapvizPluginPtr plugin, int order)
Definition: map_canvas.cpp:458
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
QPushButton * screenshot_button_
Definition: mapviz.h:153
float OffsetY() const
Definition: map_canvas.h:85
void ToggleStatusBar(bool on)
Definition: mapviz.cpp:1273
bool force_720p_
Definition: mapviz.h:160
QMenu * image_transport_menu_
Definition: mapviz.h:136


mapviz
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:08