mrpt_ekf_slam_3d.cpp
Go to the documentation of this file.
1 /*
2  * File: mrpt_ekf_slam_3d.cpp
3  * Author: Vladislav Tananaev
4  *
5  */
6 
8 #include <ros/console.h>
9 #if MRPT_VERSION >= 0x150
10 #include <mrpt_bridge/utils.h>
11 #endif
12 
14 {
15 #if MRPT_VERSION >= 0x150
16  motion_model_options_.modelSelection = CActionRobotMovement3D::mm6DOF;
17 
18  motion_model_options_.mm6DOFModel.nParticlesCount = 100;
19  motion_model_options_.mm6DOFModel.a1 = 0.114;
20  motion_model_options_.mm6DOFModel.a2 = 0.1114;
21  motion_model_options_.mm6DOFModel.a3 = 0.114;
22  motion_model_options_.mm6DOFModel.a4 = 0.114;
23  motion_model_options_.mm6DOFModel.a5 = 0.13;
24  motion_model_options_.mm6DOFModel.a6 = 0.13;
25  motion_model_options_.mm6DOFModel.a7 = 0.03;
26  motion_model_options_.mm6DOFModel.a8 = 0.03;
27  motion_model_options_.mm6DOFModel.a9 = 0.03;
28  motion_model_options_.mm6DOFModel.a10 = 0.03;
29  motion_model_options_.mm6DOFModel.additional_std_XYZ = 0.005;
30  motion_model_options_.mm6DOFModel.additional_std_angle = 0.0005;
31 #endif
32 
33  // display values
34  SHOW_3D_LIVE = false;
36 }
37 
39 {
40 }
41 
42 void EKFslam::read_iniFile(std::string ini_filename)
43 {
44  CConfigFile iniFile(ini_filename);
45 
46  // Load the config options for mapping:
47  // ----------------------------------------
48  mapping.loadOptions(iniFile);
49  mapping.KF_options.dumpToConsole();
50  mapping.options.dumpToConsole();
51 
52 #if MRPT_VERSION < 0x150
53  mapping.options.verbose = true;
54 #else
55  log4cxx::LoggerPtr ros_logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
56  mapping.setVerbosityLevel(mrpt_bridge::rosLoggerLvlToMRPTLoggerLvl(ros_logger->getLevel()));
57  mapping.logging_enable_console_output = false;
58 #if MRPT_VERSION < 0x199
59  mapping.logRegisterCallback(static_cast<output_logger_callback_t>(&mrpt_bridge::mrptToROSLoggerCallback_mrpt_15));
60 #else
61  mapping.logRegisterCallback(static_cast<output_logger_callback_t>(&mrpt_bridge::mrptToROSLoggerCallback));
62 #endif
63 #endif
64 
65  // read display variables
66  SHOW_3D_LIVE = iniFile.read_bool("MappingApplication", "SHOW_3D_LIVE", false);
67  CAMERA_3DSCENE_FOLLOWS_ROBOT = iniFile.read_bool("MappingApplication", "CAMERA_3DSCENE_FOLLOWS_ROBOT", false);
68 }
69 
70 void EKFslam::observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
71 {
72  action = CActionCollection::Create();
73 
74  CActionRobotMovement3D odom_move;
75 
76  odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
77  if (_odometry)
78  {
80  {
81  odomLastObservation_ = mrpt::poses::CPose3D(_odometry->odometry);
82  }
83 
84  mrpt::poses::CPose3D incOdoPose;
85  incOdoPose.inverseComposeFrom(mrpt::poses::CPose3D(_odometry->odometry), odomLastObservation_);
86  odomLastObservation_ = mrpt::poses::CPose3D(_odometry->odometry);
87 #if MRPT_VERSION >= 0x150
88  odom_move.computeFromOdometry(incOdoPose, motion_model_options_);
89 #else
90  ROS_WARN("Ignoring odometry. This feature requires MRPT>=1.5.0.");
91 #endif
92  action->insert(odom_move);
93  }
94 }
95 
97 {
98 #if MRPT_HAS_WXWIDGETS
99  if (SHOW_3D_LIVE)
100  {
101  win3d = mrpt::gui::CDisplayWindow3D::Create("KF-SLAM live view", 800, 500);
102  }
103 #endif
104 }
105 
107 {
108  // Save 3D view of the filter state:
109  if (SHOW_3D_LIVE && win3d)
110  {
111  mapping.getCurrentState(robotPose_, LMs_, LM_IDs_, fullState_, fullCov_);
112  // Most of this code was copy and pase from ros::amcl
113 
114  // Get the mean robot pose as 3D:
115  const CPose3D robotPoseMean3D = CPose3D(robotPose_.mean);
116 
117  // Build the path:
118  meanPath.push_back(mrpt_bridge::p2t(robotPoseMean3D));
119 
120  // create the scene
121  COpenGLScene::Ptr scene3D = COpenGLScene::Create();
122  opengl::CGridPlaneXY::Ptr grid = opengl::CGridPlaneXY::Create(-1000, 1000, -1000, 1000, 0, 5);
123  grid->setColor(0.4, 0.4, 0.4);
124  scene3D->insert(grid);
125 
126  // Robot path:
127  opengl::CSetOfLines::Ptr linesPath = opengl::CSetOfLines::Create();
128  linesPath->setColor(1, 0, 0);
129  TPose3D init_pose;
130  if (!meanPath.empty())
131  {
132  init_pose = mrpt_bridge::p2t(CPose3D(meanPath[0]));
133  int path_decim = 0;
134  for (vector<TPose3D>::iterator it = meanPath.begin(); it != meanPath.end(); ++it)
135  {
136  linesPath->appendLine(init_pose, *it);
137  init_pose = *it;
138  if (++path_decim > 10)
139  {
140  path_decim = 0;
141  mrpt::opengl::CSetOfObjects::Ptr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(0.3f, 2.0f);
142  xyz->setPose(CPose3D(*it));
143  scene3D->insert(xyz);
144  }
145  }
146  scene3D->insert(linesPath);
147  }
148 
149  // finally a big corner for the latest robot pose:
150  mrpt::opengl::CSetOfObjects::Ptr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(1.0, 2.5);
151  xyz->setPose(robotPoseMean3D);
152  scene3D->insert(xyz);
153 
154  // The camera pointing to the current robot pose:
156  {
157  win3d->setCameraPointingToPoint(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z());
158  }
159 
160  // Draw latest data association:
161  const CRangeBearingKFSLAM::TDataAssocInfo &da = mapping.getLastDataAssociation();
162  mrpt::opengl::CSetOfLines::Ptr lins = mrpt::opengl::CSetOfLines::Create();
163  lins->setLineWidth(1.2);
164  lins->setColor(1, 1, 1);
165  for (std::map<observation_index_t, prediction_index_t>::const_iterator it = da.results.associations.begin();
166  it != da.results.associations.end(); ++it)
167  {
168  const prediction_index_t idxPred = it->second;
169  // This index must match the internal list of features in the map:
170  CRangeBearingKFSLAM::KFArray_FEAT featMean;
171  mapping.getLandmarkMean(idxPred, featMean);
172 
173  TPoint3D featMean3D;
174  landmark_to_3d(featMean, featMean3D);
175  // Line: robot -> landmark:
176  lins->appendLine(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z(), featMean3D.x, featMean3D.y,
177  featMean3D.z);
178  }
179  scene3D->insert(lins);
180 
181  // The current state of KF-SLAM:
182  opengl::CSetOfObjects::Ptr objs = opengl::CSetOfObjects::Create();
183  mapping.getAs3DObject(objs);
184  scene3D->insert(objs);
185 
186  mrpt::opengl::COpenGLScene::Ptr &scn = win3d->get3DSceneAndLock();
187  scn = scene3D;
188 
189  win3d->unlockAccess3DScene();
190  win3d->repaint();
191  }
192 }
193 void EKFslam::landmark_to_3d(const CRangeBearingKFSLAM::KFArray_FEAT &lm, TPoint3D &p)
194 {
195  p.x = lm[0];
196  p.y = lm[1];
197  p.z = lm[2];
198 }
static CDisplayWindow3DPtr Create(const std::string &windowCaption, unsigned int initialWindowWidth=400, unsigned int initialWindowHeight=300)
bool SHOW_3D_LIVE
CVectorDouble fullState_
full state vector
EKFslam()
constructor
CMatrixDouble fullCov_
full covariance matrix
static CSetOfLinesPtr Create(const std::vector< mrpt::math::TSegment3D > &sgms, const bool antiAliasing=true)
std::vector< mrpt::math::TPoint3D > LMs_
vector of the landmarks
CPose3DQuatPDFGaussian robotPose_
current robot pose
void run3Dwindow()
run 3D window update from mrpt lib
#define ROS_WARN(...)
bool read_bool(const std::string &section, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
void init3Dwindow()
init 3D window from mrpt lib
std::map< unsigned int, CLandmark::TLandmarkID > LM_IDs_
vector of the landmarks ID
mrpt::math::TPose3D p2t(const mrpt::poses::CPose3D &p)
CSetOfObjectsPtr OPENGL_IMPEXP CornerXYZSimple(float scale=1.0, float lineWidth=1.0)
CConfigFile * iniFile
VerbosityLevel rosLoggerLvlToMRPTLoggerLvl(log4cxx::LevelPtr lvl)
GLfloat GLfloat p
GLenum GLenum GLenum GLenum mapping
void landmark_to_3d(const CRangeBearingKFSLAM::KFArray_FEAT &lm, TPoint3D &p)
convert landmark to 3d point
bool CAMERA_3DSCENE_FOLLOWS_ROBOT
virtual ~EKFslam()
destructor
void mrptToROSLoggerCallback(const std::string &msg, const VerbosityLevel level, const std::string &loggerName, const mrpt::system::TTimeStamp timestamp)
std::map< observation_index_t, prediction_index_t > associations
mrpt::poses::CPose3D odomLastObservation_
last observation of odometry
size_t prediction_index_t
vector< TPose3D > meanPath
static bool empty()
void observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
calculate the actions from odometry model for current observation
mrpt::gui::CDisplayWindow3D::Ptr win3d
MRPT window.
void inverseComposeFrom(const CPose3D &A, const CPose3D &B)
void mrptToROSLoggerCallback_mrpt_15(const std::string &msg, const VerbosityLevel level, const std::string &loggerName, const mrpt::system::TTimeStamp timestamp, void *userParam)
#define ROSCONSOLE_DEFAULT_NAME
void read_iniFile(std::string ini_filename)
read ini file
CActionCollection::Ptr action
actions
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f


mrpt_ekf_slam_3d
Author(s): Jose Luis, Vladislav Tananaev
autogenerated on Sat May 2 2020 03:44:08