mrpt_rbpf_slam_wrapper.cpp
Go to the documentation of this file.
00001 #include "mrpt_rbpf_slam/mrpt_rbpf_slam_wrapper.h"
00002 
00003 PFslamWrapper::PFslamWrapper()
00004 {
00005   rawlog_play_ = false;
00006   mrpt_bridge::convert(ros::Time(0), timeLastUpdate_);
00007 }
00008 
00009 PFslamWrapper::~PFslamWrapper()
00010 {
00011 }
00012 
00013 bool PFslamWrapper::is_file_exists(const std::string& name)
00014 {
00015   std::ifstream f(name.c_str());
00016   return f.good();
00017 }
00018 
00019 void PFslamWrapper::get_param()
00020 {
00021   ROS_INFO("READ PARAM FROM LAUNCH FILE");
00022   n_.param<double>("rawlog_play_delay", rawlog_play_delay, 0.1);
00023   ROS_INFO("rawlog_play_delay: %f", rawlog_play_delay);
00024 
00025   n_.getParam("rawlog_filename", rawlog_filename);
00026   ROS_INFO("rawlog_filename: %s", rawlog_filename.c_str());
00027 
00028   n_.getParam("ini_filename", ini_filename);
00029   ROS_INFO("ini_filename: %s", ini_filename.c_str());
00030 
00031   n_.param<std::string>("global_frame_id", global_frame_id, "map");
00032   ROS_INFO("global_frame_id: %s", global_frame_id.c_str());
00033 
00034   n_.param<std::string>("odom_frame_id", odom_frame_id, "odom");
00035   ROS_INFO("odom_frame_id: %s", odom_frame_id.c_str());
00036 
00037   n_.param<std::string>("base_frame_id", base_frame_id, "base_link");
00038   ROS_INFO("base_frame_id: %s", base_frame_id.c_str());
00039 
00040   n_.param<std::string>("sensor_source", sensor_source, "scan");
00041   ROS_INFO("sensor_source: %s", sensor_source.c_str());
00042 }
00043 
00044 void PFslamWrapper::init()
00045 {
00046   // get parameters from ini file
00047   if (!is_file_exists(ini_filename))
00048   {
00049     ROS_ERROR_STREAM("CAN'T READ INI FILE");
00050     return;
00051   }
00052   PFslam::read_iniFile(ini_filename);
00053   // read rawlog file if it  exists
00054   if (is_file_exists(rawlog_filename))
00055   {
00056     ROS_WARN_STREAM("PLAY FROM RAWLOG FILE: " << rawlog_filename.c_str());
00057     PFslam::read_rawlog(data, rawlog_filename);
00058     rawlog_play_ = true;
00059   }
00060 
00062   // publish grid map
00063   pub_map_ = n_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00064   pub_metadata_ = n_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00065   // robot pose
00066   pub_Particles_ = n_.advertise<geometry_msgs::PoseArray>("particlecloud", 1, true);
00067   // ro particles poses
00068   pub_Particles_Beacons_ = n_.advertise<geometry_msgs::PoseArray>("particlecloud_beacons", 1, true);
00069   beacon_viz_pub_ = n_.advertise<visualization_msgs::MarkerArray>("/beacons_viz", 1);
00070 
00071   // read sensor topics
00072   std::vector<std::string> lstSources;
00073   mrpt::system::tokenize(sensor_source, " ,\t\n", lstSources);
00074   ROS_ASSERT_MSG(!lstSources.empty(), "*Fatal*: At least one sensor source must be provided in ~sensor_sources (e.g. "
00075                                       "\"scan\" or \"beacon\")");
00076 
00078   sensorSub_.resize(lstSources.size());
00079   for (size_t i = 0; i < lstSources.size(); i++)
00080   {
00081     if (lstSources[i].find("scan") != std::string::npos)
00082     {
00083       sensorSub_[i] = n_.subscribe(lstSources[i], 1, &PFslamWrapper::laserCallback, this);
00084     }
00085     else
00086     {
00087       sensorSub_[i] = n_.subscribe(lstSources[i], 1, &PFslamWrapper::callbackBeacon, this);
00088     }
00089   }
00090 
00091   // init slam
00092   mapBuilder = new mrpt::slam::CMetricMapBuilderRBPF(rbpfMappingOptions);
00093   init_slam();
00094   init3Dwindow();
00095 }
00096 
00097 void PFslamWrapper::odometryForCallback(CObservationOdometryPtr& _odometry, const std_msgs::Header& _msg_header)
00098 {
00099   mrpt::poses::CPose3D poseOdom;
00100   if (this->waitForTransform(poseOdom, odom_frame_id, base_frame_id, _msg_header.stamp, ros::Duration(1)))
00101   {
00102     _odometry = CObservationOdometry::Create();
00103     _odometry->sensorLabel = odom_frame_id;
00104     _odometry->hasEncodersInfo = false;
00105     _odometry->hasVelocities = false;
00106     _odometry->odometry.x() = poseOdom.x();
00107     _odometry->odometry.y() = poseOdom.y();
00108     _odometry->odometry.phi() = poseOdom.yaw();
00109   }
00110 }
00111 
00112 bool PFslamWrapper::waitForTransform(mrpt::poses::CPose3D& des, const std::string& target_frame,
00113                                      const std::string& source_frame, const ros::Time& time,
00114                                      const ros::Duration& timeout, const ros::Duration& polling_sleep_duration)
00115 {
00116   tf::StampedTransform transform;
00117   try
00118   {
00119     listenerTF_.waitForTransform(target_frame, source_frame, time, polling_sleep_duration);
00120     listenerTF_.lookupTransform(target_frame, source_frame, time, transform);
00121   }
00122   catch (tf::TransformException)
00123   {
00124     ROS_INFO("Failed to get transform target_frame (%s) to source_frame (%s)", target_frame.c_str(),
00125              source_frame.c_str());
00126     return false;
00127   }
00128   mrpt_bridge::convert(transform, des);
00129   return true;
00130 }
00131 
00132 void PFslamWrapper::laserCallback(const sensor_msgs::LaserScan& _msg)
00133 {
00134 #if MRPT_VERSION >= 0x130
00135   using namespace mrpt::maps;
00136   using namespace mrpt::obs;
00137 #else
00138   using namespace mrpt::slam;
00139 #endif
00140   CObservation2DRangeScanPtr laser = CObservation2DRangeScan::Create();
00141 
00142   if (laser_poses_.find(_msg.header.frame_id) == laser_poses_.end())
00143   {
00144     updateSensorPose(_msg.header.frame_id);
00145   }
00146   else
00147   {
00148     mrpt::poses::CPose3D pose = laser_poses_[_msg.header.frame_id];
00149     mrpt_bridge::convert(_msg, laser_poses_[_msg.header.frame_id], *laser);
00150 
00151     sf = CSensoryFrame::Create();
00152     CObservationOdometryPtr odometry;
00153     odometryForCallback(odometry, _msg.header);
00154 
00155     CObservationPtr obs = CObservationPtr(laser);
00156     sf->insert(obs);
00157     observation(sf, odometry);
00158     timeLastUpdate_ = sf->getObservationByIndex(0)->timestamp;
00159 
00160     tictac.Tic();
00161     mapBuilder->processActionObservation(*action, *sf);
00162     t_exec = tictac.Tac();
00163     ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec);
00164     publishMapPose();
00165     run3Dwindow();
00166     publishTF();
00167   }
00168 }
00169 
00170 void PFslamWrapper::callbackBeacon(const mrpt_msgs::ObservationRangeBeacon& _msg)
00171 {
00172 #if MRPT_VERSION >= 0x130
00173   using namespace mrpt::maps;
00174   using namespace mrpt::obs;
00175 #else
00176   using namespace mrpt::slam;
00177 #endif
00178 
00179   CObservationBeaconRangesPtr beacon = CObservationBeaconRanges::Create();
00180   if (beacon_poses_.find(_msg.header.frame_id) == beacon_poses_.end())
00181   {
00182     updateSensorPose(_msg.header.frame_id);
00183   }
00184   else
00185   {
00186     mrpt_bridge::convert(_msg, beacon_poses_[_msg.header.frame_id], *beacon);
00187 
00188     sf = CSensoryFrame::Create();
00189     CObservationOdometryPtr odometry;
00190     odometryForCallback(odometry, _msg.header);
00191 
00192     CObservationPtr obs = CObservationPtr(beacon);
00193     sf->insert(obs);
00194     observation(sf, odometry);
00195     timeLastUpdate_ = sf->getObservationByIndex(0)->timestamp;
00196 
00197     tictac.Tic();
00198     mapBuilder->processActionObservation(*action, *sf);
00199     t_exec = tictac.Tac();
00200     ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec);
00201 
00202     publishMapPose();
00203     run3Dwindow();
00204   }
00205 }
00206 
00207 void PFslamWrapper::publishMapPose()
00208 {
00209   // if I received new grid maps from 2D laser scan sensors
00210   metric_map_ = mapBuilder->mapPDF.getCurrentMostLikelyMetricMap();
00211   mapBuilder->mapPDF.getEstimatedPosePDF(curPDF);
00212   if (metric_map_->m_gridMaps.size())
00213   {
00214     // publish map
00215     nav_msgs::OccupancyGrid _msg;
00216     mrpt_bridge::convert(*metric_map_->m_gridMaps[0], _msg);
00217     pub_map_.publish(_msg);
00218     pub_metadata_.publish(_msg.info);
00219   }
00220 
00221   // if I received new beacon (range only) map
00222   if (metric_map_->m_beaconMap)
00223   {
00224     mrpt::opengl::CSetOfObjectsPtr objs;
00225 
00226     objs = mrpt::opengl::CSetOfObjects::Create();
00227     // Get th map as the set of 3D objects
00228     metric_map_->m_beaconMap->getAs3DObject(objs);
00229 
00230     geometry_msgs::PoseArray poseArrayBeacons;
00231     poseArrayBeacons.header.frame_id = global_frame_id;
00232     poseArrayBeacons.header.stamp = ros::Time::now();
00233 
00234     // Count the number of beacons
00235     int objs_counter = 0;
00236     while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter))
00237     {
00238       objs_counter++;
00239     }
00240     poseArrayBeacons.poses.resize(objs_counter);
00241     mrpt::opengl::CEllipsoidPtr beacon_particle;
00242 
00243     for (size_t i = 0; i < objs_counter; i++)
00244     {
00245       beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
00246       mrpt_bridge::convert(mrpt::poses::CPose3D(beacon_particle->getPose()), poseArrayBeacons.poses[i]);
00247       viz_beacons.push_back(beacon_particle);
00248     }
00249     pub_Particles_Beacons_.publish(poseArrayBeacons);
00250     vizBeacons();
00251     viz_beacons.clear();
00252   }
00253 
00254   // publish pose
00255   geometry_msgs::PoseArray poseArray;
00256   poseArray.header.frame_id = global_frame_id;
00257   poseArray.header.stamp = ros::Time::now();
00258   poseArray.poses.resize(curPDF.particlesCount());
00259   for (size_t i = 0; i < curPDF.particlesCount(); i++)
00260   {
00261     mrpt::poses::CPose3D p = curPDF.getParticlePose(i);
00262     mrpt_bridge::convert(p, poseArray.poses[i]);
00263   }
00264 
00265   pub_Particles_.publish(poseArray);
00266 }
00267 
00268 void PFslamWrapper::vizBeacons()
00269 {
00270   if (viz_beacons.size() == 0)
00271   {
00272     return;
00273   }
00274   visualization_msgs::MarkerArray ma;
00275   visualization_msgs::Marker marker;
00276 
00277   marker.header.frame_id = "/map";
00278 
00279   marker.id = 0;
00280   marker.type = visualization_msgs::Marker::SPHERE;
00281   marker.action = visualization_msgs::Marker::ADD;
00282   marker.lifetime = ros::Duration(1);
00283   marker.pose.position.x = 0;
00284   marker.pose.position.y = 0;
00285   marker.pose.position.z = 0;
00286   marker.pose.orientation.x = 0.0;
00287   marker.pose.orientation.y = 0.0;
00288   marker.pose.orientation.z = 0.0;
00289   marker.pose.orientation.w = 1.0;
00290   marker.scale.x = 0.12;
00291   marker.scale.y = 0.12;
00292   marker.scale.z = 0.12;
00293   marker.color.a = 1.0;
00294   marker.color.r = 1.0;
00295   marker.color.g = 0.0;
00296 
00297   for (int i = 0; i < viz_beacons.size(); i++)
00298   {
00299     CPose3D meanPose(viz_beacons[i]->getPose());
00300     marker.type = visualization_msgs::Marker::SPHERE;
00301 
00302     marker.pose.position.x = meanPose.x();
00303     marker.pose.position.y = meanPose.y();
00304     marker.pose.position.z = meanPose.z();
00305     marker.color.r = 1.0;
00306     marker.color.g = 0.0;
00307     marker.color.b = 0.0;
00308 
00309     ma.markers.push_back(marker);
00310     marker.id++;
00311 
00312     marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00313     marker.text = std::to_string(i);
00314 
00315     marker.pose.position.x = meanPose.x();
00316     marker.pose.position.y = meanPose.y();
00317     marker.pose.position.z = meanPose.z() + 0.12;
00318     marker.color.r = 1.0;
00319     marker.color.g = 1.0;
00320     marker.color.b = 1.0;
00321     // marker.scale.z = 1;
00322     ma.markers.push_back(marker);
00323     marker.id++;
00324   }
00325 
00326   beacon_viz_pub_.publish(ma);
00327 }
00328 
00329 void PFslamWrapper::updateSensorPose(std::string _frame_id)
00330 {
00331   CPose3D pose;
00332   tf::StampedTransform transform;
00333   try
00334   {
00335     listenerTF_.lookupTransform(base_frame_id, _frame_id, ros::Time(0), transform);
00336 
00337     tf::Vector3 translation = transform.getOrigin();
00338     tf::Quaternion quat = transform.getRotation();
00339     pose.x() = translation.x();
00340     pose.y() = translation.y();
00341     pose.z() = translation.z();
00342     double roll, pitch, yaw;
00343     tf::Matrix3x3 Rsrc(quat);
00344     CMatrixDouble33 Rdes;
00345     for (int c = 0; c < 3; c++)
00346       for (int r = 0; r < 3; r++)
00347         Rdes(r, c) = Rsrc.getRow(r)[c];
00348     pose.setRotationMatrix(Rdes);
00349     laser_poses_[_frame_id] = pose;
00350     beacon_poses_[_frame_id] = pose;
00351   }
00352   catch (tf::TransformException ex)
00353   {
00354     ROS_ERROR("%s", ex.what());
00355     ros::Duration(1.0).sleep();
00356   }
00357 }
00358 
00359 bool PFslamWrapper::rawlogPlay()
00360 {
00361   if (rawlog_play_ == false)
00362   {
00363     return false;
00364   }
00365   else
00366   {
00367     for (int i = 0; i < data.size(); i++)
00368     {
00369       if (ros::ok())
00370       {
00371         tictac.Tic();
00372         mapBuilder->processActionObservation(data[i].first, data[i].second);
00373         t_exec = tictac.Tac();
00374         ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec);
00375 
00376         ros::Duration(rawlog_play_delay).sleep();
00377 
00378         metric_map_ = mapBuilder->mapPDF.getCurrentMostLikelyMetricMap();
00379         mapBuilder->mapPDF.getEstimatedPosePDF(curPDF);
00380         // if I received new grid maps from 2D laser scan sensors
00381         if (metric_map_->m_gridMaps.size())
00382         {
00383           nav_msgs::OccupancyGrid _msg;
00384 
00385           // if we have new map for current sensor update it
00386           mrpt_bridge::convert(*metric_map_->m_gridMaps[0], _msg);
00387           pub_map_.publish(_msg);
00388           pub_metadata_.publish(_msg.info);
00389         }
00390 
00391         // if I received new beacon (range only) map
00392         if (metric_map_->m_beaconMap)
00393         {
00394           mrpt::opengl::CSetOfObjectsPtr objs;
00395           objs = mrpt::opengl::CSetOfObjects::Create();
00396           metric_map_->m_beaconMap->getAs3DObject(objs);
00397 
00398           geometry_msgs::PoseArray poseArrayBeacons;
00399           poseArrayBeacons.header.frame_id = global_frame_id;
00400           poseArrayBeacons.header.stamp = ros::Time::now();
00401 
00402           int objs_counter = 0;
00403           while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter))
00404           {
00405             objs_counter++;
00406           }
00407           poseArrayBeacons.poses.resize(objs_counter);
00408           mrpt::opengl::CEllipsoidPtr beacon_particle;
00409 
00410           for (size_t i = 0; i < objs_counter; i++)
00411           {
00412             beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
00413             mrpt_bridge::convert(mrpt::poses::CPose3D(beacon_particle->getPose()), poseArrayBeacons.poses[i]);
00414             viz_beacons.push_back(beacon_particle);
00415           }
00416           pub_Particles_Beacons_.publish(poseArrayBeacons);
00417           vizBeacons();
00418           viz_beacons.clear();
00419         }
00420 
00421         // publish pose
00422         geometry_msgs::PoseArray poseArray;
00423         poseArray.header.frame_id = global_frame_id;
00424         poseArray.header.stamp = ros::Time::now();
00425         poseArray.poses.resize(curPDF.particlesCount());
00426         for (size_t i = 0; i < curPDF.particlesCount(); i++)
00427         {
00428           mrpt::poses::CPose3D p = curPDF.getParticlePose(i);
00429           mrpt_bridge::convert(p, poseArray.poses[i]);
00430         }
00431 
00432         pub_Particles_.publish(poseArray);
00433       }
00434       ros::spinOnce();
00435       run3Dwindow();
00436     }
00437   }
00438   // if there is mrpt_gui it will wait until push any key in order to close the window
00439   if (win3D)
00440     win3D->waitForKey();
00441   return true;
00442 }
00443 
00444 void PFslamWrapper::publishTF()
00445 {
00446   // Most of this code was copy and pase from ros::amcl
00447   mrpt::poses::CPose3D robotPose;
00448   mapBuilder->mapPDF.getEstimatedPosePDF(curPDF);
00449 
00450   curPDF.getMean(robotPose);
00451 
00452   tf::Stamped<tf::Pose> odom_to_map;
00453   tf::Transform tmp_tf;
00454   ros::Time stamp;
00455   mrpt_bridge::convert(timeLastUpdate_, stamp);
00456   mrpt_bridge::convert(robotPose, tmp_tf);
00457 
00458   try
00459   {
00460     tf::Stamped<tf::Pose> tmp_tf_stamped(tmp_tf.inverse(), stamp, base_frame_id);
00461     listenerTF_.transformPose(odom_frame_id, tmp_tf_stamped, odom_to_map);
00462   }
00463   catch (tf::TransformException)
00464   {
00465     ROS_INFO("Failed to subtract global_frame (%s) from odom_frame (%s)", global_frame_id.c_str(),
00466              odom_frame_id.c_str());
00467     return;
00468   }
00469 
00470   tf::Transform latest_tf_ =
00471       tf::Transform(tf::Quaternion(odom_to_map.getRotation()), tf::Point(odom_to_map.getOrigin()));
00472 
00473   // We want to send a transform that is good up until a
00474   // tolerance time so that odom can be used
00475 
00476   ros::Duration transform_tolerance_(0.5);
00477   ros::Time transform_expiration = (stamp + transform_tolerance_);
00478   tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(), transform_expiration, global_frame_id, odom_frame_id);
00479   tf_broadcaster_.sendTransform(tmp_tf_stamped);
00480 }


mrpt_rbpf_slam
Author(s): Vladislav Tananaev
autogenerated on Sun Sep 17 2017 03:02:13