00001
00002
00003
00004
00005
00006
00007
00008
00009 #pragma once
00010
00011 namespace mrpt { namespace graphslam { namespace apps {
00012
00013
00014 template<class GRAPH_T>
00015 const std::string CGraphSlamHandler_ROS<GRAPH_T>::sep_header(40, '=');
00016
00017 template<class GRAPH_T>
00018 const std::string CGraphSlamHandler_ROS<GRAPH_T>::sep_subheader(20, '-');
00019
00020
00021 template<class GRAPH_T>
00022 CGraphSlamHandler_ROS<GRAPH_T>::CGraphSlamHandler_ROS(
00023 mrpt::utils::COutputLogger* logger,
00024 TUserOptionsChecker<GRAPH_T>* options_checker,
00025 ros::NodeHandle* nh_in):
00026 parent_t(logger, options_checker, false),
00027 m_nh(nh_in)
00028 {
00029 using namespace mrpt::obs;
00030
00031 ASSERT_(m_nh);
00032
00033
00034
00035 m_queue_size = 1;
00036
00037
00038 m_pub_seq = 0;
00039 m_stats_pub_seq = 0;
00040 this->resetReceivedFlags();
00041
00042
00043 m_mrpt_odom = CObservationOdometry::Create();
00044 m_mrpt_odom->hasEncodersInfo = false;
00045 m_mrpt_odom->hasVelocities = false;
00046 m_first_time_in_sniff_odom = true;
00047
00048 m_measurement_cnt = 0;
00049
00050
00051
00052
00053 }
00054
00055 template<class GRAPH_T>
00056 CGraphSlamHandler_ROS<GRAPH_T>::~CGraphSlamHandler_ROS() { }
00057
00058 template<class GRAPH_T>
00059 void CGraphSlamHandler_ROS<GRAPH_T>::readParams() {
00060 this->readROSParameters();
00061
00062 ASSERT_(!this->m_ini_fname.empty());
00063 parent_t::readConfigFname(this->m_ini_fname);
00064
00065 }
00066
00067 template<class GRAPH_T>
00068 void CGraphSlamHandler_ROS<GRAPH_T>::readROSParameters() {
00069 using namespace mrpt::utils;
00070
00071
00072 {
00073 std::string ns = "misc/";
00074
00075
00076 bool m_disable_MRPT_visuals;
00077 m_nh->param<bool>(ns + "disable_MRPT_visuals", m_disable_MRPT_visuals, false);
00078 this->m_enable_visuals = !m_disable_MRPT_visuals;
00079
00080
00081 int lvl;
00082 m_nh->param<int>(ns + "verbosity",
00083 lvl,
00084 static_cast<int>(LVL_INFO));
00085 m_min_logging_level = static_cast<VerbosityLevel>(lvl);
00086 this->m_logger->setMinLoggingLevel(m_min_logging_level);
00087 }
00088
00089 {
00090 std::string ns = "deciders_optimizers/";
00091 m_nh->param<std::string>(ns + "NRD", m_node_reg, "CFixedIntervalsNRD");
00092 m_nh->param<std::string>(ns + "ERD", m_edge_reg, "CICPCriteriaERD");
00093 m_nh->param<std::string>(ns + "GSO", m_optimizer, "CLevMarqGSO");
00094 }
00095
00096 {
00097 std::string ns = "files/";
00098
00099
00100 std::string config_param_path = ns + "config";
00101 bool found_config = m_nh->getParam(ns + "config", this->m_ini_fname);
00102 ASSERTMSG_(found_config,
00103 mrpt::format(
00104 "Configuration file was not set. Set %s and try again.\nExiting...",
00105 config_param_path.c_str()));
00106
00107
00108 m_nh->getParam(ns + "ground_truth", this->m_gt_fname);
00109 }
00110
00111
00112
00113 {
00114 std::string ns = "frame_IDs/";
00115
00116 m_nh->param<std::string>(ns + "anchor_frame" , m_anchor_frame_id, "map");
00117 m_nh->param<std::string>(ns + "base_link_frame" , m_base_link_frame_id, "base_link");
00118 m_nh->param<std::string>(ns + "odometry_frame" , m_odom_frame_id, "odom");
00119
00120 }
00121
00122
00123
00124 this->m_options_checker->createDeciderOptimizerMappings();
00125 this->m_options_checker->populateDeciderOptimizerProperties();
00126 this->verifyUserInput();
00127
00128 this->m_logger->logFmt(LVL_DEBUG,
00129 "Successfully read parameters from ROS Parameter Server");
00130
00131
00132 if (this->m_enable_visuals) {
00133 this->initVisualization();
00134 }
00135 }
00136
00137 template<class GRAPH_T>
00138 void CGraphSlamHandler_ROS<GRAPH_T>::readStaticTFs() { }
00139
00140 template<class GRAPH_T>
00141 void CGraphSlamHandler_ROS<GRAPH_T>::initEngine_ROS() {
00142
00143 this->m_logger->logFmt(LVL_WARN,
00144 "Initializing CGraphSlamEngine_ROS instance...");
00145 this->m_engine = new CGraphSlamEngine_ROS<GRAPH_T>(
00146 m_nh,
00147 this->m_ini_fname,
00148 "",
00149 this->m_gt_fname,
00150 this->m_win_manager,
00151 this->m_options_checker->node_regs_map[m_node_reg](),
00152 this->m_options_checker->edge_regs_map[m_edge_reg](),
00153 this->m_options_checker->optimizers_map[m_optimizer]());
00154 this->m_logger->logFmt(LVL_WARN,
00155 "Successfully initialized CGraphSlamEngine_ROS instance.");
00156
00157 }
00158
00159 template<class GRAPH_T>
00160 void CGraphSlamHandler_ROS<GRAPH_T>::initEngine_MR() {
00161
00162 this->m_options_checker->node_regs_map[m_node_reg]();
00163 this->m_options_checker->edge_regs_map[m_edge_reg]();
00164 this->m_options_checker->optimizers_map[m_optimizer]();
00165
00166 this->m_logger->logFmt(LVL_WARN,
00167 "Initializing CGraphSlamEngine_MR instance...");
00168 this->m_engine = new CGraphSlamEngine_MR<GRAPH_T>(
00169 m_nh,
00170 this->m_ini_fname,
00171 "",
00172 this->m_gt_fname,
00173 this->m_win_manager,
00174 this->m_options_checker->node_regs_map[m_node_reg](),
00175 this->m_options_checker->edge_regs_map[m_edge_reg](),
00176 this->m_options_checker->optimizers_map[m_optimizer]());
00177 this->m_logger->logFmt(LVL_WARN,
00178 "Successfully initialized CGraphSlamEngine_MR instance.");
00179
00180 }
00181
00182 template<class GRAPH_T>
00183 void CGraphSlamHandler_ROS<GRAPH_T>::getROSParameters(std::string* str_out) {
00184 using namespace mrpt::utils;
00185 using namespace std;
00186
00187 ASSERT_(str_out);
00188
00189 stringstream ss("");
00190
00191
00192 ss << "ROS Parameters: " << endl;
00193 ss << sep_header << endl;
00194 ss << endl;
00195
00196 ss << "Deciders / Optimizers = " << endl;
00197 ss << sep_subheader << endl;
00198 ss << "Node Registration Decider = " << m_node_reg << endl;
00199 ss << "Edge Registration Decider = " << m_edge_reg << endl;
00200 ss << "GraphSLAM Optimizer = " << m_optimizer << endl;
00201 ss << endl;
00202
00203 ss << "Filenames: " << endl;
00204 ss << sep_subheader << endl;
00205 ss << "Configuration .ini file = " << this->m_ini_fname << endl;
00206 ss << "Ground truth filename = " << (!this->m_gt_fname.empty()
00207 ? this->m_gt_fname : "NONE")
00208 << endl;
00209 ss << endl;
00210
00211 ss << "Miscellaneous: " << endl;
00212 ss << sep_subheader << endl;
00213 ss << "Enable MRPT visuals? = " <<
00214 (this->m_enable_visuals? "TRUE" : "FALSE")
00215 << endl;
00216 ss << "Logging verbosity Level = " <<
00217 COutputLogger::logging_levels_to_names
00218 #if MRPT_VERSION>=0x199
00219 ()
00220 #endif
00221 [m_min_logging_level] << endl;;
00222 ss << endl;
00223
00224 *str_out = ss.str();
00225 }
00226
00227 template<class GRAPH_T>
00228 void CGraphSlamHandler_ROS<GRAPH_T>::getParamsAsString(std::string* str_out) {
00229 ASSERT_(str_out);
00230
00231
00232 std::string ros_params("");
00233 this->getROSParameters(&ros_params);
00234 std::string mrpt_params("");
00235 parent_t::getParamsAsString(&mrpt_params);
00236
00237 *str_out += ros_params;
00238 *str_out += "\n\n";
00239 *str_out += mrpt_params;
00240
00241
00242 }
00243
00244 template<class GRAPH_T>
00245 std::string CGraphSlamHandler_ROS<GRAPH_T>::getParamsAsString() {
00246 std::string params;
00247 this->getParamsAsString(¶ms);
00248 return params;
00249 }
00250
00251 template<class GRAPH_T>
00252 void CGraphSlamHandler_ROS<GRAPH_T>::printParams() {
00253 using namespace std;
00254 parent_t::printParams();
00255 cout << this->getParamsAsString() << endl;
00256
00257
00258 }
00259
00260 template<class GRAPH_T>
00261 void CGraphSlamHandler_ROS<GRAPH_T>::verifyUserInput() {
00262 this->m_logger->logFmt(LVL_DEBUG, "Verifying user input...");
00263
00264
00265
00266 bool node_success, edge_success, optimizer_success;
00267 bool failed = false;
00268
00269 node_success =
00270 this->m_options_checker->checkRegistrationDeciderExists(
00271 m_node_reg, "node");
00272 edge_success =
00273 this->m_options_checker->checkRegistrationDeciderExists(
00274 m_edge_reg, "edge");
00275 optimizer_success =
00276 this->m_options_checker->checkOptimizerExists(
00277 m_optimizer);
00278
00279 if (!node_success) {
00280 this->m_logger->logFmt(LVL_ERROR,
00281 "\nNode Registration Decider \"%s\" is not available",
00282 m_node_reg.c_str());
00283 this->m_options_checker->dumpRegistrarsToConsole("node");
00284 failed = true;
00285 }
00286 if (!edge_success) {
00287 this->m_logger->logFmt(LVL_ERROR,
00288 "\nEdge Registration Decider \"%s\" is not available.",
00289 m_edge_reg.c_str());
00290 this->m_options_checker->dumpRegistrarsToConsole("edge");
00291 failed = true;
00292 }
00293 if (!optimizer_success) {
00294 this->m_logger->logFmt(LVL_ERROR,
00295 "\ngraphSLAM Optimizser \"%s\" is not available.",
00296 m_optimizer.c_str());
00297 this->m_options_checker->dumpOptimizersToConsole();
00298 failed = true;
00299 }
00300 ASSERT_(!failed);
00301
00302
00303
00304 bool ini_exists = system::fileExists(this->m_ini_fname);
00305 ASSERTMSG_(ini_exists,
00306 format(
00307 "\n.ini configuration file \"%s\"doesn't exist. "
00308 "Please specify a valid pathname.\nExiting...\n",
00309 this->m_ini_fname.c_str()));
00310
00311 if (!this->m_gt_fname.empty()) {
00312 bool gt_exists = system::fileExists(this->m_gt_fname);
00313 ASSERTMSG_(gt_exists,
00314 format(
00315 "\nGround truth file \"%s\"doesn't exist."
00316 "Either unset the corresponding ROS parameter or specify a valid pathname.\n"
00317 "Exiting...\n",
00318 this->m_gt_fname.c_str()));
00319 }
00320
00321 }
00322
00323 template<class GRAPH_T>
00324 void CGraphSlamHandler_ROS<GRAPH_T>::setupComm() {
00325
00326 this->m_logger->logFmt(LVL_INFO,
00327 "Setting up ROS-related subscribers, publishers, services...");
00328
00329
00330 this->setupSubs();
00331 this->setupPubs();
00332 this->setupSrvs();
00333
00334
00335
00336
00337 }
00338
00339 template<class GRAPH_T>
00340 void CGraphSlamHandler_ROS<GRAPH_T>::setupSubs() {
00341 this->m_logger->logFmt(LVL_INFO, "Setting up the subscribers...");
00342
00343
00344 std::string ns = "input/";
00345
00346 m_odom_topic = ns + "odom";
00347 m_laser_scan_topic = ns + "laser_scan";
00348
00349
00350 m_odom_sub = m_nh->subscribe<nav_msgs::Odometry>(
00351 m_odom_topic,
00352 m_queue_size,
00353 &self_t::sniffOdom, this);
00354
00355
00356 m_laser_scan_sub = m_nh->subscribe<sensor_msgs::LaserScan>(
00357 m_laser_scan_topic,
00358 m_queue_size,
00359 &self_t::sniffLaserScan, this);
00360
00361
00362
00363
00364
00365
00366
00367 }
00368
00369 template<class GRAPH_T>
00370 void CGraphSlamHandler_ROS<GRAPH_T>::setupPubs() {
00371 this->m_logger->logFmt(LVL_INFO, "Setting up the publishers...");
00372
00373
00374 std::string ns = "feedback/";
00375
00376 m_curr_robot_pos_topic = ns + "robot_position";
00377 m_robot_trajectory_topic = ns + "robot_trajectory";
00378 m_robot_tr_poses_topic = ns + "robot_tr_poses";
00379 m_odom_trajectory_topic = ns + "odom_trajectory";
00380 m_gridmap_topic = ns + "gridmap";
00381 m_stats_topic = ns + "graphslam_stats";
00382
00383
00384
00385
00386 m_curr_robot_pos_pub = m_nh->advertise<geometry_msgs::PoseStamped>(
00387 m_curr_robot_pos_topic,
00388 m_queue_size);
00389 m_robot_trajectory_pub = m_nh->advertise<nav_msgs::Path>(
00390 m_robot_trajectory_topic,
00391 m_queue_size);
00392 m_robot_tr_poses_pub = m_nh->advertise<geometry_msgs::PoseArray>(
00393 m_robot_tr_poses_topic,
00394 m_queue_size);
00395
00396
00397 m_odom_path.header.seq = 0;
00398 m_odom_path.header.stamp = ros::Time::now();
00399 m_odom_path.header.frame_id = m_anchor_frame_id;
00400
00401 m_odom_trajectory_pub = m_nh->advertise<nav_msgs::Path>(
00402 m_odom_trajectory_topic,
00403 m_queue_size);
00404
00405
00406 m_gridmap_pub = m_nh->advertise<nav_msgs::OccupancyGrid>(
00407 m_gridmap_topic,
00408 m_queue_size,
00409 true);
00410
00411 m_stats_pub = m_nh->advertise<mrpt_msgs::GraphSlamStats>(
00412 m_stats_topic,
00413 m_queue_size,
00414 true);
00415
00416 }
00417
00418 template<class GRAPH_T>
00419 void CGraphSlamHandler_ROS<GRAPH_T>::setupSrvs() {
00420 this->m_logger->logFmt(LVL_INFO, "Setting up the services...");
00421
00422
00423
00424 }
00425
00426 template<class GRAPH_T>
00427 bool CGraphSlamHandler_ROS<GRAPH_T>::usePublishersBroadcasters() {
00428 using namespace mrpt::utils;
00429 using namespace std;
00430
00431 MRPT_START;
00432 bool ret_val = true;
00433
00434 ros::Time timestamp = ros::Time::now();
00435
00436
00437 pose_t mrpt_pose = this->m_engine->getCurrentRobotPosEstimation();
00438
00439
00440
00441
00442
00443 geometry_msgs::TransformStamped anchor_base_link_transform;
00444 anchor_base_link_transform.header.stamp = ros::Time::now();
00445 anchor_base_link_transform.header.frame_id = m_anchor_frame_id;
00446 anchor_base_link_transform.child_frame_id = m_base_link_frame_id;
00447
00448
00449 anchor_base_link_transform.transform.translation.x = mrpt_pose.x();
00450 anchor_base_link_transform.transform.translation.y = mrpt_pose.y();
00451 anchor_base_link_transform.transform.translation.z = 0;
00452
00453
00454 anchor_base_link_transform.transform.rotation =
00455 tf::createQuaternionMsgFromYaw(mrpt_pose.phi());
00456
00457
00458 m_broadcaster.sendTransform(anchor_base_link_transform);
00459
00460
00461
00462
00463
00464
00465 if (!m_anchor_odom_transform.child_frame_id.empty()) {
00466 m_broadcaster.sendTransform(m_anchor_odom_transform);
00467 }
00468
00469
00470 {
00471 geometry_msgs::PoseStamped geom_pose;
00472 geom_pose.header.stamp = timestamp;
00473 geom_pose.header.seq = m_pub_seq;
00474 geom_pose.header.frame_id = m_anchor_frame_id;
00475
00476
00477 mrpt_bridge::convert(mrpt_pose, geom_pose.pose);
00478 m_curr_robot_pos_pub.publish(geom_pose);
00479 }
00480
00481
00482
00483 {
00484 this->m_logger->logFmt(LVL_DEBUG,
00485 "Publishing the current robot trajectory");
00486 typename GRAPH_T::global_poses_t graph_poses;
00487 #if MRPT_VERSION>=0x199
00488 graph_poses = this->m_engine->getRobotEstimatedTrajectory();
00489 #else
00490 this->m_engine->getRobotEstimatedTrajectory(&graph_poses);
00491 #endif
00492
00493 nav_msgs::Path path;
00494
00495
00496 path.header.stamp = timestamp;
00497 path.header.seq = m_pub_seq;
00498 path.header.frame_id = m_anchor_frame_id;
00499
00500
00501
00502
00503
00504 geometry_msgs::PoseArray geom_poses;
00505 geom_poses.header.stamp = timestamp;
00506 geom_poses.header.frame_id = m_anchor_frame_id;
00507
00508 for (auto n_cit = graph_poses.begin();
00509 n_cit != graph_poses.end();
00510 ++n_cit) {
00511
00512 geometry_msgs::PoseStamped geom_pose_stamped;
00513 geometry_msgs::Pose geom_pose;
00514
00515
00516 const pose_t& mrpt_pose = n_cit->second;
00517 mrpt_bridge::convert(mrpt_pose, geom_pose);
00518 geom_poses.poses.push_back(geom_pose);
00519 geom_pose_stamped.pose = geom_pose;
00520
00521
00522 geom_pose_stamped.header.stamp = timestamp;
00523 geom_pose_stamped.header.seq = m_pub_seq;
00524 geom_pose_stamped.header.frame_id = m_anchor_frame_id;
00525
00526 path.poses.push_back(geom_pose_stamped);
00527 }
00528
00529
00530 if (this->m_engine->getGraph().nodeCount() > m_graph_nodes_last_size) {
00531 m_robot_tr_poses_pub.publish(geom_poses);
00532 m_robot_trajectory_pub.publish(path);
00533 }
00534 }
00535
00536
00537 m_odom_trajectory_pub.publish(m_odom_path);
00538
00539
00540
00541 if (this->m_engine->getGraph().nodeCount() > m_graph_nodes_last_size) {
00542 std_msgs::Header h;
00543 mrpt::system::TTimeStamp mrpt_time;
00544 mrpt::maps::COccupancyGridMap2D::Ptr mrpt_gridmap =
00545 mrpt::maps::COccupancyGridMap2D::Create();
00546 this->m_engine->getMap(mrpt_gridmap, &mrpt_time);
00547
00548
00549 mrpt_bridge::convert(mrpt_time, h.stamp);
00550 h.seq = m_pub_seq;
00551 h.frame_id = m_anchor_frame_id;
00552
00553
00554 nav_msgs::OccupancyGrid nav_gridmap;
00555 mrpt_bridge::convert(*mrpt_gridmap, nav_gridmap, h);
00556 m_gridmap_pub.publish(nav_gridmap);
00557 }
00558
00559
00560 {
00561 mrpt_msgs::GraphSlamStats stats;
00562 stats.header.seq = m_stats_pub_seq++;
00563
00564 map<string, int> node_stats;
00565 map<string, int> edge_stats;
00566 vector<double> def_energy_vec;
00567 mrpt::system::TTimeStamp mrpt_time;
00568
00569 this->m_engine->getGraphSlamStats(&node_stats,
00570 &edge_stats,
00571 &mrpt_time);
00572
00573
00574 stats.nodes_total = node_stats["nodes_total"];
00575 stats.edges_total = edge_stats["edges_total"];
00576 if (edge_stats.find("ICP2D") != edge_stats.end()) {
00577 stats.edges_ICP2D = edge_stats["ICP2D"];
00578 }
00579 if (edge_stats.find("ICP3D") != edge_stats.end()) {
00580 stats.edges_ICP3D = edge_stats["ICP3D"];
00581 }
00582 if (edge_stats.find("Odometry") != edge_stats.end()) {
00583 stats.edges_odom = edge_stats["Odometry"];
00584 }
00585 stats.loop_closures = edge_stats["loop_closures"];
00586
00587
00588 this->m_engine->getDeformationEnergyVector(
00589 &stats.slam_evaluation_metric);
00590
00591 mrpt_bridge::convert(mrpt_time, stats.header.stamp);
00592
00593 m_stats_pub.publish(stats);
00594
00595 }
00596
00597
00598
00599
00600 m_graph_nodes_last_size = this->m_engine->getGraph().nodeCount();
00601 m_pub_seq++;
00602
00603 if (this->m_enable_visuals) {
00604 ret_val = this->queryObserverForEvents();
00605 }
00606
00607 return ret_val;
00608 MRPT_END;
00609 }
00610
00611 template<class GRAPH_T>
00612 void CGraphSlamHandler_ROS<GRAPH_T>::sniffLaserScan(
00613 const sensor_msgs::LaserScan::ConstPtr& ros_laser_scan) {
00614 using namespace std;
00615 using namespace mrpt::utils;
00616 using namespace mrpt::obs;
00617
00618 this->m_logger->logFmt(
00619 LVL_DEBUG,
00620 "sniffLaserScan: Received a LaserScan msg. Converting it to MRPT format...");
00621
00622
00623 m_mrpt_laser_scan = CObservation2DRangeScan::Create();
00624 mrpt::poses::CPose3D rel_pose;
00625 mrpt_bridge::convert(*ros_laser_scan, rel_pose, *m_mrpt_laser_scan);
00626
00627 m_received_laser_scan = true;
00628 CObservation::Ptr tmp = mrpt::ptr_cast<CObservation>::from(m_mrpt_laser_scan);
00629 this->processObservation(tmp);
00630 }
00631
00632 template<class GRAPH_T>
00633 void CGraphSlamHandler_ROS<GRAPH_T>::sniffOdom(
00634 const nav_msgs::Odometry::ConstPtr& ros_odom) {
00635 using namespace std;
00636 using namespace mrpt::utils;
00637 using namespace mrpt::obs;
00638 using namespace mrpt::poses;
00639
00640 this->m_logger->logFmt(
00641 LVL_DEBUG,
00642 "sniffOdom: Received an odometry msg. Converting it to MRPT format...");
00643
00644
00645 {
00646
00647 m_anchor_odom_transform.header.frame_id = m_anchor_frame_id;
00648 m_anchor_odom_transform.header.stamp = ros_odom->header.stamp;
00649 m_anchor_odom_transform.header.seq = ros_odom->header.seq;
00650
00651 m_anchor_odom_transform.child_frame_id = m_odom_frame_id;
00652
00653
00654
00655
00656
00657
00658 m_anchor_odom_transform.transform.translation.x =
00659 ros_odom->pose.pose.position.x;
00660 m_anchor_odom_transform.transform.translation.y =
00661 ros_odom->pose.pose.position.y;
00662 m_anchor_odom_transform.transform.translation.z =
00663 ros_odom->pose.pose.position.z;
00664
00665
00666 m_anchor_odom_transform.transform.rotation =
00667 ros_odom->pose.pose.orientation;
00668 }
00669
00670
00671
00672 mrpt_bridge::convert(
00673 ros_odom->header.stamp,
00674 m_mrpt_odom->timestamp);
00675 mrpt_bridge::convert(
00676 ros_odom->pose.pose,
00677 m_mrpt_odom->odometry);
00678
00679
00680
00681 if (m_first_time_in_sniff_odom) {
00682 m_input_odometry_offset = m_mrpt_odom->odometry;
00683 m_first_time_in_sniff_odom = false;
00684 }
00685
00686 m_mrpt_odom->odometry =
00687 m_mrpt_odom->odometry - m_input_odometry_offset;
00688
00689
00690 {
00691 geometry_msgs::PoseStamped pose_stamped;
00692 pose_stamped.header = ros_odom->header;
00693
00694
00695 mrpt_bridge::convert(
00696 m_mrpt_odom->odometry,
00697 pose_stamped.pose);
00698 m_odom_path.poses.push_back(pose_stamped);
00699 }
00700
00701
00702 stringstream ss;
00703 ss << "Odometry - MRPT format:\t" << m_mrpt_odom->odometry << endl;
00704 this->m_logger->logFmt(LVL_DEBUG, "%s", ss.str().c_str());
00705
00706 m_received_odom = true;
00707 CObservation::Ptr tmp = mrpt::ptr_cast<mrpt::obs::CObservation>::from(m_mrpt_odom);
00708 this->processObservation(tmp);
00709 }
00710
00711 template<class GRAPH_T>
00712 void CGraphSlamHandler_ROS<GRAPH_T>::sniffCameraImage() {
00713 THROW_EXCEPTION("Method is not implemented yet.");
00714
00715 }
00716 template<class GRAPH_T>
00717 void CGraphSlamHandler_ROS<GRAPH_T>::sniff3DPointCloud() {
00718 THROW_EXCEPTION("Method is not implemented yet.");
00719
00720 }
00721 template<class GRAPH_T>
00722 void CGraphSlamHandler_ROS<GRAPH_T>::processObservation(
00723 mrpt::obs::CObservation::Ptr& observ) {
00724 using namespace mrpt::utils;
00725 using namespace std;
00726
00727 this->_process(observ);
00728 this->resetReceivedFlags();
00729
00730 }
00731
00732 template<class GRAPH_T>
00733 void CGraphSlamHandler_ROS<GRAPH_T>::_process(
00734 mrpt::obs::CObservation::Ptr& observ) {
00735 using namespace mrpt::utils;
00736
00737
00738
00739
00740 if (!this->m_engine->isPaused()) {
00741 this->m_engine->execGraphSlamStep(observ, m_measurement_cnt);
00742 m_measurement_cnt++;
00743 }
00744 }
00745
00746 template<class GRAPH_T>
00747 void CGraphSlamHandler_ROS<GRAPH_T>::resetReceivedFlags() {
00748 m_received_odom = false;
00749 m_received_laser_scan = false;
00750 m_received_camera = false;
00751 m_received_point_cloud = false;
00752 }
00753
00754 } } }
00755