Go to the documentation of this file.
10 #ifndef CHeightGridMap2D_MRF_MRF_H
11 #define CHeightGridMap2D_MRF_MRF_H
42 double x_min = -2,
double x_max = 2,
43 double y_min = -2,
double y_max = 2,
double resolution = 0.1,
44 bool run_first_map_estimation_now=
true
61 virtual void getAs3DObject( mrpt::opengl::CSetOfObjectsPtr &outObj )
const MRPT_OVERRIDE;
64 virtual void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &meanObj, mrpt::opengl::CSetOfObjectsPtr &varObj )
const MRPT_OVERRIDE;
70 virtual
bool dem_get_z_by_cell(const
size_t cx, const
size_t cy,
double &z_out) const
MRPT_OVERRIDE;
71 virtual
bool dem_get_z(const
double x, const
double y,
double &z_out) const
MRPT_OVERRIDE;
76 return &insertionOptions;
81 bool internal_insertObservation( const
mrpt::obs::CObservation *obs, const
mrpt::poses::CPose3D *robotPose = NULL )
MRPT_OVERRIDE;
82 double internal_computeObservationLikelihood( const
mrpt::obs::CObservation *obs, const
mrpt::poses::CPose3D &takenFrom )
MRPT_OVERRIDE;
85 bool run_map_estimation_at_ctor;
86 double min_x,max_x,min_y,max_y,resolution;
#define MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
Extra params for insertIndividualPoint()
Virtual base class for Digital Elevation Model (DEM) maps.
Parameters common to any derived class.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CHeightGridMap2D_MRF represents a PDF of gas concentrations over a 2D area.
#define MAP_DEFINITION_START(_CLASS_NAME_, _LINKAGE_)
Add a MAP_DEFINITION_START() ...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
This class allows loading and storing values and vectors of different types from a configuration text...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
TMapRepresentation
The type of map representation to be used, see CRandomFieldGridMap2D for a discussion.
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Parameters related with inserting observations into the map.
Page generated by Doxygen 1.8.17 for MRPT 1.4.0 SVN: at Sat Jan 18 22:37:07 UTC 2020 | | |