CMapMerger.cpp
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+
9  */
10 
12 
13 using namespace mrpt::graphslam;
14 using namespace mrpt::graphslam::detail;
15 using namespace mrpt_msgs;
16 using namespace mrpt::maps;
17 using namespace mrpt::slam;
18 using namespace mrpt::math;
19 using namespace mrpt::system;
20 using namespace mrpt::poses;
21 using namespace mrpt::opengl;
22 using namespace ros;
23 using namespace nav_msgs;
24 using namespace std;
25 
26 // helper methods
27 
29 
32  mrpt::gui::CDisplayWindow3D* win, std::string obj_name = "")
33 {
34  using namespace mrpt::opengl;
35  ASSERT_(win);
36  bool res = true;
37  COpenGLScene::Ptr& scene = win->get3DSceneAndLock();
38 
39  if (obj_name.empty())
40  {
41  cout << "Clearing entire scene." << endl;
42  scene.reset();
43  }
44  else
45  {
46  CRenderizable::Ptr obj = scene->getByName(obj_name);
47  if (obj)
48  {
49  scene->removeObject(obj);
50  }
51  else
52  {
53  res = false;
54  }
55  }
56 
57  win->unlockAccess3DScene();
58  win->forceRepaint();
59  return res;
60 }
61 
64  mrpt::graphslam::CWindowManager* win_manager, std::string obj_name = "")
65 {
66  ASSERT_(win_manager);
67  return removeObjectFrom3DScene(win_manager->win, obj_name);
68 }
69 
70 template <class RENDERIZABLE_OBJECT>
72  mrpt::gui::CDisplayWindow3D* win, const RENDERIZABLE_OBJECT& o,
73  const std::string& obj_name = "",
74  const mrpt::poses::CPose3D& obj_pose = EMPTY_POSE)
75 {
76  using namespace mrpt::opengl;
77 
78  COpenGLScene::Ptr& scene = win->get3DSceneAndLock();
79  CSetOfObjects::Ptr obj = o.getVisualization();
80 
81  obj->setPose(obj_pose);
82 
83  if (!obj_name.empty())
84  {
85  obj->setName(obj_name);
86  }
87 
88  scene->insert(obj);
89 
90  win->unlockAccess3DScene();
91  win->forceRepaint();
92 }
93 
94 void addAxis(mrpt::gui::CDisplayWindow3D* win)
95 {
96  using namespace mrpt;
97  using namespace mrpt::opengl;
98  ASSERT_(win);
99 
100  COpenGLScene::Ptr& scene = win->get3DSceneAndLock();
101  opengl::CAxis::Ptr obj =
102  opengl::CAxis::Create(-6, -6, -6, 6, 6, 6, 2, 2, true);
103  obj->setLocation(0, 0, 0);
104  scene->insert(obj);
105  win->unlockAccess3DScene();
106  win->forceRepaint();
107 }
108 
109 void addGrid(mrpt::gui::CDisplayWindow3D* win)
110 {
111  using namespace mrpt;
112  using namespace mrpt::opengl;
113  ASSERT_(win);
114 
115  COpenGLScene::Ptr& scene = win->get3DSceneAndLock();
116  opengl::CGridPlaneXY::Ptr obj =
117  opengl::CGridPlaneXY::Create(-20, 20, -20, 20, 0, 1);
118  obj->setColor(0.7, 0.7, 0.7);
119  obj->setLocation(0, 0, 0);
120  scene->insert(obj);
121 
122  win->unlockAccess3DScene();
123  win->forceRepaint();
124 }
125 
126 void addSupWidgets(mrpt::gui::CDisplayWindow3D* win)
127 {
128  ASSERT_(win);
129 
130  addAxis(win);
131  addGrid(win);
132 }
133 
135 
137  mrpt::system::COutputLogger* logger_in, ros::NodeHandle* nh_in)
138  : m_logger(logger_in),
139  m_nh(nh_in),
140  m_conn_manager(logger_in, nh_in),
141  m_queue_size(1),
142  quit_keypress1("q"),
143  quit_keypress2("Ctrl+c"),
144  map_merge_keypress("n"),
145  save_map_merging_results(true)
146 {
147  ASSERT_(m_nh);
148 
149  m_global_ns = "/map_merger";
150 
151  // GridMap Alignment options to be used in merging.
152  m_alignment_options.methodSelection = CGridMapAligner::amModifiedRANSAC;
155  m_alignment_options.min_ICP_goodness = 0.60;
156  m_alignment_options.maxKLd_for_merge = 0.90;
157  m_alignment_options.ransac_minSetSizeRatio = 0.40;
158  // m_alignment_options.loadFromConfigFileName(
159  //"/home/bergercookie/mrpt/share/mrpt/config_files/grid-matching/gridmatch_example.ini",
160  //"grid-match");
161  m_alignment_options.dumpToConsole();
162 
163  // initialize CDisplayWindow for fused map
165  m_fused_map_win_manager->win->setWindowTitle("Fused map");
167 }
168 
170  mrpt::graphslam::CWindowObserver* win_observer)
171 {
172  ASSERT_(win_observer);
173 
174  win_observer->registerKeystroke(quit_keypress1, "Finish execution");
175  win_observer->registerKeystroke(
176  map_merge_keypress, "Compute next available grid-merging");
177 }
178 
180 {
181  // delete the generated neighbors intances
182  for (neighbors_t::iterator n_it = m_neighbors.begin();
183  n_it != m_neighbors.end(); ++n_it)
184  {
185  delete m_neighbors_to_windows.at(*n_it)->observer;
186  delete m_neighbors_to_windows.at(*n_it)->win;
187  delete m_neighbors_to_windows.at(*n_it);
188  delete *n_it;
189  }
190 
191  // delete fused window manager
192  delete m_fused_map_win_manager->win;
193  delete m_fused_map_win_manager->observer;
195 
196  m_logger->logFmt(LVL_WARN, "Exiting...");
197 }
198 
200 {
201  MRPT_START;
202 
203  // get the new GraphSlamAgents
204  const GraphSlamAgents& nearby_slam_agents =
206  // m_logger->logFmt(LVL_DEBUG, "nearby_slam_agents size: %lu\n",
207  // static_cast<unsigned long>(nearby_slam_agents.list.size()));
208 
209  for (GraphSlamAgents::_list_type::const_iterator it =
210  nearby_slam_agents.list.begin();
211  it != nearby_slam_agents.list.end(); ++it)
212  {
213  const GraphSlamAgent& gsa = *it;
214 
215  // Is the current GraphSlamAgent already registered?
216  auto search = [gsa](const TNeighborAgentMapProps* neighbor) {
217  return (neighbor->agent == gsa);
218  };
219  typename neighbors_t::iterator n_it =
220  find_if(m_neighbors.begin(), m_neighbors.end(), search);
221 
222  if (n_it == m_neighbors.end())
223  { // current gsa not found, add it
224 
225  m_neighbors.push_back(
227  TNeighborAgentMapProps* latest_neighbor = m_neighbors.back();
228  latest_neighbor->setupComm();
229  m_logger->logFmt(
230  LVL_WARN,
231  "Initialized NeighborAgentMapProps instance for agent %s...",
232  latest_neighbor->agent.topic_namespace.data.c_str());
233 
234  // initialize the window
235  mrpt::graphslam::CWindowManager* win_manager = initWindowVisuals();
236  win_manager->win->setWindowTitle(
237  latest_neighbor->agent.topic_namespace.data);
238  m_neighbors_to_windows.insert(
239  make_pair(latest_neighbor, win_manager));
240  this->monitorKeystrokes(win_manager->observer);
241  }
242  } // end for all fetched GraphSlamAgents
243 
244  // run through the open windows - Exit if instructed
245  bool continue_exec = true;
246  for (map<TNeighborAgentMapProps*, CWindowManager*>::const_iterator it =
247  m_neighbors_to_windows.begin();
248  it != m_neighbors_to_windows.end(); ++it)
249  {
250  CWindowManager* win_manager = it->second;
251 
252  std::map<std::string, bool> events_map;
253  win_manager->observer->returnEventsStruct(&events_map);
254 
255  if (events_map.at(map_merge_keypress))
256  {
257  mergeMaps();
258  }
259  win_manager->win->forceRepaint();
260 
261  // continue or exit
262  if (!win_manager->isOpen() || events_map.at(quit_keypress1) ||
263  events_map.at(quit_keypress2))
264  {
265  continue_exec = false;
266  break;
267  }
268  }
269 
270  // Fetch the events for the main (fused map) window
271  if (continue_exec)
272  {
273  std::map<std::string, bool> events_map;
274  m_fused_map_win_manager->observer->returnEventsStruct(&events_map);
275  if (events_map.at(map_merge_keypress))
276  {
277  mergeMaps();
278  }
279  m_fused_map_win_manager->win->forceRepaint();
280  continue_exec = m_fused_map_win_manager->isOpen() &&
281  !events_map.at(quit_keypress1) &&
282  !events_map.at(quit_keypress2);
283  }
284 
285  return continue_exec;
286 
287  MRPT_END;
288 } // end of updateState
289 
291 {
292  MRPT_START;
293  m_logger->logFmt(LVL_WARN, "In mergeMaps.");
294 
295  CGridMapAligner gridmap_aligner;
296  gridmap_aligner.options = m_alignment_options;
297 
298  // List of maps that is to be filled.
299  maps_t mrpt_gridmaps;
300  trajectories_t mrpt_trajectories;
301 
302  // traverse Neighbor instances - get their nav_msgs::OccupancyGrid maps,
303  // trajectories
304  for (neighbors_t::const_iterator n_it = m_neighbors.begin();
305  n_it != m_neighbors.end(); ++n_it)
306  {
307  TNeighborAgentMapProps& neighbor = **n_it;
308  CWindowManager* neighbor_win_manager = m_neighbors_to_windows.at(*n_it);
309 
310  // reset visuals for each neighbor's window
311  removeObjectFrom3DScene(neighbor_win_manager->win);
312  addSupWidgets(neighbor_win_manager->win);
313 
314  if (neighbor.nav_map && neighbor.nav_robot_trajectory)
315  {
316  //
317  // map
318  //
319  COccupancyGridMap2D::Ptr map = COccupancyGridMap2D::Create();
320  m_logger->logFmt(
321  LVL_INFO, "Adding map of agent \"%s\" to the stack",
322  neighbor.agent.topic_namespace.data.c_str());
323  mrpt::ros1bridge::fromROS(*neighbor.nav_map, *map);
324 
325  // visualize map in corresponding window
326  addToWindow(neighbor_win_manager->win, *map);
327  mrpt_gridmaps.insert(make_pair(*n_it, map));
328 
329  //
330  // trajectory
331  //
332  CSetOfLines::Ptr curr_traj = CSetOfLines::Create();
333  curr_traj->setPose(CPose3D(0, 0, 0.3, 0, 0, 0));
334  curr_traj->setLineWidth(1.5);
335  curr_traj->setColor(TColorf(0, 0, 1));
336  // append a dummy line so that you can later use append using
337  // CSetOfLines::appendLienStrip method.
338  curr_traj->appendLine(
339  /* 1st */ 0, 0, 0,
340  /* 2nd */ 0, 0, 0);
341 
342  for (nav_msgs::Path::_poses_type::const_iterator pth_it =
343  neighbor.nav_robot_trajectory->poses.begin();
344  pth_it != neighbor.nav_robot_trajectory->poses.end(); ++pth_it)
345  {
346  curr_traj->appendLineStrip(
347  pth_it->pose.position.x, pth_it->pose.position.y, 0);
348  }
349  // visualize trajectory
350  {
351  COpenGLScene::Ptr& scene =
352  neighbor_win_manager->win->get3DSceneAndLock();
353  scene->insert(curr_traj);
354 
355  neighbor_win_manager->win->unlockAccess3DScene();
356  neighbor_win_manager->win->forceRepaint();
357  }
358 
359  // cache trajectory so that I can later visualize it in the fused
360  // map
361  {
362  // operate on copy of object - it is already inserted and used
363  // in another window
364  auto tmp = CSetOfLines::Ptr(
365  dynamic_cast<CSetOfLines*>(curr_traj->clone()));
366  auto curr_traj = mrpt::ptr_cast<CSetOfLines>::from(tmp);
367  ASSERT_(curr_traj);
368  mrpt_trajectories.insert(make_pair(&neighbor, curr_traj));
369  }
370 
371  } // end if both nav_map and nav_robot_trajectory exist
372  } // end for all neighbors traversal
373 
374  // join all gathered MRPT gridmaps
375  if (mrpt_gridmaps.size() >= 2)
376  {
377  m_logger->logFmt(
378  LVL_INFO, "Executing map merging for [%lu] gridmaps",
379  static_cast<unsigned long>(mrpt_gridmaps.size()));
380  int merge_counter = 0;
381 
382  // save results
383  std::string output_dir_fname = "map_merger_results";
385  {
386  m_logger->logFmt(
387  LVL_INFO, "Saving map-merging results to \"%s\"",
388  output_dir_fname.c_str());
389 
390  // mrpt::system::TTimeStamp cur_date(getCurrentTime());
391  // string cur_date_str(dateTimeToString(cur_date));
392  // string
393  // cur_date_validstr(fileNameStripInvalidChars(cur_date_str));
394  // std::string output_dir_fname = "map_merger_results_" +
395  // cur_date_validstr;
396  bool does_exist = directoryExists(output_dir_fname);
397  if (does_exist)
398  {
399  deleteFilesInDirectory(output_dir_fname);
400  }
401  else
402  {
403  m_logger->logFmt(
404  LVL_INFO, "Initializing gridmaps output directory.\n");
405  createDirectory(output_dir_fname);
406  }
407  }
408 
409  // initialize final fused map
410  COccupancyGridMap2D::Ptr fused_map = COccupancyGridMap2D::Create();
411  fused_map->copyMapContentFrom(*mrpt_gridmaps.begin()->second);
412 
413  ASSERT_(fused_map);
414 
415  {
416  // clear the fused map visuals
417  COpenGLScene::Ptr& fused_scene =
418  m_fused_map_win_manager->win->get3DSceneAndLock();
419  fused_scene.reset();
420  m_logger->logFmt(LVL_INFO, "Clearing the fused map visuals");
421 
423 
424  // add first map
425  CSetOfObjects::Ptr first_map_obj = fused_map->getVisualization();
426 
427  // each map in the fused display will have a different name - based
428  // on the topic namespace
429  first_map_obj->setName(format(
430  "map_%s", mrpt_gridmaps.begin()
431  ->first->agent.topic_namespace.data.c_str()));
432  fused_scene->insert(first_map_obj);
433 
434  m_fused_map_win_manager->win->unlockAccess3DScene();
435  m_fused_map_win_manager->win->forceRepaint();
436  }
437 
438  // save the first gridmap
440  {
441  stringstream ss;
442  ss << output_dir_fname << "/"
443  << "map" << merge_counter;
444  (mrpt_gridmaps.begin()->second)
445  ->saveMetricMapRepresentationToFile(ss.str());
446  }
447 
448  // value at which to display each new gridmap in the display window
449  double off_z = 1;
450  double off_z_step = 1;
451 
452  // map of TNeighborAgentMapProps* to a corresponding flag specifying
453  // whether the COccupancyGridMap is correctly aligned can thus can be
454  // used.
455  neighbor_to_is_used_t neighbor_to_is_used;
456  // first gridmap frame coincedes with the global frame - used anyway
457 
458  // map from TNeighborAgentMapProps* to a corresponding relative pose
459  // with regards to the global fused map
460  neighbor_to_rel_pose_t neighbor_to_rel_pose;
461  for (neighbors_t::const_iterator n_it = m_neighbors.begin();
462  n_it != m_neighbors.end(); ++n_it)
463  {
464  neighbor_to_is_used[*n_it] = false;
465  neighbor_to_rel_pose[*n_it] = CPose2D();
466  }
467 
468  // mark first as used - one trajectory should be there anyway
469  neighbor_to_is_used[*m_neighbors.begin()] = true;
470 
471  // for all captured gridmaps - except the first
472  for (maps_t::iterator m_it = std::next(mrpt_gridmaps.begin());
473  m_it != mrpt_gridmaps.end(); ++m_it, ++merge_counter)
474  {
475  TNeighborAgentMapProps* curr_neighbor = m_it->first;
476  COccupancyGridMap2D* curr_gridmap = m_it->second.get();
477 
478  // run alignment procedure
479  CGridMapAligner::TReturnInfo results;
480  CPosePDFGaussian init_estim;
481  m_logger->logFmt(
482  LVL_INFO, "Trying to align the maps, initial estimation: %s",
483  init_estim.mean.asString().c_str());
484 
485  TMetricMapAlignmentResult alignRes;
486 
487  const CPosePDF::Ptr pdf_tmp = gridmap_aligner.AlignPDF(
488  fused_map.get(), curr_gridmap, init_estim, alignRes);
489 
490  const auto run_time = alignRes.executionTime;
491 
492  m_logger->logFmt(LVL_INFO, "Elapsed Time: %f", run_time);
493 
494  CPosePDFSOG::Ptr pdf_out = CPosePDFSOG::Create();
495  pdf_out->copyFrom(*pdf_tmp);
496 
497  CPose2D pose_out;
498  CMatrixDouble33 cov_out;
499  pdf_out->getMostLikelyCovarianceAndMean(cov_out, pose_out);
500 
501  // dismiss this?
502  if (results.goodness > 0.999 || isEssentiallyZero(pose_out))
503  {
504  continue;
505  }
506 
507  neighbor_to_rel_pose.at(curr_neighbor) = pose_out;
508  neighbor_to_is_used.at(curr_neighbor) = true;
509 
510  m_logger->logFmt(
511  LVL_INFO, "%s\n",
512  getGridMapAlignmentResultsAsString(*pdf_tmp, results).c_str());
513 
514  // save current gridmap
516  {
517  stringstream ss;
518  ss << output_dir_fname << "/"
519  << "map" << merge_counter;
520  curr_gridmap->saveMetricMapRepresentationToFile(ss.str());
521  }
522 
523  // Add current map to the fused map visualization
524  {
525  COpenGLScene::Ptr fused_scene =
526  m_fused_map_win_manager->win->get3DSceneAndLock();
527 
528  // insert current map
529  m_logger->logFmt(
530  LVL_INFO,
531  "Adding map to the fused map visualiztion using "
532  "transformation %s",
533  pose_out.asString().c_str());
534  CSetOfObjects::Ptr curr_map_obj =
535  curr_gridmap->getVisualization();
536 
537  curr_map_obj->setName(format(
538  "map_%s",
539  curr_neighbor->agent.topic_namespace.data.c_str()));
540  curr_map_obj->setPose(pose_out + CPose3D(0, 0, off_z, 0, 0, 0));
541  off_z += off_z_step;
542  fused_scene->insert(curr_map_obj);
543 
544  m_fused_map_win_manager->win->unlockAccess3DScene();
545  m_fused_map_win_manager->win->forceRepaint();
546  }
547 
548  // TODO - merge current gridmap into the fused map by using the
549  // found transformation
550 
551  } // end for all gridmaps
552 
553  TColorManager traj_color_mngr; // different color to each trajectory
554  // Traverse and add all the trajectories to the fused map visualization
555  for (trajectories_t::const_iterator it = mrpt_trajectories.begin();
556  it != mrpt_trajectories.end(); ++it)
557  {
558  TNeighborAgentMapProps* curr_neighbor = it->first;
559 
560  if (!neighbor_to_is_used.at(curr_neighbor))
561  {
562  m_logger->logFmt(
563  LVL_WARN,
564  "Skipping visualizing trajectory of agent %s in the fused "
565  "map",
566  curr_neighbor->agent.topic_namespace.data.c_str());
567  continue;
568  }
569 
570  CSetOfLines::Ptr curr_traj = it->second;
571  m_logger->logFmt(
572  LVL_WARN, "Adding #%lu lines...",
573  static_cast<unsigned long>(curr_traj->getLineCount()));
574 
575  // set the pose of the trajectory
576  CPose3D rel_pose(neighbor_to_rel_pose.at(curr_neighbor));
577  // elevate by the last used offset
578  rel_pose += CPose3D(0, 0, off_z, 0, 0, 0);
579 
580  curr_traj->setColor(traj_color_mngr.getNextTColorf());
581  curr_traj->setPose(rel_pose);
582  curr_traj->setName(format(
583  "traj_%s", curr_neighbor->agent.topic_namespace.data.c_str()));
584  { // save 3D Scene
585  COpenGLScene::Ptr fused_scene =
586  m_fused_map_win_manager->win->get3DSceneAndLock();
587  fused_scene->insert(curr_traj);
588 
589  m_fused_map_win_manager->win->unlockAccess3DScene();
590  m_fused_map_win_manager->win->forceRepaint();
591  }
592  }
593 
594  { // save the COpenGLScene
595 
596  COpenGLScene::Ptr fused_scene =
597  m_fused_map_win_manager->win->get3DSceneAndLock();
598  std::string fname = output_dir_fname + "/" + "output_scene.3DScene";
599  fused_scene->saveToFile(fname);
600 
601  m_fused_map_win_manager->win->unlockAccess3DScene();
602  m_fused_map_win_manager->win->forceRepaint();
603  }
604 
605  // save final fused map
606  // TODO
607 
608  } // end if gridmap.size() >= 2
609  MRPT_END;
610 }
611 
613 {
614  mrpt::graphslam::CWindowManager* win_manager = new CWindowManager();
615  this->initWindowVisuals(win_manager);
616  return win_manager;
617 }
618 
619 void CMapMerger::initWindowVisuals(mrpt::graphslam::CWindowManager* win_manager)
620 {
621  using namespace mrpt::opengl;
622  using namespace mrpt::gui;
623  using namespace mrpt::graphslam;
624  ASSERT_(win_manager);
625 
626  CWindowObserver* win_observer = new CWindowObserver();
627  CDisplayWindow3D* win =
628  new CDisplayWindow3D("GraphSlam building procedure", 800, 600);
629  win->setPos(400, 200);
630  win_observer->observeBegin(*win);
631  {
632  COpenGLScene::Ptr& scene = win->get3DSceneAndLock();
633  COpenGLViewport::Ptr main_view = scene->getViewport("main");
634  win_observer->observeBegin(*main_view);
635  win->unlockAccess3DScene();
636  }
637 
638  // pass the window and the observer pointers to the CWindowManager instance
639  win_manager->setCDisplayWindow3DPtr(win);
640  win_manager->setWindowObserverPtr(win_observer);
641 
642  addSupWidgets(win_manager->win);
643  m_logger->logFmt(LVL_DEBUG, "Initialized CDisplayWindow3D...");
644 }
mrpt::graphslam::CMapMerger::trajectories_t
std::map< TNeighborAgentMapProps *, mrpt::opengl::CSetOfLines::Ptr > trajectories_t
Robot trajectory visual object type.
Definition: CMapMerger.h:65
mrpt::graphslam::CMapMerger::maps_t
std::map< TNeighborAgentMapProps *, COccupancyGridMap2D::Ptr > maps_t
Definition: CMapMerger.h:58
mrpt::graphslam::detail::CConnectionManager::getNearbySlamAgents
void getNearbySlamAgents(mrpt_msgs::GraphSlamAgents *agents_vec, bool ignore_self=true)
Fill the given vector with the SLAM Agents that the current manager can see and communicate with.
Definition: CConnectionManager.cpp:108
mrpt::graphslam::CMapMerger::m_logger
mrpt::system::COutputLogger * m_logger
Definition: CMapMerger.h:89
mrpt::graphslam::CMapMerger::m_global_ns
std::string m_global_ns
Topic namespace under which current node is going to be publishing.
Definition: CMapMerger.h:96
mrpt::graphslam::CMapMerger::initWindowVisuals
mrpt::graphslam::CWindowManager * initWindowVisuals()
Definition: CMapMerger.cpp:612
ros
mrpt::graphslam::CMapMerger::neighbor_to_is_used_t
std::map< TNeighborAgentMapProps *, bool > neighbor_to_is_used_t
Definition: CMapMerger.h:59
addSupWidgets
void addSupWidgets(mrpt::gui::CDisplayWindow3D *win)
Definition: CMapMerger.cpp:126
addGrid
void addGrid(mrpt::gui::CDisplayWindow3D *win)
Definition: CMapMerger.cpp:109
mrpt::graphslam::CMapMerger::CMapMerger
CMapMerger(mrpt::system::COutputLogger *logger_in, ros::NodeHandle *nh_in)
Definition: CMapMerger.cpp:136
mrpt::graphslam::CMapMerger::m_conn_manager
mrpt::graphslam::detail::CConnectionManager m_conn_manager
Definition: CMapMerger.h:91
mrpt::graphslam::CMapMerger::save_map_merging_results
bool save_map_merging_results
Definition: CMapMerger.h:109
EMPTY_POSE
const mrpt::poses::CPose3D EMPTY_POSE
Definition: CMapMerger.h:38
mrpt
Definition: CConnectionManager.h:31
mrpt::graphslam::CMapMerger::map_merge_keypress
std::string map_merge_keypress
Definition: CMapMerger.h:107
mrpt::graphslam::detail::isEssentiallyZero
bool isEssentiallyZero(const mrpt::poses::CPose2D &p)
Definition: common.cpp:46
mrpt::graphslam::CMapMerger::updateState
bool updateState()
Query and fetch the list of new graphSLAM agents.
Definition: CMapMerger.cpp:199
removeObjectFrom3DScene
bool removeObjectFrom3DScene(mrpt::gui::CDisplayWindow3D *win, std::string obj_name="")
Definition: CMapMerger.cpp:31
mrpt::graphslam
Definition: CConnectionManager.h:33
mrpt::graphslam::TNeighborAgentMapProps::agent
const mrpt_msgs::GraphSlamAgent & agent
Pointer to the GraphSlamAgent instance of the neighbor.
Definition: TNeighborAgentMapProps.h:57
mrpt::graphslam::TNeighborAgentMapProps
Struct holding a COccupancyGridMap2D (as well as subscribers for updating it) for a specific running ...
Definition: TNeighborAgentMapProps.h:30
mrpt::graphslam::CMapMerger::monitorKeystrokes
void monitorKeystrokes(mrpt::graphslam::CWindowObserver *win_observer)
Compact method for monitoring the given keystrokes for the given observer.
Definition: CMapMerger.cpp:169
mrpt::graphslam::CMapMerger::m_neighbors_to_windows
std::map< TNeighborAgentMapProps *, CWindowManager * > m_neighbors_to_windows
Definition: CMapMerger.h:88
mrpt::graphslam::CMapMerger::mergeMaps
void mergeMaps()
Definition: CMapMerger.cpp:290
mrpt::graphslam::CMapMerger::quit_keypress2
std::string quit_keypress2
Definition: CMapMerger.h:106
search
ROSCPP_DECL bool search(const std::string &key, std::string &result)
CMapMerger.h
mrpt::graphslam::detail::getGridMapAlignmentResultsAsString
std::string getGridMapAlignmentResultsAsString(const mrpt::poses::CPosePDF &pdf, const mrpt::slam::CGridMapAligner::TReturnInfo &ret_info)
Definition: common.cpp:20
mrpt::graphslam::CMapMerger::m_fused_map_win_manager
mrpt::graphslam::CWindowManager * m_fused_map_win_manager
Definition: CMapMerger.h:111
mrpt::graphslam::CMapMerger::quit_keypress1
std::string quit_keypress1
Definition: CMapMerger.h:105
mrpt::graphslam::CMapMerger::m_alignment_options
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
Definition: CMapMerger.h:103
mrpt::graphslam::CMapMerger::~CMapMerger
~CMapMerger()
Definition: CMapMerger.cpp:179
std
mrpt::graphslam::detail
Definition: CConnectionManager.h:35
mrpt::graphslam::TNeighborAgentMapProps::nav_robot_trajectory
nav_msgs::Path::ConstPtr nav_robot_trajectory
Trajectory of the correspondign agent - in ROS form.
Definition: TNeighborAgentMapProps.h:61
mrpt::math
Definition: CGraphSlamEngine_MR_impl.h:19
mrpt::graphslam::CMapMerger::neighbor_to_rel_pose_t
std::map< TNeighborAgentMapProps *, mrpt::poses::CPose2D > neighbor_to_rel_pose_t
Definition: CMapMerger.h:61
addAxis
void addAxis(mrpt::gui::CDisplayWindow3D *win)
Definition: CMapMerger.cpp:94
mrpt::graphslam::CMapMerger::m_neighbors
neighbors_t m_neighbors
CConnectionManager instance for fetching the running graphSLAM agents.
Definition: CMapMerger.h:87
mrpt::graphslam::TNeighborAgentMapProps::setupComm
void setupComm()
Definition: TNeighborAgentMapProps.cpp:67
mrpt::graphslam::CMapMerger::m_nh
ros::NodeHandle * m_nh
Definition: CMapMerger.h:90
mrpt::graphslam::TNeighborAgentMapProps::nav_map
nav_msgs::OccupancyGrid::ConstPtr nav_map
Map generated by the corresponding agent - in ROS form.
Definition: TNeighborAgentMapProps.h:59
ros::NodeHandle
addToWindow
void addToWindow(mrpt::gui::CDisplayWindow3D *win, const RENDERIZABLE_OBJECT &o, const std::string &obj_name="", const mrpt::poses::CPose3D &obj_pose=EMPTY_POSE)
Definition: CMapMerger.cpp:71


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Sep 19 2024 02:26:31