Go to the documentation of this file.00001
00002
00003
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
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
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 mapping.logRegisterCallback(static_cast<output_logger_callback_t>(&mrpt_bridge::mrptToROSLoggerCallback));
00055 #endif
00056
00057
00058 SHOW_3D_LIVE = iniFile.read_bool("MappingApplication", "SHOW_3D_LIVE", false);
00059 CAMERA_3DSCENE_FOLLOWS_ROBOT = iniFile.read_bool("MappingApplication", "CAMERA_3DSCENE_FOLLOWS_ROBOT", false);
00060 }
00061
00062 void EKFslam::observation(CSensoryFramePtr _sf, CObservationOdometryPtr _odometry)
00063 {
00064 action = CActionCollection::Create();
00065 CActionRobotMovement2D odom_move;
00066 odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
00067
00068 if (_odometry)
00069 {
00070 if (odomLastObservation_.empty())
00071 {
00072 odomLastObservation_ = _odometry->odometry;
00073 }
00074
00075 mrpt::poses::CPose2D incOdoPose = _odometry->odometry - odomLastObservation_;
00076 odomLastObservation_ = _odometry->odometry;
00077 odom_move.computeFromOdometry(incOdoPose, motion_model_options_);
00078 action->insert(odom_move);
00079 }
00080 else if (use_motion_model_default_options_)
00081 {
00082 odom_move.computeFromOdometry(mrpt::poses::CPose2D(0, 0, 0), motion_model_default_options_);
00083 action->insert(odom_move);
00084 }
00085 }
00086
00087 void EKFslam::init3Dwindow()
00088 {
00089 #if MRPT_HAS_WXWIDGETS
00090 if (SHOW_3D_LIVE)
00091 {
00092 win3d = mrpt::gui::CDisplayWindow3D::Create("KF-SLAM live view", 800, 500);
00093 }
00094 #endif
00095 }
00096
00097 void EKFslam::run3Dwindow()
00098 {
00099
00100 if (SHOW_3D_LIVE && win3d.present())
00101 {
00102 mapping.getCurrentState(robotPose_, LMs_, LM_IDs_, fullState_, fullCov_);
00103
00104
00105
00106 const CPose3D robotPoseMean3D = CPose3D(robotPose_.mean);
00107
00108
00109 meanPath.push_back(TPose3D(robotPoseMean3D));
00110
00111
00112 COpenGLScenePtr scene3D = COpenGLScene::Create();
00113 opengl::CGridPlaneXYPtr grid = opengl::CGridPlaneXY::Create(-1000, 1000, -1000, 1000, 0, 5);
00114 grid->setColor(0.4, 0.4, 0.4);
00115 scene3D->insert(grid);
00116
00117
00118 opengl::CSetOfLinesPtr linesPath = opengl::CSetOfLines::Create();
00119 linesPath->setColor(1, 0, 0);
00120 TPose3D init_pose;
00121 if (!meanPath.empty())
00122 {
00123 init_pose = TPose3D(CPose3D(meanPath[0]));
00124 int path_decim = 0;
00125 for (vector<TPose3D>::iterator it = meanPath.begin(); it != meanPath.end(); ++it)
00126 {
00127 linesPath->appendLine(init_pose, *it);
00128 init_pose = *it;
00129 if (++path_decim > 10)
00130 {
00131 path_decim = 0;
00132 mrpt::opengl::CSetOfObjectsPtr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(0.3f, 2.0f);
00133 xyz->setPose(CPose3D(*it));
00134 scene3D->insert(xyz);
00135 }
00136 }
00137 scene3D->insert(linesPath);
00138 }
00139
00140
00141 mrpt::opengl::CSetOfObjectsPtr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(1.0, 2.5);
00142 xyz->setPose(robotPoseMean3D);
00143 scene3D->insert(xyz);
00144
00145
00146 if (CAMERA_3DSCENE_FOLLOWS_ROBOT)
00147 {
00148 win3d->setCameraPointingToPoint(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z());
00149 }
00150
00151
00152 const CRangeBearingKFSLAM2D::TDataAssocInfo &da = mapping.getLastDataAssociation();
00153 mrpt::opengl::CSetOfLinesPtr lins = mrpt::opengl::CSetOfLines::Create();
00154 lins->setLineWidth(1.2);
00155 lins->setColor(1, 1, 1);
00156 for (std::map<observation_index_t, prediction_index_t>::const_iterator it = da.results.associations.begin();
00157 it != da.results.associations.end(); ++it)
00158 {
00159 const prediction_index_t idxPred = it->second;
00160
00161 CRangeBearingKFSLAM2D::KFArray_FEAT featMean;
00162 mapping.getLandmarkMean(idxPred, featMean);
00163
00164 TPoint3D featMean3D;
00165 landmark_to_3d(featMean, featMean3D);
00166
00167 lins->appendLine(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z(), featMean3D.x, featMean3D.y,
00168 featMean3D.z);
00169 }
00170 scene3D->insert(lins);
00171
00172
00173 opengl::CSetOfObjectsPtr objs = opengl::CSetOfObjects::Create();
00174 mapping.getAs3DObject(objs);
00175 scene3D->insert(objs);
00176
00177 mrpt::opengl::COpenGLScenePtr &scn = win3d->get3DSceneAndLock();
00178 scn = scene3D;
00179
00180 win3d->unlockAccess3DScene();
00181 win3d->repaint();
00182 }
00183 }
00184 void EKFslam::landmark_to_3d(const CRangeBearingKFSLAM2D::KFArray_FEAT &lm, TPoint3D &p)
00185 {
00186 p.x = lm[0];
00187 p.y = lm[1];
00188 p.z = 0;
00189 }