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.5,
    44                         bool  run_first_map_estimation_now=
true      59                 virtual void getAs3DObject( mrpt::opengl::CSetOfObjectsPtr &outObj ) 
const MRPT_OVERRIDE;
    62                 virtual void  getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr    &meanObj, mrpt::opengl::CSetOfObjectsPtr        &varObj ) 
const MRPT_OVERRIDE;
    68                 virtual 
bool   dem_get_z_by_cell(const 
size_t cx, const 
size_t cy, 
double &z_out) const  
MRPT_OVERRIDE;
    69                 virtual 
bool   dem_get_z(const 
double x, const 
double y, 
double &z_out) const  
MRPT_OVERRIDE;
    74                         return &insertionOptions;
    79                 bool  internal_insertObservation( const 
mrpt::obs::CObservation *obs, const 
mrpt::poses::CPose3D *robotPose = NULL ) 
MRPT_OVERRIDE;
    80                 double internal_computeObservationLikelihood( const 
mrpt::obs::CObservation *obs, const 
mrpt::poses::CPose3D &takenFrom ) 
MRPT_OVERRIDE;
    83                         bool    run_map_estimation_at_ctor;  
    84                         double  min_x,max_x,min_y,max_y,resolution;     
 Extra params for insertIndividualPoint() 
 
#define MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
 
#define MRPT_OVERRIDE
C++11 "override" for virtuals: 
 
TMapRepresentation
The type of map representation to be used, see CRandomFieldGridMap2D for a discussion. 
 
CHeightGridMap2D_MRF represents digital-elevation-model over a 2D area, with uncertainty, based on a Markov-Random-Field (MRF) estimator. 
 
This class allows loading and storing values and vectors of different types from a configuration text...
 
Parameters related with inserting observations into the map. 
 
Parameters common to any derived class. 
 
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
 
#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...
 
GLsizei const GLchar ** string
 
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries. 
 
#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...
 
Virtual base class for Digital Elevation Model (DEM) maps. 
 
GLsizei GLsizei GLchar * source
 
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
 
GLenum const GLfloat * params
 
#define MAP_DEFINITION_START(_CLASS_NAME_, _LINKAGE_)
Add a MAP_DEFINITION_START() ... 
 
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...