8 #if MRPT_VERSION >= 0x150 9 #include <mrpt_bridge/utils.h> 14 #if MRPT_VERSION>=0x150 15 #define gausianModel gaussianModel // a typo was fixed in 1.5.0 42 CConfigFile iniFile(ini_filename);
47 mapping.KF_options.dumpToConsole();
48 mapping.options.dumpToConsole();
50 #if MRPT_VERSION >= 0x150 52 mapping.setVerbosityLevel(mrpt_bridge::rosLoggerLvlToMRPTLoggerLvl(ros_logger->getLevel()));
53 mapping.logging_enable_console_output =
false;
55 #if MRPT_VERSION >= 0x199 56 mapping.logRegisterCallback(static_cast<output_logger_callback_t>(&mrpt_bridge::mrptToROSLoggerCallback));
58 mapping.logRegisterCallback(static_cast<output_logger_callback_t>(&mrpt_bridge::mrptToROSLoggerCallback_mrpt_15));
63 SHOW_3D_LIVE = iniFile.read_bool(
"MappingApplication",
"SHOW_3D_LIVE",
false);
69 action = CActionCollection::Create();
70 CActionRobotMovement2D odom_move;
71 odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
94 #if MRPT_HAS_WXWIDGETS 97 win3d = mrpt::gui::CDisplayWindow3D::Create(
"KF-SLAM live view", 800, 500);
111 const CPose3D robotPoseMean3D = CPose3D(
robotPose_.mean);
114 meanPath.push_back(mrpt_bridge::p2t(robotPoseMean3D));
117 COpenGLScene::Ptr scene3D = COpenGLScene::Create();
118 opengl::CGridPlaneXY::Ptr grid = opengl::CGridPlaneXY::Create(-1000, 1000, -1000, 1000, 0, 5);
119 grid->setColor(0.4, 0.4, 0.4);
120 scene3D->insert(grid);
123 opengl::CSetOfLines::Ptr linesPath = opengl::CSetOfLines::Create();
124 linesPath->setColor(1, 0, 0);
128 init_pose = mrpt_bridge::p2t(CPose3D(
meanPath[0]));
130 for (vector<TPose3D>::iterator it =
meanPath.begin(); it !=
meanPath.end(); ++it)
132 linesPath->appendLine(init_pose, *it);
134 if (++path_decim > 10)
137 mrpt::opengl::CSetOfObjects::Ptr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(0.3
f, 2.0
f);
138 xyz->setPose(CPose3D(*it));
139 scene3D->insert(xyz);
142 scene3D->insert(linesPath);
146 mrpt::opengl::CSetOfObjects::Ptr xyz = mrpt::opengl::stock_objects::CornerXYZSimple(1.0, 2.5);
147 xyz->setPose(robotPoseMean3D);
148 scene3D->insert(xyz);
153 win3d->setCameraPointingToPoint(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z());
157 const CRangeBearingKFSLAM2D::TDataAssocInfo &da =
mapping.getLastDataAssociation();
158 mrpt::opengl::CSetOfLines::Ptr lins = mrpt::opengl::CSetOfLines::Create();
159 lins->setLineWidth(1.2);
160 lins->setColor(1, 1, 1);
161 for (std::map<observation_index_t, prediction_index_t>::const_iterator it = da.results.associations.begin();
162 it != da.results.associations.end(); ++it)
164 const prediction_index_t idxPred = it->second;
166 CRangeBearingKFSLAM2D::KFArray_FEAT featMean;
167 mapping.getLandmarkMean(idxPred, featMean);
172 lins->appendLine(robotPoseMean3D.x(), robotPoseMean3D.y(), robotPoseMean3D.z(), featMean3D.x, featMean3D.y,
175 scene3D->insert(lins);
178 opengl::CSetOfObjects::Ptr objs = opengl::CSetOfObjects::Create();
180 scene3D->insert(objs);
182 mrpt::opengl::COpenGLScene::Ptr &scn =
win3d->get3DSceneAndLock();
185 win3d->unlockAccess3DScene();
bool use_motion_model_default_options_
used default odom_params
CVectorDouble fullState_
full state vector
CMatrixDouble fullCov_
full covariance matrix
CPosePDFGaussian robotPose_
current robot pose
void run3Dwindow()
run 3D window update from mrpt lib
mrpt::poses::CPose2D odomLastObservation_
last observation of odometry
std::vector< mrpt::math::TPoint2D > LMs_
vector of the landmarks
void init3Dwindow()
init 3D window from mrpt lib
std::map< unsigned int, CLandmark::TLandmarkID > LM_IDs_
vector of the landmarks ID
CRangeBearingKFSLAM2D mapping
EKF slam 2d class.
bool CAMERA_3DSCENE_FOLLOWS_ROBOT
virtual ~EKFslam()
destructor
vector< TPose3D > meanPath
void observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
calculate the actions from odometry model for current observation
mrpt::gui::CDisplayWindow3D::Ptr win3d
MRPT window.
CActionRobotMovement2D::TMotionModelOptions motion_model_default_options_
used if there are is not odom
void landmark_to_3d(const CRangeBearingKFSLAM2D::KFArray_FEAT &lm, TPoint3D &p)
convert landmark to 3d point
#define ROSCONSOLE_DEFAULT_NAME
void read_iniFile(std::string ini_filename)
read ini file
CActionRobotMovement2D::TMotionModelOptions motion_model_options_
used with odom value motion noise
CActionCollection::Ptr action
actions