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


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