9 #if MRPT_VERSION >= 0x150 15 #if MRPT_VERSION >= 0x150 16 motion_model_options_.modelSelection = CActionRobotMovement3D::mm6DOF;
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;
49 mapping.KF_options.dumpToConsole();
50 mapping.options.dumpToConsole();
52 #if MRPT_VERSION < 0x150 57 mapping.logging_enable_console_output =
false;
58 #if MRPT_VERSION < 0x199 72 action = CActionCollection::Create();
74 CActionRobotMovement3D odom_move;
76 odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
87 #if MRPT_VERSION >= 0x150 88 odom_move.computeFromOdometry(incOdoPose, motion_model_options_);
90 ROS_WARN(
"Ignoring odometry. This feature requires MRPT>=1.5.0.");
98 #if MRPT_HAS_WXWIDGETS 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);
127 opengl::CSetOfLines::Ptr linesPath = opengl::CSetOfLines::Create();
128 linesPath->setColor(1, 0, 0);
134 for (vector<TPose3D>::iterator it =
meanPath.begin(); it !=
meanPath.end(); ++it)
136 linesPath->appendLine(init_pose, *it);
138 if (++path_decim > 10)
143 scene3D->insert(xyz);
146 scene3D->insert(linesPath);
151 xyz->setPose(robotPoseMean3D);
152 scene3D->insert(xyz);
157 win3d->setCameraPointingToPoint(robotPoseMean3D.
x(), robotPoseMean3D.
y(), robotPoseMean3D.z());
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();
170 CRangeBearingKFSLAM::KFArray_FEAT featMean;
171 mapping.getLandmarkMean(idxPred, featMean);
176 lins->appendLine(robotPoseMean3D.
x(), robotPoseMean3D.
y(), robotPoseMean3D.z(), featMean3D.
x, featMean3D.
y,
179 scene3D->insert(lins);
182 opengl::CSetOfObjects::Ptr objs = opengl::CSetOfObjects::Create();
184 scene3D->insert(objs);
186 mrpt::opengl::COpenGLScene::Ptr &scn =
win3d->get3DSceneAndLock();
189 win3d->unlockAccess3DScene();
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)
TDataAssociationResults results
std::vector< mrpt::math::TPoint3D > LMs_
vector of the landmarks
CPose3DQuatPDFGaussian robotPose_
current robot pose
void run3Dwindow()
run 3D window update from mrpt lib
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
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
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