9 #ifndef CMultiMetricMap_H
10 #define CMultiMetricMap_H
35 class TSetOfMetricMapInitializers;
76 virtual
void internal_clear();
84 virtual
bool internal_insertObservation( const
CObservation *obs, const
CPose3D *robotPose = NULL );
101 void loadFromConfigFile(
103 const std::string §ion);
107 void dumpToTextStream(
CStream &out)
const;
128 } likelihoodMapSelection;
198 float getNewStaticPointsRatio(
203 virtual void determineMatching2D(
204 const CMetricMap * otherMap,
211 float compute3DMatchingRatio(
212 const CMetricMap *otherMap,
214 float maxDistForCorr = 0.10f,
215 float maxMahaDistForCorr = 2.0f
220 void saveMetricMapRepresentationToFile(
221 const std::string &filNamePrefix
227 void auxParticleFilterCleanUp();
231 void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &outObj )
const;
237 bool canComputeObservationLikelihood(
const CObservation *obs );
260 TMetricMapInitializer();
280 } occupancyGridMap2D_options;
300 } colourOctoMap_options;
309 } pointsMapOptions_options;
321 } gasGridMap_options;
333 } wifiGridMap_options;
345 } landmarksMap_options;
378 } reflectivityMap_options;
388 } colouredPointsMapOptions_options;
397 } weightedPointsMapOptions_options;
408 std::deque<TMetricMapInitializer>
m_list;
411 size_t size()
const {
return m_list.size(); }
417 iterator
begin() {
return m_list.begin(); }
418 const_iterator
begin()
const {
return m_list.begin(); }
420 iterator
end() {
return m_list.end(); }
421 const_iterator
end()
const {
return m_list.end(); }
649 void loadFromConfigFile(
651 const std::string §ionName);
655 void dumpToTextStream(
CStream &out)
const;
CPointsMap::TLikelihoodOptions likelihoodOpts
//!< Customizable initial likelihood options
TMapRepresentation
The type of map representation to be used, see CRandomFieldGridMap2D for a discussion.
bool enableInsertion_colourPointsMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
Specific options for landmarks maps (mrpt::slam::CLandmarksMap)
TSetOfMetricMapInitializers()
float resolution
See CHeightGridMap2D::CHeightGridMap2D.
COccupancyGridMap2D::TLikelihoodOptions likelihoodOpts
Customizable initial options.
CGasConcentrationGridMap2D::TMapRepresentation mapType
The kind of map representation (see CGasConcentrationGridMap2D::CGasConcentrationGridMap2D) ...
double resolution
The finest resolution of the octomap (default: 0.10 meters)
CWirelessPowerGridMap2D::TMapRepresentation mapType
The kind of map representation (see CWirelessPowerGridMap2D::CWirelessPowerGridMap2D) ...
std::deque< CWirelessPowerGridMap2DPtr > m_wifiGridMaps
CLandmarksMap::TLikelihoodOptions likelihoodOpts
Customizable initial options.
The definition of parameters for generating colors from laser scans.
CHeightGridMap2D::TMapRepresentation mapType
The kind of map representation (see CHeightGridMap2D::CHeightGridMap2D)
This class stores any customizable set of metric maps.
Specific options for 2D grid maps (mrpt::slam::COccupancyGridMap2D)
With this struct options are provided to the observation insertion process.
bool enableInsertion_weightedPointsMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
const_iterator begin() const
COctoMap::TInsertionOptions insertionOpts
Customizable initial options.
Options used when evaluating "computeObservationLikelihood" in the derived classes.
bool enableInsertion_wifiGridMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
CHeightGridMap2D::TInsertionOptions insertionOpts
Customizable initial options.
std::deque< CGasConcentrationGridMap2DPtr > m_gasGridMaps
bool enableInsertion_beaconMap
Default = true (set to false to avoid "insertObservation" to update a given map)
With this struct options are provided to the observation insertion process.
Only specializations of this class are defined for each enum type of interest.
std::deque< CReflectivityGridMap2DPtr > m_reflectivityMaps
CColouredOctoMap::TInsertionOptions insertionOpts
Customizable initial options.
const Scalar * const_iterator
CPointsMap::TInsertionOptions insertionOpts
Customizable initial options for loading the class' own defaults.
std::deque< TMetricMapInitializer >::const_iterator const_iterator
unsigned int m_ID
An auxiliary variable that can be used freely by the users (this will be copied to other maps using t...
std::deque< CColouredOctoMapPtr > m_colourOctoMaps
CMultiMetricMap::TOptions options
This options will be loaded when creating the set of maps in CMultiMetricMap (See CMultiMetricMap::TO...
This struct contains data for choosing the method by which new beacons are inserted in the map...
With this struct options are provided to the likelihood computations.
float resolution
See CWirelessPowerGridMap2D::CWirelessPowerGridMap2D.
COccupancyGridMap2D::TInsertionOptions insertionOpts
Customizable initial options.
Parameters related with inserting observations into the map:
slam::CMultiMetricMap::TOptions::TMapSelectionForLikelihood enum_t
CColouredPointsMap::TColourOptions colourOpts
Customizable initial options for loading the class' own defaults. */.
With this struct options are provided to the observation insertion process.
CPointsMap::TLikelihoodOptions likelihoodOpts
//!< Customizable initial likelihood options
This class allows loading and storing values and vectors of different types from a configuration text...
CPointsMap::TInsertionOptions insertionOpts
Customizable initial options for loading the class' own defaults.
CPointsMap::TInsertionOptions insertionOpts
Customizable initial options for loading the class' own defaults.
std::deque< CMultiMetricMap::TPairIdBeacon > initialBeacons
Initial contents of the map, especified by a set of 3D Beacons with associated IDs.
Declares a virtual base class for all metric maps storage classes.
CBeaconMap::TInsertionOptions insertionOpts
Customizable initial options.
float resolution
See CReflectivityGridMap2DOptions::CReflectivityGridMap2DOptions.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
CColouredPointsMapPtr m_colourPointsMap
bool enableInsertion_gasGridMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
#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...
float resolution
See CGasConcentrationGridMap2D::CGasConcentrationGridMap2D.
static void fill(bimap< enum_t, std::string > &m_map)
Parameters related with inserting observations into the map:
Specific options for wifi grid maps (mrpt::slam::CWirelessPowerGridMap2D)
Declares a class that represents any robot's observation.
A bidirectional version of std::map, declared as bimap and which actually contains two std...
std::deque< COccupancyGridMap2DPtr > m_gridMaps
Specific options for coloured point maps (mrpt::slam::CPointsMap)
std::deque< TMetricMapInitializer >::iterator iterator
bool enableInsertion_colourOctoMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
TMapSelectionForLikelihood
This selects the map to be used when computing the likelihood of an observation.
Parameters for the determination of matchings between point clouds, etc.
CWirelessPowerGridMap2D::TInsertionOptions insertionOpts
Customizable initial options.
bool enableInsertion_octoMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
With this struct options are provided to the likelihood computations.
double resolution
The finest resolution of the octomap (default: 0.10 meters)
std::deque< TMetricMapInitializer > m_list
bool enableInsertion_reflectivityMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
CPointsMap::TLikelihoodOptions likelihoodOpts
//!< Customizable initial likelihood options
A class used to store a 3D point.
CBeaconMap::TLikelihoodOptions likelihoodOpts
Customizable initial options.
std::deque< CHeightGridMap2DPtr > m_heightMaps
float resolution
See COccupancyGridMap2D::COccupancyGridMap2D.
Specific options for landmarks maps (mrpt::slam::CBeaconMap)
bool enableInsertion_gridMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
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...
CColouredOctoMap::TLikelihoodOptions likelihoodOpts
Customizable initial options.
Parameters related with inserting observations into the map.
Specific options for 3D octo maps (mrpt::slam::COctoMap)
Specific options for gas grid maps (mrpt::slam::CGasConcentrationGridMap2D)
Specific options for 3D octo maps (mrpt::slam::COctoMap)
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
bool enableInsertion_landmarksMap
Default = true (set to false to avoid "insertObservation" to update a given map)
A class used to store a 2D pose.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Specific options for height grid maps (mrpt::slam::CHeightGridMap2D)
CReflectivityGridMap2D::TInsertionOptions insertionOpts
Customizable initial options.
CLandmarksMap::TInsertionOptions insertionOpts
Customizable initial options.
Specific options for coloured point maps (mrpt::slam::CPointsMap)
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
Parameters related with inserting observations into the map.
Specific options for point maps (mrpt::slam::CPointsMap)
std::pair< CPoint3D, unsigned int > TPairIdBeacon
bool enableInsertion_pointsMap
Default = true (set to false to avoid "insertObservation" to update a given map)
TRuntimeClassIdPtr metricMapClassType
Set this to CLASS_ID(< class >) where < class > is any CMetricMap derived class.
CWeightedPointsMapPtr m_weightedPointsMap
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
CLandmarksMapPtr m_landmarksMap
Specific options for height grid maps (mrpt::slam::CReflectivityGridMap2D)
CBeaconMapPtr m_beaconMap
TMapRepresentation
The type of map representation to be used.
COctoMap::TLikelihoodOptions likelihoodOpts
Customizable initial options.
Some options for this class:
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
const_iterator end() const
bool m_disableSaveAs3DObject
This value will be copied to the member with the same value in the map, see mrpt::slam::CMetricMap::m...
CGasConcentrationGridMap2D::TInsertionOptions insertionOpts
Customizable initial options.
std::deque< COctoMapPtr > m_octoMaps
Each structure of this kind will determine the kind (and initial configuration) of one map to be buil...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
std::deque< CSimplePointsMapPtr > m_pointsMaps
void push_back(const TMetricMapInitializer &o)
bool enableInsertion_heightMaps
Default = true (set to false to avoid "insertObservation" to update a given map)
With this struct options are provided to the observation likelihood computation process.