mrpt_ekf_slam_2d.cpp
Go to the documentation of this file.
00001 /*
00002  * File: mrpt_ekf_slam_2d.cpp
00003  * Author: Vladislav Tananaev
00004  *
00005  */
00006 
00007 #include "mrpt_ekf_slam_2d/mrpt_ekf_slam_2d.h"
00008 #if MRPT_VERSION >= 0x150
00009 #include <mrpt_bridge/utils.h>
00010 #endif
00011 
00012 EKFslam::EKFslam()
00013 {
00014 #if MRPT_VERSION>=0x150
00015 #define gausianModel gaussianModel    // a typo was fixed in 1.5.0
00016 #endif
00017 
00018   use_motion_model_default_options_ = false;
00019   motion_model_default_options_.modelSelection = CActionRobotMovement2D::mmGaussian;
00020   motion_model_default_options_.gausianModel.minStdXY = 0.10;
00021   motion_model_default_options_.gausianModel.minStdPHI = 2.0;
00022 
00023   motion_model_options_.modelSelection = CActionRobotMovement2D::mmGaussian;
00024   motion_model_options_.gausianModel.a1 = 0.034;
00025   motion_model_options_.gausianModel.a2 = 0.057;
00026   motion_model_options_.gausianModel.a3 = 0.014;
00027   motion_model_options_.gausianModel.a4 = 0.097;
00028   motion_model_options_.gausianModel.minStdXY = 0.005;
00029   motion_model_options_.gausianModel.minStdPHI = 0.05;
00030 
00031   // display values
00032   SHOW_3D_LIVE = false;
00033   CAMERA_3DSCENE_FOLLOWS_ROBOT = false;
00034 }
00035 
00036 EKFslam::~EKFslam()
00037 {
00038 }
00039 
00040 void EKFslam::read_iniFile(std::string ini_filename)
00041 {
00042   CConfigFile iniFile(ini_filename);
00043 
00044   // Load the config options for mapping:
00045   // ----------------------------------------
00046   mapping.loadOptions(iniFile);
00047   mapping.KF_options.dumpToConsole();
00048   mapping.options.dumpToConsole();
00049 
00050 #if MRPT_VERSION >= 0x150
00051   log4cxx::LoggerPtr ros_logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
00052   mapping.setVerbosityLevel(mrpt_bridge::rosLoggerLvlToMRPTLoggerLvl(ros_logger->getLevel()));
00053   mapping.logging_enable_console_output = false;
00054 
00055 #if MRPT_VERSION >= 0x199
00056   mapping.logRegisterCallback(static_cast<output_logger_callback_t>(&mrpt_bridge::mrptToROSLoggerCallback));
00057 #else
00058   mapping.logRegisterCallback(static_cast<output_logger_callback_t>(&mrpt_bridge::mrptToROSLoggerCallback_mrpt_15));
00059 #endif
00060 #endif
00061 
00062   // read display variables
00063   SHOW_3D_LIVE = iniFile.read_bool("MappingApplication", "SHOW_3D_LIVE", false);
00064   CAMERA_3DSCENE_FOLLOWS_ROBOT = iniFile.read_bool("MappingApplication", "CAMERA_3DSCENE_FOLLOWS_ROBOT", false);
00065 }
00066 
00067 void EKFslam::observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
00068 {
00069   action = CActionCollection::Create();
00070   CActionRobotMovement2D odom_move;
00071   odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
00072 
00073   if (_odometry)
00074   {
00075     if (odomLastObservation_.empty())
00076     {
00077       odomLastObservation_ = _odometry->odometry;
00078     }
00079 
00080     mrpt::poses::CPose2D incOdoPose = _odometry->odometry - odomLastObservation_;
00081     odomLastObservation_ = _odometry->odometry;
00082     odom_move.computeFromOdometry(incOdoPose, motion_model_options_);
00083     action->insert(odom_move);
00084   }
00085   else if (use_motion_model_default_options_)
00086   {
00087     odom_move.computeFromOdometry(mrpt::poses::CPose2D(0, 0, 0), motion_model_default_options_);
00088     action->insert(odom_move);
00089   }
00090 }
00091 
00092 void EKFslam::init3Dwindow()
00093 {
00094 #if MRPT_HAS_WXWIDGETS
00095   if (SHOW_3D_LIVE)
00096   {
00097     win3d = mrpt::gui::CDisplayWindow3D::Create("KF-SLAM live view", 800, 500);
00098   }
00099 #endif
00100 }
00101 
00102 void EKFslam::run3Dwindow()
00103 {
00104   // Save 3D view of the filter state:
00105   if (SHOW_3D_LIVE && win3d)
00106   {
00107     mapping.getCurrentState(robotPose_, LMs_, LM_IDs_, fullState_, fullCov_);
00108     // Most of this code was copy and pase from ros::amcl
00109 
00110     // Get the mean robot pose as 3D:
00111     const CPose3D robotPoseMean3D = CPose3D(robotPose_.mean);
00112 
00113     // Build the path:
00114         meanPath.push_back(mrpt_bridge::p2t(robotPoseMean3D));
00115 
00116     // create the scene
00117     COpenGLScene::Ptr scene3D = COpenGLScene::Create();
00118     opengl::CGridPlaneXY::Ptr grid = opengl::CGridPlaneXY::Create(-1000, 1000, -1000, 1000, 0, 5);
00119     grid->setColor(0.4, 0.4, 0.4);
00120     scene3D->insert(grid);
00121 
00122     // Robot path:
00123     opengl::CSetOfLines::Ptr linesPath = opengl::CSetOfLines::Create();
00124     linesPath->setColor(1, 0, 0);
00125     TPose3D init_pose;
00126     if (!meanPath.empty())
00127     {
00128           init_pose = mrpt_bridge::p2t(CPose3D(meanPath[0]));
00129       int path_decim = 0;
00130       for (vector<TPose3D>::iterator it = meanPath.begin(); it != meanPath.end(); ++it)
00131       {
00132         linesPath->appendLine(init_pose, *it);
00133         init_pose = *it;
00134         if (++path_decim > 10)
00135         {
00136           path_decim = 0;
00137           mrpt::opengl::CSetOfObjects::Ptr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(0.3f, 2.0f);
00138           xyz->setPose(CPose3D(*it));
00139           scene3D->insert(xyz);
00140         }
00141       }
00142       scene3D->insert(linesPath);
00143     }
00144 
00145     // finally a big corner for the latest robot pose:
00146     mrpt::opengl::CSetOfObjects::Ptr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(1.0, 2.5);
00147     xyz->setPose(robotPoseMean3D);
00148     scene3D->insert(xyz);
00149 
00150     // The camera pointing to the current robot pose:
00151     if (CAMERA_3DSCENE_FOLLOWS_ROBOT)
00152     {
00153       win3d->setCameraPointingToPoint(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z());
00154     }
00155 
00156     // Draw latest data association:
00157     const CRangeBearingKFSLAM2D::TDataAssocInfo &da = mapping.getLastDataAssociation();
00158     mrpt::opengl::CSetOfLines::Ptr lins = mrpt::opengl::CSetOfLines::Create();
00159     lins->setLineWidth(1.2);
00160     lins->setColor(1, 1, 1);
00161     for (std::map<observation_index_t, prediction_index_t>::const_iterator it = da.results.associations.begin();
00162          it != da.results.associations.end(); ++it)
00163     {
00164       const prediction_index_t idxPred = it->second;
00165       // This index must match the internal list of features in the map:
00166       CRangeBearingKFSLAM2D::KFArray_FEAT featMean;
00167       mapping.getLandmarkMean(idxPred, featMean);
00168 
00169       TPoint3D featMean3D;
00170       landmark_to_3d(featMean, featMean3D);
00171       // Line: robot -> landmark:
00172       lins->appendLine(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z(), featMean3D.x, featMean3D.y,
00173                        featMean3D.z);
00174     }
00175     scene3D->insert(lins);
00176 
00177     // The current state of KF-SLAM:
00178     opengl::CSetOfObjects::Ptr objs = opengl::CSetOfObjects::Create();
00179     mapping.getAs3DObject(objs);
00180     scene3D->insert(objs);
00181 
00182     mrpt::opengl::COpenGLScene::Ptr &scn = win3d->get3DSceneAndLock();
00183     scn = scene3D;
00184 
00185     win3d->unlockAccess3DScene();
00186     win3d->repaint();
00187   }
00188 }
00189 void EKFslam::landmark_to_3d(const CRangeBearingKFSLAM2D::KFArray_FEAT &lm, TPoint3D &p)
00190 {
00191   p.x = lm[0];
00192   p.y = lm[1];
00193   p.z = 0;
00194 }


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