8 #if MRPT_VERSION >= 0x150 14 #if MRPT_VERSION>=0x150 15 #define gausianModel gaussianModel // a typo was fixed in 1.5.0 47 mapping.KF_options.dumpToConsole();
48 mapping.options.dumpToConsole();
50 #if MRPT_VERSION >= 0x150 53 mapping.logging_enable_console_output =
false;
55 #if MRPT_VERSION >= 0x199 69 action = CActionCollection::Create();
70 CActionRobotMovement2D odom_move;
71 odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
94 #if MRPT_HAS_WXWIDGETS 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);
130 for (vector<TPose3D>::iterator it =
meanPath.begin(); it !=
meanPath.end(); ++it)
132 linesPath->appendLine(init_pose, *it);
134 if (++path_decim > 10)
139 scene3D->insert(xyz);
142 scene3D->insert(linesPath);
147 xyz->setPose(robotPoseMean3D);
148 scene3D->insert(xyz);
153 win3d->setCameraPointingToPoint(robotPoseMean3D.
x(), robotPoseMean3D.
y(), robotPoseMean3D.z());
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();
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
static CDisplayWindow3DPtr Create(const std::string &windowCaption, unsigned int initialWindowWidth=400, unsigned int initialWindowHeight=300)
CVectorDouble fullState_
full state vector
CMatrixDouble fullCov_
full covariance matrix
static CSetOfLinesPtr Create(const std::vector< mrpt::math::TSegment3D > &sgms, const bool antiAliasing=true)
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
bool read_bool(const std::string §ion, 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)
VerbosityLevel rosLoggerLvlToMRPTLoggerLvl(log4cxx::LevelPtr lvl)
GLenum GLenum GLenum GLenum mapping
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
size_t prediction_index_t
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.
void mrptToROSLoggerCallback_mrpt_15(const std::string &msg, const VerbosityLevel level, const std::string &loggerName, const mrpt::system::TTimeStamp timestamp, void *userParam)
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
TDataAssociationResults results
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f