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


mrpt_ekf_slam_2d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Thu Jun 6 2019 21:40:15