CGraphSlamHandler_ROS_impl.h
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 #pragma once
10 
11 namespace mrpt { namespace graphslam { namespace apps {
12 
13 // static member variables
14 template<class GRAPH_T>
15 const std::string CGraphSlamHandler_ROS<GRAPH_T>::sep_header(40, '=');
16 
17 template<class GRAPH_T>
18 const std::string CGraphSlamHandler_ROS<GRAPH_T>::sep_subheader(20, '-');
19 
20 // Ctor
21 template<class GRAPH_T>
23  mrpt::utils::COutputLogger* logger,
24  TUserOptionsChecker<GRAPH_T>* options_checker,
25  ros::NodeHandle* nh_in):
26  parent_t(logger, options_checker, /*enable_visuals=*/ false),
27  m_nh(nh_in)
28 {
29  using namespace mrpt::obs;
30 
31  ASSERT_(m_nh);
32 
33  // TODO - does this affect?
34  // Previous value = 0;
35  m_queue_size = 1;
36 
37  // variables initialization/assignment
38  m_pub_seq = 0;
39  m_stats_pub_seq = 0;
40  this->resetReceivedFlags();
41 
42  // measurements initialization
43  m_mrpt_odom = CObservationOdometry::Create();
44  m_mrpt_odom->hasEncodersInfo = false;
45  m_mrpt_odom->hasVelocities = false;
47 
49 
50  // Thu Nov 3 23:36:49 EET 2016, Nikos Koukis
51  // WARNING: ROS Server Parameters have not been read yet. Make sure you know
52  // what to initialize at this stage!
53 }
54 
55 template<class GRAPH_T>
57 
58 template<class GRAPH_T>
60  this->readROSParameters();
61 
62  ASSERT_(!this->m_ini_fname.empty());
63  parent_t::readConfigFname(this->m_ini_fname);
64 
65 }
66 
67 template<class GRAPH_T>
69  using namespace mrpt::utils;
70 
71  // misc
72  {
73  std::string ns = "misc/";
74 
75  // enable/disable visuals
76  bool m_disable_MRPT_visuals;
77  m_nh->param<bool>(ns + "disable_MRPT_visuals", m_disable_MRPT_visuals, false);
78  this->m_enable_visuals = !m_disable_MRPT_visuals;
79 
80  // verbosity level
81  int lvl;
82  m_nh->param<int>(ns + "verbosity",
83  lvl,
84  static_cast<int>(LVL_INFO));
85  m_min_logging_level = static_cast<VerbosityLevel>(lvl);
86  this->m_logger->setMinLoggingLevel(m_min_logging_level);
87  }
88  // deciders, optimizer
89  {
90  std::string ns = "deciders_optimizers/";
91  m_nh->param<std::string>(ns + "NRD", m_node_reg, "CFixedIntervalsNRD");
92  m_nh->param<std::string>(ns + "ERD", m_edge_reg, "CICPCriteriaERD");
93  m_nh->param<std::string>(ns + "GSO", m_optimizer, "CLevMarqGSO");
94  }
95  // filenames
96  {
97  std::string ns = "files/";
98 
99  // configuration file - mandatory
100  std::string config_param_path = ns + "config";
101  bool found_config = m_nh->getParam(ns + "config", this->m_ini_fname);
102  ASSERTMSG_(found_config,
103  mrpt::format(
104  "Configuration file was not set. Set %s and try again.\nExiting...",
105  config_param_path.c_str()));
106 
107  // ground-truth file
108  m_nh->getParam(ns + "ground_truth", this->m_gt_fname);
109  }
110 
111  // TF Frame IDs
112  // names of the frames of the corresponding robot parts
113  {
114  std::string ns = "frame_IDs/";
115 
116  m_nh->param<std::string>(ns + "anchor_frame" , m_anchor_frame_id, "map");
117  m_nh->param<std::string>(ns + "base_link_frame" , m_base_link_frame_id, "base_link");
118  m_nh->param<std::string>(ns + "odometry_frame" , m_odom_frame_id, "odom");
119 
120  }
121 
122  // ASSERT that the given user options are valid
123  // Fill the TuserOptionsChecker related structures
124  this->m_options_checker->createDeciderOptimizerMappings();
125  this->m_options_checker->populateDeciderOptimizerProperties();
126  this->verifyUserInput();
127 
128  this->m_logger->logFmt(LVL_DEBUG,
129  "Successfully read parameters from ROS Parameter Server");
130 
131  // Visuals initialization
132  if (this->m_enable_visuals) {
133  this->initVisualization();
134  }
135 } // end of readROSParameters
136 
137 template<class GRAPH_T>
139 
140 template<class GRAPH_T>
142 
143  this->m_logger->logFmt(LVL_WARN,
144  "Initializing CGraphSlamEngine_ROS instance...");
145  this->m_engine = new CGraphSlamEngine_ROS<GRAPH_T>(
146  m_nh,
147  this->m_ini_fname,
148  /*rawlog_fname=*/ "",
149  this->m_gt_fname,
150  this->m_win_manager,
151  this->m_options_checker->node_regs_map[m_node_reg](),
152  this->m_options_checker->edge_regs_map[m_edge_reg](),
153  this->m_options_checker->optimizers_map[m_optimizer]());
154  this->m_logger->logFmt(LVL_WARN,
155  "Successfully initialized CGraphSlamEngine_ROS instance.");
156 
157 }
158 
159 template<class GRAPH_T>
161 
162  this->m_options_checker->node_regs_map[m_node_reg]();
163  this->m_options_checker->edge_regs_map[m_edge_reg]();
164  this->m_options_checker->optimizers_map[m_optimizer]();
165 
166  this->m_logger->logFmt(LVL_WARN,
167  "Initializing CGraphSlamEngine_MR instance...");
168  this->m_engine = new CGraphSlamEngine_MR<GRAPH_T>(
169  m_nh,
170  this->m_ini_fname,
171  /*rawlog_fname=*/ "",
172  this->m_gt_fname,
173  this->m_win_manager,
174  this->m_options_checker->node_regs_map[m_node_reg](),
175  this->m_options_checker->edge_regs_map[m_edge_reg](),
176  this->m_options_checker->optimizers_map[m_optimizer]());
177  this->m_logger->logFmt(LVL_WARN,
178  "Successfully initialized CGraphSlamEngine_MR instance.");
179 
180 }
181 
182 template<class GRAPH_T>
184  using namespace mrpt::utils;
185  using namespace std;
186 
187  ASSERT_(str_out);
188 
189  stringstream ss("");
190 
191 
192  ss << "ROS Parameters: " << endl;
193  ss << sep_header << endl;
194  ss << endl;
195 
196  ss << "Deciders / Optimizers = " << endl;
197  ss << sep_subheader << endl;
198  ss << "Node Registration Decider = " << m_node_reg << endl;
199  ss << "Edge Registration Decider = " << m_edge_reg << endl;
200  ss << "GraphSLAM Optimizer = " << m_optimizer << endl;
201  ss << endl;
202 
203  ss << "Filenames: " << endl;
204  ss << sep_subheader << endl;
205  ss << "Configuration .ini file = " << this->m_ini_fname << endl;
206  ss << "Ground truth filename = " << (!this->m_gt_fname.empty()
207  ? this->m_gt_fname : "NONE")
208  << endl;
209  ss << endl;
210 
211  ss << "Miscellaneous: " << endl;
212  ss << sep_subheader << endl;
213  ss << "Enable MRPT visuals? = " <<
214  (this->m_enable_visuals? "TRUE" : "FALSE")
215  << endl;
216  ss << "Logging verbosity Level = " <<
217  COutputLogger::logging_levels_to_names
218 #if MRPT_VERSION>=0x199
219  ()
220 #endif
221  [m_min_logging_level] << endl;;
222  ss << endl;
223 
224  *str_out = ss.str();
225 }
226 
227 template<class GRAPH_T>
229  ASSERT_(str_out);
230 
231  // ros parameters
232  std::string ros_params("");
233  this->getROSParameters(&ros_params);
234  std::string mrpt_params("");
235  parent_t::getParamsAsString(&mrpt_params);
236 
237  *str_out += ros_params;
238  *str_out += "\n\n";
239  *str_out += mrpt_params;
240 
241  // various parameters
242 }
243 
244 template<class GRAPH_T>
246  std::string params;
247  this->getParamsAsString(&params);
248  return params;
249 }
250 
251 template<class GRAPH_T>
253  using namespace std;
254  parent_t::printParams();
255  cout << this->getParamsAsString() << endl;
256 
257 
258 }
259 
260 template<class GRAPH_T>
262  this->m_logger->logFmt(LVL_DEBUG, "Verifying user input...");
263 
264 
265  // verify the NRD, ERD, GSO parameters
266  bool node_success, edge_success, optimizer_success;
267  bool failed = false;
268 
269  node_success =
270  this->m_options_checker->checkRegistrationDeciderExists(
271  m_node_reg, "node");
272  edge_success =
273  this->m_options_checker->checkRegistrationDeciderExists(
274  m_edge_reg, "edge");
275  optimizer_success =
276  this->m_options_checker->checkOptimizerExists(
277  m_optimizer);
278 
279  if (!node_success) {
280  this->m_logger->logFmt(LVL_ERROR,
281  "\nNode Registration Decider \"%s\" is not available",
282  m_node_reg.c_str());
283  this->m_options_checker->dumpRegistrarsToConsole("node");
284  failed = true;
285  }
286  if (!edge_success) {
287  this->m_logger->logFmt(LVL_ERROR,
288  "\nEdge Registration Decider \"%s\" is not available.",
289  m_edge_reg.c_str());
290  this->m_options_checker->dumpRegistrarsToConsole("edge");
291  failed = true;
292  }
293  if (!optimizer_success) {
294  this->m_logger->logFmt(LVL_ERROR,
295  "\ngraphSLAM Optimizser \"%s\" is not available.",
296  m_optimizer.c_str());
297  this->m_options_checker->dumpOptimizersToConsole();
298  failed = true;
299  }
300  ASSERT_(!failed);
301 
302  // verify that the path to the files is correct
303  // .ini file
304  bool ini_exists = system::fileExists(this->m_ini_fname);
305  ASSERTMSG_(ini_exists,
306  format(
307  "\n.ini configuration file \"%s\"doesn't exist. "
308  "Please specify a valid pathname.\nExiting...\n",
309  this->m_ini_fname.c_str()));
310  // ground-truth file
311  if (!this->m_gt_fname.empty()) {
312  bool gt_exists = system::fileExists(this->m_gt_fname);
313  ASSERTMSG_(gt_exists,
314  format(
315  "\nGround truth file \"%s\"doesn't exist."
316  "Either unset the corresponding ROS parameter or specify a valid pathname.\n"
317  "Exiting...\n",
318  this->m_gt_fname.c_str()));
319  }
320 
321 } // end of verifyUserInput
322 
323 template<class GRAPH_T>
325 
326  this->m_logger->logFmt(LVL_INFO,
327  "Setting up ROS-related subscribers, publishers, services...");
328 
329  // setup subscribers, publishers, services...
330  this->setupSubs();
331  this->setupPubs();
332  this->setupSrvs();
333 
334  // fetch the static geometrical transformations
335  //this->readStaticTFs();
336 
337 } // end of setupComm
338 
339 template<class GRAPH_T>
341  this->m_logger->logFmt(LVL_INFO, "Setting up the subscribers...");
342 
343  // setup the names
344  std::string ns = "input/";
345 
346  m_odom_topic = ns + "odom";
347  m_laser_scan_topic = ns + "laser_scan";
348 
349  // odometry
350  m_odom_sub = m_nh->subscribe<nav_msgs::Odometry>(
351  m_odom_topic,
352  m_queue_size,
353  &self_t::sniffOdom, this);
354 
355  // laser_scans
356  m_laser_scan_sub = m_nh->subscribe<sensor_msgs::LaserScan>(
358  m_queue_size,
359  &self_t::sniffLaserScan, this);
360 
361  // camera
362  // TODO
363 
364  // 3D point clouds
365  // TODO
366 
367 } // end of setupSubs
368 
369 template<class GRAPH_T>
371  this->m_logger->logFmt(LVL_INFO, "Setting up the publishers...");
372 
373  // setup the names
374  std::string ns = "feedback/";
375 
376  m_curr_robot_pos_topic = ns + "robot_position";
377  m_robot_trajectory_topic = ns + "robot_trajectory";
378  m_robot_tr_poses_topic = ns + "robot_tr_poses";
379  m_odom_trajectory_topic = ns + "odom_trajectory";
380  m_gridmap_topic = ns + "gridmap";
381  m_stats_topic = ns + "graphslam_stats";
382 
383  // setup the publishers
384 
385  // agent estimated position
386  m_curr_robot_pos_pub = m_nh->advertise<geometry_msgs::PoseStamped>(
388  m_queue_size);
389  m_robot_trajectory_pub = m_nh->advertise<nav_msgs::Path>(
391  m_queue_size);
392  m_robot_tr_poses_pub = m_nh->advertise<geometry_msgs::PoseArray>(
394  m_queue_size);
395 
396  // odometry nav_msgs::Path
397  m_odom_path.header.seq = 0;
398  m_odom_path.header.stamp = ros::Time::now();
399  m_odom_path.header.frame_id = m_anchor_frame_id;
400 
401  m_odom_trajectory_pub = m_nh->advertise<nav_msgs::Path>(
403  m_queue_size);
404 
405  // generated gridmap
406  m_gridmap_pub = m_nh->advertise<nav_msgs::OccupancyGrid>(
408  m_queue_size,
409  /*latch=*/true);
410 
411  m_stats_pub = m_nh->advertise<mrpt_msgs::GraphSlamStats>(
413  m_queue_size,
414  /*latch=*/true);
415 
416 } // end of setupPubs
417 
418 template<class GRAPH_T>
420  this->m_logger->logFmt(LVL_INFO, "Setting up the services...");
421 
422  // TODO Error statistics
423 
424 } // end of setupSrvs
425 
426 template<class GRAPH_T>
428  using namespace mrpt::utils;
429  using namespace std;
430 
431  MRPT_START;
432  bool ret_val = true;
433 
434  ros::Time timestamp = ros::Time::now();
435 
436  // current MRPT robot pose
437  pose_t mrpt_pose = this->m_engine->getCurrentRobotPosEstimation();
438 
439  //
440  // convert pose_t to corresponding geometry_msg::TransformStamped
441  // anchor frame <=> base_link
442  //
443  geometry_msgs::TransformStamped anchor_base_link_transform;
444  anchor_base_link_transform.header.stamp = ros::Time::now();
445  anchor_base_link_transform.header.frame_id = m_anchor_frame_id;
446  anchor_base_link_transform.child_frame_id = m_base_link_frame_id;
447 
448  // translation
449  anchor_base_link_transform.transform.translation.x = mrpt_pose.x();
450  anchor_base_link_transform.transform.translation.y = mrpt_pose.y();
451  anchor_base_link_transform.transform.translation.z = 0;
452 
453  // rotation
454  anchor_base_link_transform.transform.rotation =
455  tf::createQuaternionMsgFromYaw(mrpt_pose.phi());
456 
457  // TODO - potential error in the rotation, investigate this
458  m_broadcaster.sendTransform(anchor_base_link_transform);
459 
460  // anchor frame <=> odom frame
461  //
462  // make sure that we have received odometry information in the first
463  // place...
464  // the corresponding field would be initialized
465  if (!m_anchor_odom_transform.child_frame_id.empty()) {
467  }
468 
469  // set an arrow indicating the current orientation of the robot
470  {
471  geometry_msgs::PoseStamped geom_pose;
472  geom_pose.header.stamp = timestamp;
473  geom_pose.header.seq = m_pub_seq;
474  geom_pose.header.frame_id = m_anchor_frame_id; // with regards to base_link...
475 
476  // position
477  mrpt_bridge::convert(mrpt_pose, geom_pose.pose);
478  m_curr_robot_pos_pub.publish(geom_pose);
479  }
480 
481  // robot trajectory
482  // publish the trajectory of the robot
483  {
484  this->m_logger->logFmt(LVL_DEBUG,
485  "Publishing the current robot trajectory");
486  typename GRAPH_T::global_poses_t graph_poses;
487 #if MRPT_VERSION>=0x199
488  graph_poses = this->m_engine->getRobotEstimatedTrajectory();
489 #else
490  this->m_engine->getRobotEstimatedTrajectory(&graph_poses);
491 #endif
492 
493  nav_msgs::Path path;
494 
495  // set the header
496  path.header.stamp = timestamp;
497  path.header.seq = m_pub_seq;
498  path.header.frame_id = m_anchor_frame_id;
499 
500  //
501  // fill in the pose as well as the nav_msgs::Path at the same time.
502  //
503 
504  geometry_msgs::PoseArray geom_poses;
505  geom_poses.header.stamp = timestamp;
506  geom_poses.header.frame_id = m_anchor_frame_id;
507 
508  for (auto n_cit = graph_poses.begin();
509  n_cit != graph_poses.end();
510  ++n_cit) {
511 
512  geometry_msgs::PoseStamped geom_pose_stamped;
513  geometry_msgs::Pose geom_pose;
514 
515  // grab the pose - convert to geometry_msgs::Pose format
516  const pose_t& mrpt_pose = n_cit->second;
517  mrpt_bridge::convert(mrpt_pose, geom_pose);
518  geom_poses.poses.push_back(geom_pose);
519  geom_pose_stamped.pose = geom_pose;
520 
521  // edit the header
522  geom_pose_stamped.header.stamp = timestamp;
523  geom_pose_stamped.header.seq = m_pub_seq;
524  geom_pose_stamped.header.frame_id = m_anchor_frame_id;
525 
526  path.poses.push_back(geom_pose_stamped);
527  }
528 
529  // publish only on new node addition
530  if (this->m_engine->getGraph().nodeCount() > m_graph_nodes_last_size) {
531  m_robot_tr_poses_pub.publish(geom_poses);
533  }
534  }
535 
536  // Odometry trajectory - nav_msgs::Path
538 
539  // generated gridmap
540  // publish only on new node addition
541  if (this->m_engine->getGraph().nodeCount() > m_graph_nodes_last_size) {
542  std_msgs::Header h;
543  mrpt::system::TTimeStamp mrpt_time;
544  mrpt::maps::COccupancyGridMap2D::Ptr mrpt_gridmap =
545  mrpt::maps::COccupancyGridMap2D::Create();
546  this->m_engine->getMap(mrpt_gridmap, &mrpt_time);
547 
548  // timestamp
549  mrpt_bridge::convert(mrpt_time, h.stamp);
550  h.seq = m_pub_seq;
551  h.frame_id = m_anchor_frame_id;
552 
553  // nav gridmap
554  nav_msgs::OccupancyGrid nav_gridmap;
555  mrpt_bridge::convert(*mrpt_gridmap, nav_gridmap, h);
556  m_gridmap_pub.publish(nav_gridmap);
557  }
558 
559  // GraphSlamStats publishing
560  {
561  mrpt_msgs::GraphSlamStats stats;
562  stats.header.seq = m_stats_pub_seq++;
563 
564  map<string, int> node_stats;
565  map<string, int> edge_stats;
566  vector<double> def_energy_vec;
567  mrpt::system::TTimeStamp mrpt_time;
568 
569  this->m_engine->getGraphSlamStats(&node_stats,
570  &edge_stats,
571  &mrpt_time);
572 
573  // node/edge count
574  stats.nodes_total = node_stats["nodes_total"];
575  stats.edges_total = edge_stats["edges_total"];
576  if (edge_stats.find("ICP2D") != edge_stats.end()) {
577  stats.edges_ICP2D = edge_stats["ICP2D"];
578  }
579  if (edge_stats.find("ICP3D") != edge_stats.end()) {
580  stats.edges_ICP3D = edge_stats["ICP3D"];
581  }
582  if (edge_stats.find("Odometry") != edge_stats.end()) {
583  stats.edges_odom = edge_stats["Odometry"];
584  }
585  stats.loop_closures = edge_stats["loop_closures"];
586 
587  // SLAM evaluation metric
588  this->m_engine->getDeformationEnergyVector(
589  &stats.slam_evaluation_metric);
590 
591  mrpt_bridge::convert(mrpt_time, stats.header.stamp);
592 
593  m_stats_pub.publish(stats);
594 
595  }
596 
597 
598 
599  // update the last known size
600  m_graph_nodes_last_size = this->m_engine->getGraph().nodeCount();
601  m_pub_seq++;
602 
603  if (this->m_enable_visuals) {
604  ret_val = this->queryObserverForEvents();
605  }
606 
607  return ret_val;
608  MRPT_END;
609 } // end of usePublishersBroadcasters
610 
611 template<class GRAPH_T>
613  const sensor_msgs::LaserScan::ConstPtr& ros_laser_scan) {
614  using namespace std;
615  using namespace mrpt::utils;
616  using namespace mrpt::obs;
617 
618  this->m_logger->logFmt(
619  LVL_DEBUG,
620  "sniffLaserScan: Received a LaserScan msg. Converting it to MRPT format...");
621 
622  // build the CObservation2DRangeScan
623  m_mrpt_laser_scan = CObservation2DRangeScan::Create();
624  mrpt::poses::CPose3D rel_pose; // pose is 0.
625  mrpt_bridge::convert(*ros_laser_scan, rel_pose, *m_mrpt_laser_scan);
626 
627  m_received_laser_scan = true;
628  CObservation::Ptr tmp = mrpt::ptr_cast<CObservation>::from(m_mrpt_laser_scan);
629  this->processObservation(tmp);
630 } // end of sniffLaserScan
631 
632 template<class GRAPH_T>
634  const nav_msgs::Odometry::ConstPtr& ros_odom) {
635  using namespace std;
636  using namespace mrpt::utils;
637  using namespace mrpt::obs;
638  using namespace mrpt::poses;
639 
640  this->m_logger->logFmt(
641  LVL_DEBUG,
642  "sniffOdom: Received an odometry msg. Converting it to MRPT format...");
643 
644  // update the odometry frame with regards to the anchor
645  {
646  // header
647  m_anchor_odom_transform.header.frame_id = m_anchor_frame_id;
648  m_anchor_odom_transform.header.stamp = ros_odom->header.stamp;
649  m_anchor_odom_transform.header.seq = ros_odom->header.seq;
650 
651  m_anchor_odom_transform.child_frame_id = m_odom_frame_id;
652 
653  //
654  // copy ros_odom ==> m_anchor_odom
655  //
656 
657  // translation
658  m_anchor_odom_transform.transform.translation.x =
659  ros_odom->pose.pose.position.x;
660  m_anchor_odom_transform.transform.translation.y =
661  ros_odom->pose.pose.position.y;
662  m_anchor_odom_transform.transform.translation.z =
663  ros_odom->pose.pose.position.z;
664 
665  // quaternion
666  m_anchor_odom_transform.transform.rotation =
667  ros_odom->pose.pose.orientation;
668  }
669 
670  // build and fill an MRPT CObservationOdometry instance for manipulation from
671  // the main algorithm
672  mrpt_bridge::convert(
673  /* src = */ ros_odom->header.stamp,
674  /* dst = */ m_mrpt_odom->timestamp);
675  mrpt_bridge::convert(
676  /* src = */ ros_odom->pose.pose,
677  /* dst = */ m_mrpt_odom->odometry);
678 
679  // if this is the first call odometry should be 0. Decrement by the
680  // corresponding offset
684  }
685  // decrement by the (constant) offset
686  m_mrpt_odom->odometry =
688 
689  // add to the overall odometry path
690  {
691  geometry_msgs::PoseStamped pose_stamped;
692  pose_stamped.header = ros_odom->header;
693 
694  // just for convenience - convert the MRPT pose back to PoseStamped
695  mrpt_bridge::convert(
696  /* src = */ m_mrpt_odom->odometry,
697  /* des = */ pose_stamped.pose);
698  m_odom_path.poses.push_back(pose_stamped);
699  }
700 
701  // print the odometry - for debugging reasons...
702  stringstream ss;
703  ss << "Odometry - MRPT format:\t" << m_mrpt_odom->odometry << endl;
704  this->m_logger->logFmt(LVL_DEBUG, "%s", ss.str().c_str());
705 
706  m_received_odom = true;
707  CObservation::Ptr tmp = mrpt::ptr_cast<mrpt::obs::CObservation>::from(m_mrpt_odom);
708  this->processObservation(tmp);
709 } // end of sniffOdom
710 
711 template<class GRAPH_T>
713  THROW_EXCEPTION("Method is not implemented yet.");
714 
715 }
716 template<class GRAPH_T>
718  THROW_EXCEPTION("Method is not implemented yet.");
719 
720 }
721 template<class GRAPH_T>
723  mrpt::obs::CObservation::Ptr& observ) {
724  using namespace mrpt::utils;
725  using namespace std;
726 
727  this->_process(observ);
728  this->resetReceivedFlags();
729 
730 }
731 
732 template<class GRAPH_T>
734  mrpt::obs::CObservation::Ptr& observ) {
735  using namespace mrpt::utils;
736 
737  //this->m_logger->logFmt(LVL_DEBUG, "Calling execGraphSlamStep...");
738 
739  // TODO - use the exit code of execGraphSlamStep to exit??
740  if (!this->m_engine->isPaused()) {
741  this->m_engine->execGraphSlamStep(observ, m_measurement_cnt);
743  }
744 }
745 
746 template<class GRAPH_T>
748  m_received_odom = false;
749  m_received_laser_scan = false;
750  m_received_camera = false;
751  m_received_point_cloud = false;
752 }
753 
754 } } } // end of namespaces
755 
void readROSParameters()
read configuration parameters from the ROS parameter server.
void readParams()
Read the problem configuration parameters.
void verifyUserInput()
Verify that the parameters read are valid and can be used with the CGraphSlamEngine_ROS instance...
void publish(const boost::shared_ptr< M > &message) const
bool usePublishersBroadcasters()
Provide feedback about the SLAM operation using ROS publilshers, update the registered frames using t...
CGraphSlamHandler_ROS(mrpt::utils::COutputLogger *logger, TUserOptionsChecker< GRAPH_T > *options_checker, ros::NodeHandle *nh_in)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void initEngine_ROS()
Initialize the CGraphslamEngine_* object.
bool m_first_time_in_sniff_odom
Initial offset of the received odometry.
size_t m_measurement_cnt
Total counter of the processed measurements.
mrpt::obs::CObservation2DRangeScan::Ptr m_mrpt_laser_scan
GRAPH_T::constraint_t::type_value pose_t
type of underlying poses (2D/3D).
VerbosityLevel m_min_logging_level
Minimum logging level for the current class instance.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
geometry_msgs::TransformStamped m_anchor_odom_transform
ros::NodeHandle * m_nh
Pointer to the Ros NodeHanle instance.
void sniffOdom(const nav_msgs::Odometry::ConstPtr &ros_odom)
Callback method for handling incoming odometry measurements in a ROS topic.
CGraphSlamHandler< GRAPH_T > parent_t
Handy parent type.
void _process(mrpt::obs::CObservation::Ptr &observ)
Low level wrapper for executing the CGraphSlamEngine_ROS::execGraphSlamStep method.
void sniffLaserScan(const sensor_msgs::LaserScan::ConstPtr &ros_laser_scan)
Callback method for handling incoming LaserScans objects in a ROS topic.
void setupComm()
Wrapper method around the protected setup* class methods.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void getROSParameters(std::string *str_out)
Fill in the given string with the parameters that have been read from the ROS parameter server...
void sendTransform(const geometry_msgs::TransformStamped &transform)
nav_msgs::Path m_odom_path
Odometry path of the robot. Handy mostly for visualization reasons.
std::string m_anchor_frame_id
Frame that the robot starts from. In a single-robot SLAM setup this can be set to the world frame...
void printParams()
Print in a compact manner the overall problem configuration parameters.
int m_pub_seq
Times a messge has been published => usePublishersBroadcasters method is called.
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
bool getParam(const std::string &key, std::string &s) const
void resetReceivedFlags()
Reset the flags indicating whether we have received new data (odometry, laser scans etc...
static Time now()
mrpt::obs::CObservationOdometry::Ptr m_mrpt_odom
Received laser scan - converted into MRPT CObservation* format.
void processObservation(mrpt::obs::CObservation::Ptr &observ)
Process an incoming measurement.
int m_queue_size
ROS topic publisher standard queue size.
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM ...


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 19:37:48