mrpt_ekf_slam_2d_wrapper.cpp
Go to the documentation of this file.
00001 /*
00002  * File: mrpt_ekf_slam_2d_wrapper.cpp
00003  * Author: Vladislav Tananaev
00004  *
00005  */
00006 
00007 #include "mrpt_ekf_slam_2d/mrpt_ekf_slam_2d_wrapper.h"
00008 
00009 EKFslamWrapper::EKFslamWrapper()
00010 {
00011   rawlog_play_ = false;
00012   mrpt_bridge::convert(ros::Time(0), timeLastUpdate_);
00013 }
00014 EKFslamWrapper::~EKFslamWrapper()
00015 {
00016 }
00017 bool EKFslamWrapper::is_file_exists(const std::string& name)
00018 {
00019   std::ifstream f(name.c_str());
00020   return f.good();
00021 }
00022 
00023 void EKFslamWrapper::get_param()
00024 {
00025   ROS_INFO("READ PARAM FROM LAUNCH FILE");
00026   n_.param<double>("ellipse_scale", ellipse_scale_, 1);
00027   ROS_INFO("ellipse_scale: %f", ellipse_scale_);
00028 
00029   n_.param<double>("rawlog_play_delay", rawlog_play_delay, 0.1);
00030   ROS_INFO("rawlog_play_delay: %f", rawlog_play_delay);
00031 
00032   n_.getParam("rawlog_filename", rawlog_filename);
00033   ROS_INFO("rawlog_filename: %s", rawlog_filename.c_str());
00034 
00035   n_.getParam("ini_filename", ini_filename);
00036   ROS_INFO("ini_filename: %s", ini_filename.c_str());
00037 
00038   n_.param<std::string>("global_frame_id", global_frame_id, "map");
00039   ROS_INFO("global_frame_id: %s", global_frame_id.c_str());
00040 
00041   n_.param<std::string>("odom_frame_id", odom_frame_id, "odom");
00042   ROS_INFO("odom_frame_id: %s", odom_frame_id.c_str());
00043 
00044   n_.param<std::string>("base_frame_id", base_frame_id, "base_link");
00045   ROS_INFO("base_frame_id: %s", base_frame_id.c_str());
00046 
00047   n_.param<std::string>("sensor_source", sensor_source, "scan");
00048   ROS_INFO("sensor_source: %s", sensor_source.c_str());
00049 }
00050 void EKFslamWrapper::init()
00051 {
00052   // get parameters from ini file
00053 
00054   if (!is_file_exists(ini_filename))
00055   {
00056     ROS_ERROR_STREAM("CAN'T READ INI FILE");
00057     return;
00058   }
00059 
00060   EKFslam::read_iniFile(ini_filename);
00061   // read rawlog file if it  exists
00062   if (is_file_exists(rawlog_filename))
00063   {
00064     ROS_WARN_STREAM("PLAY FROM RAWLOG FILE: " << rawlog_filename.c_str());
00065     rawlog_play_ = true;
00066   }
00067 
00068   state_viz_pub_ = n_.advertise<visualization_msgs::MarkerArray>("/state_viz", 1);  // map
00069   data_association_viz_pub_ =
00070       n_.advertise<visualization_msgs::MarkerArray>("/data_association_viz", 1);  // data_association
00071 
00072   // read sensor topics
00073   std::vector<std::string> lstSources;
00074   mrpt::system::tokenize(sensor_source, " ,\t\n", lstSources);
00075   ROS_ASSERT_MSG(!lstSources.empty(), "*Fatal*: At least one sensor source must be provided in ~sensor_sources (e.g. "
00076                                       "\"scan\" or \"beacon\")");
00077 
00079   sensorSub_.resize(lstSources.size());
00080   for (size_t i = 0; i < lstSources.size(); i++)
00081   {
00082     if (lstSources[i].find("landmark") != std::string::npos)
00083     {
00084       sensorSub_[i] = n_.subscribe(lstSources[i], 1, &EKFslamWrapper::landmarkCallback, this);
00085     }
00086     else
00087     {
00088       ROS_ERROR("Can't find the sensor topics. The sensor topics should contain the word \"landmark\" in the name");
00089     }
00090   }
00091 
00092   init3Dwindow();
00093 }
00094 
00095 void EKFslamWrapper::odometryForCallback(CObservationOdometryPtr& _odometry, const std_msgs::Header& _msg_header)
00096 {
00097   mrpt::poses::CPose3D poseOdom;
00098   if (this->waitForTransform(poseOdom, odom_frame_id, base_frame_id, _msg_header.stamp, ros::Duration(1)))
00099   {
00100     _odometry = CObservationOdometry::Create();
00101     _odometry->sensorLabel = odom_frame_id;
00102     _odometry->hasEncodersInfo = false;
00103     _odometry->hasVelocities = false;
00104     _odometry->odometry.x() = poseOdom.x();
00105     _odometry->odometry.y() = poseOdom.y();
00106     _odometry->odometry.phi() = poseOdom.yaw();
00107   }
00108 }
00109 
00110 void EKFslamWrapper::updateSensorPose(std::string _frame_id)
00111 {
00112   CPose3D pose;
00113   tf::StampedTransform transform;
00114   try
00115   {
00116     listenerTF_.lookupTransform(base_frame_id, _frame_id, ros::Time(0), transform);
00117 
00118     tf::Vector3 translation = transform.getOrigin();
00119     tf::Quaternion quat = transform.getRotation();
00120     pose.x() = translation.x();
00121     pose.y() = translation.y();
00122     pose.z() = translation.z();
00123     double roll, pitch, yaw;
00124     tf::Matrix3x3 Rsrc(quat);
00125     CMatrixDouble33 Rdes;
00126     for (int c = 0; c < 3; c++)
00127       for (int r = 0; r < 3; r++)
00128         Rdes(r, c) = Rsrc.getRow(r)[c];
00129     pose.setRotationMatrix(Rdes);
00130     landmark_poses_[_frame_id] = pose;
00131   }
00132   catch (tf::TransformException ex)
00133   {
00134     ROS_ERROR("%s", ex.what());
00135     ros::Duration(1.0).sleep();
00136   }
00137 }
00138 
00139 bool EKFslamWrapper::waitForTransform(mrpt::poses::CPose3D& des, const std::string& target_frame,
00140                                       const std::string& source_frame, const ros::Time& time,
00141                                       const ros::Duration& timeout, const ros::Duration& polling_sleep_duration)
00142 {
00143   tf::StampedTransform transform;
00144   try
00145   {
00146     listenerTF_.waitForTransform(target_frame, source_frame, time, polling_sleep_duration);
00147     listenerTF_.lookupTransform(target_frame, source_frame, time, transform);
00148   }
00149   catch (tf::TransformException)
00150   {
00151     ROS_INFO("Failed to get transform target_frame (%s) to source_frame (%s)", target_frame.c_str(),
00152              source_frame.c_str());
00153     return false;
00154   }
00155   mrpt_bridge::convert(transform, des);
00156   return true;
00157 }
00158 
00159 void EKFslamWrapper::landmarkCallback(const mrpt_msgs::ObservationRangeBearing& _msg)
00160 {
00161 #if MRPT_VERSION >= 0x130
00162   using namespace mrpt::maps;
00163   using namespace mrpt::obs;
00164 #else
00165   using namespace mrpt::slam;
00166 #endif
00167   CObservationBearingRangePtr landmark = CObservationBearingRange::Create();
00168 
00169   if (landmark_poses_.find(_msg.header.frame_id) == landmark_poses_.end())
00170   {
00171     updateSensorPose(_msg.header.frame_id);
00172   }
00173   else
00174   {
00175     mrpt::poses::CPose3D pose = landmark_poses_[_msg.header.frame_id];
00176     mrpt_bridge::convert(_msg, landmark_poses_[_msg.header.frame_id], *landmark);
00177 
00178     sf = CSensoryFrame::Create();
00179     CObservationOdometryPtr odometry;
00180     odometryForCallback(odometry, _msg.header);
00181 
00182     CObservationPtr obs = CObservationPtr(landmark);
00183     sf->insert(obs);
00184     observation(sf, odometry);
00185     timeLastUpdate_ = sf->getObservationByIndex(0)->timestamp;
00186 
00187     tictac.Tic();
00188     mapping.processActionObservation(action, sf);
00189     t_exec = tictac.Tac();
00190     ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec);
00191     ros::Duration(rawlog_play_delay).sleep();
00192     mapping.getCurrentState(robotPose_, LMs_, LM_IDs_, fullState_, fullCov_);
00193     viz_state();
00194     viz_dataAssociation();
00195     run3Dwindow();
00196     publishTF();
00197   }
00198 }
00199 
00200 bool EKFslamWrapper::rawlogPlay()
00201 {
00202   if (rawlog_play_ == false)
00203   {
00204     return false;
00205   }
00206   else
00207   {
00208     size_t rawlogEntry = 0;
00209     CFileGZInputStream rawlogFile(rawlog_filename);
00210     CActionCollectionPtr action;
00211     CSensoryFramePtr observations;
00212 
00213     for (;;)
00214     {
00215       if (ros::ok())
00216       {
00217         if (!CRawlog::readActionObservationPair(rawlogFile, action, observations, rawlogEntry))
00218         {
00219           break;  // file EOF
00220         }
00221         tictac.Tic();
00222         mapping.processActionObservation(action, observations);
00223         t_exec = tictac.Tac();
00224         ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec);
00225         ros::Duration(rawlog_play_delay).sleep();
00226         mapping.getCurrentState(robotPose_, LMs_, LM_IDs_, fullState_, fullCov_);
00227 
00228         viz_state();
00229         viz_dataAssociation();
00230         run3Dwindow();
00231       }
00232     }
00233     if (win3d)
00234     {
00235       cout << "\n Close the 3D window to quit the application.\n";
00236       win3d->waitForKey();
00237     }
00238     return true;
00239   }
00240 }
00241 
00242 // Local function to force the axis to be right handed for 2D. Based on the one from ecl_statistics
00243 void EKFslamWrapper::makeRightHanded(Eigen::Matrix2d& eigenvectors, Eigen::Vector2d& eigenvalues)
00244 {
00245   // Note that sorting of eigenvalues may end up with left-hand coordinate system.
00246   // So here we correctly sort it so that it does end up being righ-handed and normalised.
00247   Eigen::Vector3d c0;
00248   c0.setZero();
00249   c0.head<2>() = eigenvectors.col(0);
00250   c0.normalize();
00251   Eigen::Vector3d c1;
00252   c1.setZero();
00253   c1.head<2>() = eigenvectors.col(1);
00254   c1.normalize();
00255   Eigen::Vector3d cc = c0.cross(c1);
00256   if (cc[2] < 0)
00257   {
00258     eigenvectors << c1.head<2>(), c0.head<2>();
00259     double e = eigenvalues[0];
00260     eigenvalues[0] = eigenvalues[1];
00261     eigenvalues[1] = e;
00262   }
00263   else
00264   {
00265     eigenvectors << c0.head<2>(), c1.head<2>();
00266   }
00267 }
00268 
00269 void EKFslamWrapper::computeEllipseOrientationScale2D(tf::Quaternion& orientation, Eigen::Vector2d& scale,
00270                                                       const mrpt::math::CMatrixDouble covariance)
00271 {
00272   tf::Matrix3x3 tf3d;
00273   Eigen::Vector2d eigenvalues(Eigen::Vector2d::Identity());
00274   Eigen::Matrix2d eigenvectors(Eigen::Matrix2d::Zero());
00275 
00276   // NOTE: The SelfAdjointEigenSolver only references the lower triangular part of the covariance matrix
00277   Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> eigensolver(covariance);
00278   // Compute eigenvectors and eigenvalues
00279   if (eigensolver.info() == Eigen::Success)
00280   {
00281     eigenvalues = eigensolver.eigenvalues();
00282     eigenvectors = eigensolver.eigenvectors();
00283   }
00284   else
00285   {
00286     ROS_ERROR_STREAM("failed to compute eigen vectors/values for position. Is the covariance matrix correct?");
00287     eigenvalues = Eigen::Vector2d::Zero();  // Setting the scale to zero will hide it on the screen
00288     eigenvectors = Eigen::Matrix2d::Identity();
00289   }
00290 
00291   // Be sure we have a right-handed orientation system
00292   makeRightHanded(eigenvectors, eigenvalues);
00293 
00294   // Rotation matrix around  z axis
00295   tf3d.setValue(eigenvectors(0, 0), eigenvectors(0, 1), 0, eigenvectors(1, 0), eigenvectors(1, 1), 0, 0, 0, 1);
00296 
00297   // get orientation from rotation matrix
00298   tf3d.getRotation(orientation);
00299   // get scale
00300   scale[0] = eigenvalues[0];
00301   scale[1] = eigenvalues[1];
00302 }
00303 
00304 void EKFslamWrapper::viz_dataAssociation()
00305 {
00306   // robot pose
00307   mrpt::poses::CPose3D robotPose;
00308   robotPose = CPose3D(robotPose_.mean);
00309   geometry_msgs::Point pointRobotPose;
00310   pointRobotPose.z = 0;
00311   pointRobotPose.x = robotPose.x();
00312   pointRobotPose.y = robotPose.y();
00313 
00314   // visualization of the data association
00315   visualization_msgs::MarkerArray ma;
00316   visualization_msgs::Marker line_strip;
00317 
00318   line_strip.header.frame_id = "/map";
00319   line_strip.header.stamp = ros::Time::now();
00320 
00321   line_strip.id = 0;
00322   line_strip.type = visualization_msgs::Marker::LINE_STRIP;
00323   line_strip.action = visualization_msgs::Marker::ADD;
00324 
00325   line_strip.lifetime = ros::Duration(0.1);
00326   line_strip.pose.position.x = 0;
00327   line_strip.pose.position.y = 0;
00328   line_strip.pose.position.z = 0;
00329   line_strip.pose.orientation.x = 0.0;
00330   line_strip.pose.orientation.y = 0.0;
00331   line_strip.pose.orientation.z = 0.0;
00332   line_strip.pose.orientation.w = 1.0;
00333   line_strip.scale.x = 0.02;  // line uses only x component
00334   line_strip.scale.y = 0.0;
00335   line_strip.scale.z = 0.0;
00336   line_strip.color.a = 1.0;
00337   line_strip.color.r = 1.0;
00338   line_strip.color.g = 1.0;
00339   line_strip.color.b = 1.0;
00340 
00341   // Draw latest data association:
00342   const CRangeBearingKFSLAM2D::TDataAssocInfo& da = mapping.getLastDataAssociation();
00343 
00344   for (auto it = da.results.associations.begin(); it != da.results.associations.end(); ++it)
00345   {
00346     const prediction_index_t idxPred = it->second;
00347     // This index must match the internal list of features in the map:
00348     CRangeBearingKFSLAM2D::KFArray_FEAT featMean;
00349     mapping.getLandmarkMean(idxPred, featMean);
00350 
00351     line_strip.points.clear();
00352     line_strip.points.push_back(pointRobotPose);
00353     geometry_msgs::Point pointLm;
00354     pointLm.z = 0.0;
00355     pointLm.x = featMean[0];
00356     pointLm.y = featMean[1];
00357     line_strip.points.push_back(pointLm);
00358     ma.markers.push_back(line_strip);
00359     line_strip.id++;
00360   }
00361 
00362   data_association_viz_pub_.publish(ma);
00363 }
00364 void EKFslamWrapper::viz_state()
00365 {
00366   visualization_msgs::MarkerArray ma;
00367   visualization_msgs::Marker marker;
00368   marker.header.frame_id = "/map";
00369   marker.id = 0;
00370   marker.type = visualization_msgs::Marker::SPHERE;
00371   marker.action = visualization_msgs::Marker::ADD;
00372   marker.lifetime = ros::Duration(0);
00373 
00374   // get the covariance matrix 2x2 for each ellipsoid including robot pose
00375   mrpt::opengl::CSetOfObjectsPtr objs;
00376   objs = mrpt::opengl::CSetOfObjects::Create();
00377   mapping.getAs3DObject(objs);
00378 
00379   // Count the number of landmarks
00380   int objs_counter = 0;
00381   while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter))
00382   {
00383     objs_counter++;
00384   }
00385 
00386   mrpt::opengl::CEllipsoidPtr landmark;
00387   for (size_t i = 0; i < objs_counter; i++)
00388   {
00389     landmark = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
00390 
00391     mrpt::math::CMatrixDouble covariance = landmark->getCovMatrix();
00392     float quantiles = landmark->getQuantiles();
00393 
00394     // mean position
00395         CPose3D pose = mrpt::poses::CPose3D(landmark->getPose());  // pose of the robot and landmarks (x,y,z=0)
00396 
00397     // covariance ellipses
00398     tf::Quaternion orientation;
00399     Eigen::Vector2d scale;
00400 
00401     computeEllipseOrientationScale2D(orientation, scale, covariance);
00402 
00403     marker.id++;
00404     marker.color.a = 1.0;
00405     if (i == 0)
00406     {  // robot position
00407       marker.color.r = 1.0;
00408       marker.color.g = 0.0;
00409       marker.color.b = 0.0;
00410     }
00411     else
00412     {
00413       marker.color.r = 0.0;
00414       marker.color.g = 0.0;
00415       marker.color.b = 1.0;
00416     }
00417     marker.type = visualization_msgs::Marker::SPHERE;
00418     marker.pose.position.x = pose.x();
00419     marker.pose.position.y = pose.y();
00420     marker.pose.position.z = 0;
00421     marker.pose.orientation.x = orientation.x();
00422     marker.pose.orientation.y = orientation.y();
00423     marker.pose.orientation.z = orientation.z();
00424     marker.pose.orientation.w = orientation.w();
00425     marker.scale.x = ellipse_scale_ * quantiles * sqrt(scale[0]);
00426     marker.scale.y = ellipse_scale_ * quantiles * sqrt(scale[1]);
00427     marker.scale.z = 0.00001;  // Z can't be 0, limitation of ROS
00428     ma.markers.push_back(marker);
00429 
00430     marker.id++;
00431     marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00432     if (i == 0)
00433     {
00434       marker.text = "robot";
00435     }
00436     else
00437     {
00438       marker.text = std::to_string(LM_IDs_[i]);
00439     }
00440     marker.pose.position.x = pose.x();
00441     marker.pose.position.y = pose.y();
00442     marker.pose.position.z = 0.1;
00443     marker.color.r = 1.0;
00444     marker.color.g = 1.0;
00445     marker.color.b = 1.0;
00446     marker.scale.x = 0.3;
00447     marker.scale.y = 0.3;
00448     marker.scale.z = 0.3;
00449     ma.markers.push_back(marker);
00450   }
00451 
00452   state_viz_pub_.publish(ma);
00453 }
00454 
00455 void EKFslamWrapper::publishTF()
00456 {
00457   mapping.getCurrentState(robotPose_, LMs_, LM_IDs_, fullState_, fullCov_);
00458   // Most of this code was copy and pase from ros::amcl
00459   mrpt::poses::CPose3D robotPose;
00460   robotPose = CPose3D(robotPose_.mean);
00461 
00462   tf::Stamped<tf::Pose> odom_to_map;
00463   tf::Transform tmp_tf;
00464   ros::Time stamp;
00465   mrpt_bridge::convert(timeLastUpdate_, stamp);
00466   mrpt_bridge::convert(robotPose, tmp_tf);
00467 
00468   try
00469   {
00470     tf::Stamped<tf::Pose> tmp_tf_stamped(tmp_tf.inverse(), stamp, base_frame_id);
00471     listenerTF_.transformPose(odom_frame_id, tmp_tf_stamped, odom_to_map);
00472   }
00473   catch (tf::TransformException)
00474   {
00475     ROS_INFO("Failed to subtract global_frame (%s) from odom_frame (%s)", global_frame_id.c_str(),
00476              odom_frame_id.c_str());
00477     return;
00478   }
00479 
00480   tf::Transform latest_tf_ =
00481       tf::Transform(tf::Quaternion(odom_to_map.getRotation()), tf::Point(odom_to_map.getOrigin()));
00482 
00483   // We want to send a transform that is good up until a
00484   // tolerance time so that odom can be used
00485   ros::Duration transform_tolerance_(0.1);
00486   ros::Time transform_expiration = (stamp + transform_tolerance_);
00487   tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(), transform_expiration, global_frame_id, odom_frame_id);
00488   tf_broadcaster_.sendTransform(tmp_tf_stamped);
00489 }


mrpt_ekf_slam_2d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Sun Sep 17 2017 03:01:57