Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Classes | Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
mrpt::maps::COctoMap Class Reference

Detailed Description

A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ library.

This version only stores occupancy information at each octree node. See the base class mrpt::maps::COctoMapBase.

See also
CMetricMap, the example in "MRPT/samples/octomap_simple"

Definition at line 35 of file maps/COctoMap.h.

#include <mrpt/maps/COctoMap.h>

Inheritance diagram for mrpt::maps::COctoMap:
Inheritance graph

Classes

struct  TMapDefinition
 
struct  TMapDefinitionBase
 

Public Types

typedef COctoMapBase< octomap::OcTree, octomap::OcTreeNode > myself_t
 The type of this MRPT class.
 
typedef octomap::OcTree octree_t
 The type of the octree class in the "octomap" library.
 
typedef octomap::OcTreeNode octree_node_t
 The type of nodes in the octree, in the "octomap" library.
 

Public Member Functions

 COctoMap (const double resolution=0.10)
 Default constructor.
 
virtual ~COctoMap ()
 Destructor.
 
virtual void getAsOctoMapVoxels (mrpt::opengl::COctoMapVoxels &gl_obj) const MRPT_OVERRIDE
 Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object.
 
octomap::OcTree & getOctomap ()
 Get a reference to the internal octomap object.
 
virtual bool isEmpty () const MRPT_OVERRIDE
 Returns true if the map is empty/no observation has been inserted.
 
virtual void saveMetricMapRepresentationToFile (const std::string &filNamePrefix) const MRPT_OVERRIDE
 This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).
 
virtual void getAs3DObject (mrpt::opengl::CSetOfObjectsPtr &outObj) const MRPT_OVERRIDE
 Returns a 3D object representing the map.
 
bool isPointWithinOctoMap (const float x, const float y, const float z) const
 Check whether the given point lies within the volume covered by the octomap (that is, whether it is "mapped")
 
bool getPointOccupancy (const float x, const float y, const float z, double &prob_occupancy) const
 Get the occupancy probability [0,1] of a point.
 
void updateVoxel (const double x, const double y, const double z, bool occupied)
 Manually updates the occupancy of the voxel at (x,y,z) as being occupied (true) or free (false), using the log-odds parameters in insertionOptions.
 
void insertPointCloud (const CPointsMap &ptMap, const float sensor_x, const float sensor_y, const float sensor_z)
 Update the octomap with a 2D or 3D scan, given directly as a point cloud and the 3D location of the sensor (the origin of the rays) in this map's frame of reference.
 
void insertRay (const float end_x, const float end_y, const float end_z, const float sensor_x, const float sensor_y, const float sensor_z)
 Just like insertPointCloud but with a single ray.
 
bool castRay (const mrpt::math::TPoint3D &origin, const mrpt::math::TPoint3D &direction, mrpt::math::TPoint3D &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
 Performs raycasting in 3d, similar to computeRay().
 
void clear ()
 Erase all the contents of the map.
 
void loadFromProbabilisticPosesAndObservations (const mrpt::maps::CSimpleMap &Map)
 Load the map contents from a CSimpleMap object, erasing all previous content of the map.
 
void loadFromSimpleMap (const mrpt::maps::CSimpleMap &Map)
 Load the map contents from a CSimpleMap object, erasing all previous content of the map.
 
bool insertObservation (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)
 Insert the observation information into this map.
 
bool insertObservationPtr (const mrpt::obs::CObservationPtr &obs, const mrpt::poses::CPose3D *robotPose=NULL)
 A wrapper for smart pointers, just calls the non-smart pointer version.
 
double computeObservationLikelihood (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom)
 Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
 
double computeObservationLikelihood (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
virtual bool canComputeObservationLikelihood (const mrpt::obs::CObservation *obs)
 Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.
 
bool canComputeObservationLikelihood (const mrpt::obs::CObservationPtr &obs)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
double computeObservationsLikelihood (const mrpt::obs::CSensoryFrame &sf, const mrpt::poses::CPose2D &takenFrom)
 Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFrame.
 
bool canComputeObservationsLikelihood (const mrpt::obs::CSensoryFrame &sf)
 Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.
 
virtual void determineMatching2D (const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const
 Computes the matching between this and another 2D point map, which includes finding:
 
virtual void determineMatching3D (const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const
 Computes the matchings between this and another 3D points map - method used in 3D-ICP.
 
virtual float compute3DMatchingRatio (const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const
 Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps.
 
virtual void auxParticleFilterCleanUp ()
 This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
 
virtual float squareDistanceToClosestCorrespondence (float x0, float y0) const
 Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.
 
virtual const mrpt::maps::CSimplePointsMapgetAsSimplePointsMap () const
 If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points map, return it.
 
virtual mrpt::maps::CSimplePointsMapgetAsSimplePointsMap ()
 
Direct access to octomap library methods
double getResolution () const
 
unsigned int getTreeDepth () const
 
size_t size () const
 
size_t memoryUsage () const
 
size_t memoryUsageNode () const
 
size_t memoryFullGrid () const
 
double volume () const
 
void getMetricSize (double &x, double &y, double &z)
 Size of OcTree (all known space) in meters for x, y and z dimension.
 
void getMetricSize (double &x, double &y, double &z) const
 Size of OcTree (all known space) in meters for x, y and z dimension.
 
void getMetricMin (double &x, double &y, double &z)
 minimum value of the bounding box of all known space in x, y, z
 
void getMetricMin (double &x, double &y, double &z) const
 minimum value of the bounding box of all known space in x, y, z
 
void getMetricMax (double &x, double &y, double &z)
 maximum value of the bounding box of all known space in x, y, z
 
void getMetricMax (double &x, double &y, double &z) const
 maximum value of the bounding box of all known space in x, y, z
 
size_t calcNumNodes () const
 Traverses the tree to calculate the total number of nodes.
 
size_t getNumLeafNodes () const
 Traverses the tree to calculate the total number of leaf nodes.
 

Public Attributes

TInsertionOptions insertionOptions
 The options used when inserting observations in the map.
 
TLikelihoodOptions likelihoodOptions
 
TRenderingOptions renderingOptions
 
TMapGenericParams genericMapParams
 Common params to all maps.
 

Static Public Attributes

RTTI stuff <br>
static const mrpt::utils::TRuntimeClassId classCMetricMap
 

Protected Member Functions

bool internal_insertObservation (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose) MRPT_OVERRIDE
 Internal method called by insertObservation()
 
virtual void internal_clear () MRPT_OVERRIDE
 Internal method called by clear()
 
bool internal_build_PointCloud_for_observation (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose, octomap::point3d &point3d_sensorPt, octomap::Pointcloud &ptr_scan) const
 Builds the list of 3D points in global coordinates for a generic observation.
 
void publishEvent (const mrptEvent &e) const
 Called when you want this object to emit an event to all the observers currently subscribed to this object.
 
bool hasSubscribers () const
 Can be called by a derived class before preparing an event for publishing with publishEvent to determine if there is no one subscribed, so it can save the wasted time preparing an event that will be not read.
 
CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const MRPT_OVERRIDE
 
void readFromStream (mrpt::utils::CStream &in, int version) MRPT_OVERRIDE
 

Protected Attributes

octomap::OcTree m_octomap
 The actual octo-map object.
 

Private Member Functions

virtual double internal_computeObservationLikelihood (const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) MRPT_OVERRIDE
 Internal method called by computeObservationLikelihood()
 
virtual bool internal_canComputeObservationLikelihood (const mrpt::obs::CObservation *obs)
 Internal method called by canComputeObservationLikelihood()
 
virtual void OnPostSuccesfulInsertObs (const mrpt::obs::CObservation *)
 Hook for each time a "internal_insertObservation" returns "true" This is called automatically from insertObservation() when internal_insertObservation returns true.
 
void internal_observer_begin (CObserver *)
 
void internal_observer_end (CObserver *)
 

Private Attributes

std::set< CObserver * > m_subscribers
 

RTTI stuff <br>

typedef COctoMapPtr SmartPtr
 
static mrpt::utils::CLASSINIT _init_COctoMap
 
static mrpt::utils::TRuntimeClassId classCOctoMap
 
static const mrpt::utils::TRuntimeClassIdclassinfo
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const MRPT_OVERRIDE
 
virtual mrpt::utils::CObjectduplicate () const MRPT_OVERRIDE
 
static mrpt::utils::CObjectCreateObject ()
 
static COctoMapPtr Create ()
 

Map Definition Interface stuff (see mrpt::maps::TMetricMapInitializer) @{

static const size_t m_private_map_register_id
 ID used to initialize class registration (just ignore it)
 
static mrpt::maps::TMetricMapInitializerMapDefinition ()
 Returns default map definition initializer.
 
static COctoMapCreateFromMapDefinition (const mrpt::maps::TMetricMapInitializer &def)
 Constructor from a map definition structure: initializes the map and its parameters accordingly.
 
static mrpt::maps::CMetricMapinternal_CreateFromMapDefinition (const mrpt::maps::TMetricMapInitializer &def)
 

Member Typedef Documentation

◆ myself_t

typedef COctoMapBase<octomap::OcTree ,octomap::OcTreeNode > mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::myself_t
inherited

The type of this MRPT class.

Definition at line 46 of file maps/COctoMapBase.h.

◆ octree_node_t

typedef octomap::OcTreeNode mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::octree_node_t
inherited

The type of nodes in the octree, in the "octomap" library.

Definition at line 48 of file maps/COctoMapBase.h.

◆ octree_t

typedef octomap::OcTree mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::octree_t
inherited

The type of the octree class in the "octomap" library.

Definition at line 47 of file maps/COctoMapBase.h.

◆ SmartPtr

A typedef for the associated smart pointer

Definition at line 38 of file maps/COctoMap.h.

Constructor & Destructor Documentation

◆ COctoMap()

mrpt::maps::COctoMap::COctoMap ( const double  resolution = 0.10)

Default constructor.

◆ ~COctoMap()

virtual mrpt::maps::COctoMap::~COctoMap ( )
virtual

Destructor.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId * mrpt::maps::COctoMap::_GetBaseClass ( )
staticprotected

◆ auxParticleFilterCleanUp()

virtual void mrpt::maps::CMetricMap::auxParticleFilterCleanUp ( )
inlinevirtualinherited

This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".

This method should normally do nothing, but in some cases can be used to free auxiliary cached variables.

Reimplemented in mrpt::maps::CMultiMetricMap, and mrpt::maps::CLandmarksMap.

Definition at line 235 of file maps/CMetricMap.h.

◆ calcNumNodes()

size_t mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::calcNumNodes ( ) const
inlineinherited

Traverses the tree to calculate the total number of nodes.

Definition at line 284 of file maps/COctoMapBase.h.

◆ canComputeObservationLikelihood() [1/2]

virtual bool mrpt::maps::CMetricMap::canComputeObservationLikelihood ( const mrpt::obs::CObservation obs)
virtualinherited

Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.

an occupancy grid map cannot with an image).

Parameters
obsThe observation.
See also
computeObservationLikelihood, genericMapParams.enableObservationLikelihood

◆ canComputeObservationLikelihood() [2/2]

bool mrpt::maps::CMetricMap::canComputeObservationLikelihood ( const mrpt::obs::CObservationPtr obs)
inherited

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ canComputeObservationsLikelihood()

bool mrpt::maps::CMetricMap::canComputeObservationsLikelihood ( const mrpt::obs::CSensoryFrame sf)
inherited

Returns true if this map is able to compute a sensible likelihood function for this observation (i.e.

an occupancy grid map cannot with an image).

Parameters
sfThe observations.
See also
canComputeObservationLikelihood

◆ castRay()

bool mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::castRay ( const mrpt::math::TPoint3D origin,
const mrpt::math::TPoint3D direction,
mrpt::math::TPoint3D end,
bool  ignoreUnknownCells = false,
double  maxRange = -1.0 
) const
inherited

Performs raycasting in 3d, similar to computeRay().

A ray is cast from origin with a given direction, the first occupied cell is returned (as center coordinate). If the starting coordinate is already occupied in the tree, this coordinate will be returned as a hit.

Parameters
originstarting coordinate of ray
directionA vector pointing in the direction of the raycast. Does not need to be normalized.
endreturns the center of the cell that was hit by the ray, if successful
ignoreUnknownCellswhether unknown cells are ignored. If false (default), the raycast aborts when an unkown cell is hit.
maxRangeMaximum range after which the raycast is aborted (<= 0: no limit, default)
Returns
whether or not an occupied cell was hit

Definition at line 249 of file COctoMapBase_impl.h.

◆ clear()

void mrpt::maps::CMetricMap::clear ( )
inherited

Erase all the contents of the map.

Referenced by mrpt::maps::CRandomFieldGridMap2D::clear(), and mrpt::maps::CReflectivityGridMap2D::clear().

◆ compute3DMatchingRatio()

virtual float mrpt::maps::CMetricMap::compute3DMatchingRatio ( const mrpt::maps::CMetricMap otherMap,
const mrpt::poses::CPose3D otherMapPose,
const TMatchingRatioParams params 
) const
virtualinherited

Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps.

This method always return 0 for grid maps.

Parameters
otherMap[IN] The other map to compute the matching with.
otherMapPose[IN] The 6D pose of the other map as seen from "this".
params[IN] Matching parameters
Returns
The matching ratio [0,1]
See also
determineMatching2D

Reimplemented in mrpt::maps::CBeaconMap, mrpt::maps::CHeightGridMap2D, mrpt::maps::COccupancyGridMap2D, mrpt::maps::CPointsMap, mrpt::maps::CRandomFieldGridMap2D, mrpt::maps::CReflectivityGridMap2D, mrpt::maps::CMultiMetricMap, and mrpt::maps::CLandmarksMap.

◆ computeObservationLikelihood() [1/2]

double mrpt::maps::CMetricMap::computeObservationLikelihood ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose2D takenFrom 
)
inherited

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ computeObservationLikelihood() [2/2]

double mrpt::maps::CMetricMap::computeObservationLikelihood ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D takenFrom 
)
inherited

Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.

Parameters
takenFromThe robot's pose the observation is supposed to be taken from.
obsThe observation.
Returns
This method returns a log-likelihood.
See also
Used in particle filter algorithms, see: CMultiMetricMapPDF::update

◆ computeObservationsLikelihood()

double mrpt::maps::CMetricMap::computeObservationsLikelihood ( const mrpt::obs::CSensoryFrame sf,
const mrpt::poses::CPose2D takenFrom 
)
inherited

Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFrame.

Parameters
takenFromThe robot's pose the observation is supposed to be taken from.
sfThe set of observations in a CSensoryFrame.
Returns
This method returns a log-likelihood.
See also
canComputeObservationsLikelihood

◆ Create()

static COctoMapPtr mrpt::maps::COctoMap::Create ( )
static

◆ CreateFromMapDefinition()

static COctoMap * mrpt::maps::COctoMap::CreateFromMapDefinition ( const mrpt::maps::TMetricMapInitializer def)
static

Constructor from a map definition structure: initializes the map and its parameters accordingly.

◆ CreateObject()

static mrpt::utils::CObject * mrpt::maps::COctoMap::CreateObject ( )
static

◆ determineMatching2D()

virtual void mrpt::maps::CMetricMap::determineMatching2D ( const mrpt::maps::CMetricMap otherMap,
const mrpt::poses::CPose2D otherMapPose,
mrpt::utils::TMatchingPairList correspondences,
const TMatchingParams params,
TMatchingExtraResults extraResults 
) const
virtualinherited

Computes the matching between this and another 2D point map, which includes finding:

  • The set of points pairs in each map
  • The mean squared distance between corresponding pairs.

The algorithm is:

  • For each point in "otherMap":
    • Transform the point according to otherMapPose
    • Search with a KD-TREE the closest correspondences in "this" map.
    • Add to the set of candidate matchings, if it passes all the thresholds in params.

This method is the most time critical one into ICP-like algorithms.

Parameters
otherMap[IN] The other map to compute the matching with.
otherMapPose[IN] The pose of the other map as seen from "this".
params[IN] Parameters for the determination of pairings.
correspondences[OUT] The detected matchings pairs.
extraResults[OUT] Other results.
See also
compute3DMatchingRatio

Reimplemented in mrpt::maps::CMultiMetricMap, mrpt::maps::CBeaconMap, mrpt::maps::COccupancyGridMap2D, and mrpt::maps::CPointsMap.

◆ determineMatching3D()

virtual void mrpt::maps::CMetricMap::determineMatching3D ( const mrpt::maps::CMetricMap otherMap,
const mrpt::poses::CPose3D otherMapPose,
mrpt::utils::TMatchingPairList correspondences,
const TMatchingParams params,
TMatchingExtraResults extraResults 
) const
virtualinherited

Computes the matchings between this and another 3D points map - method used in 3D-ICP.

This method finds the set of point pairs in each map.

The method is the most time critical one into ICP-like algorithms.

The algorithm is:

  • For each point in "otherMap":
    • Transform the point according to otherMapPose
    • Search with a KD-TREE the closest correspondences in "this" map.
    • Add to the set of candidate matchings, if it passes all the thresholds in params.
Parameters
otherMap[IN] The other map to compute the matching with.
otherMapPose[IN] The pose of the other map as seen from "this".
params[IN] Parameters for the determination of pairings.
correspondences[OUT] The detected matchings pairs.
extraResults[OUT] Other results.
See also
compute3DMatchingRatio

Reimplemented in mrpt::maps::CPointsMap.

◆ duplicate()

virtual mrpt::utils::CObject * mrpt::maps::COctoMap::duplicate ( ) const
virtual

◆ getAs3DObject()

virtual void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr outObj) const
inlinevirtualinherited

Returns a 3D object representing the map.

See also
renderingOptions

Implements mrpt::maps::CMetricMap.

Definition at line 195 of file maps/COctoMapBase.h.

◆ getAsOctoMapVoxels()

virtual void mrpt::maps::COctoMap::getAsOctoMapVoxels ( mrpt::opengl::COctoMapVoxels gl_obj) const
virtual

Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object.

See also
renderingOptions

Implements mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >.

◆ getAsSimplePointsMap() [1/2]

virtual mrpt::maps::CSimplePointsMap * mrpt::maps::CMetricMap::getAsSimplePointsMap ( )
inlinevirtualinherited

◆ getAsSimplePointsMap() [2/2]

virtual const mrpt::maps::CSimplePointsMap * mrpt::maps::CMetricMap::getAsSimplePointsMap ( ) const
inlinevirtualinherited

If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points map, return it.

Otherwise, return NULL

Reimplemented in mrpt::maps::CMultiMetricMap, mrpt::maps::CPointsMap, and mrpt::maps::CSimplePointsMap.

Definition at line 243 of file maps/CMetricMap.h.

◆ getMetricMax() [1/2]

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getMetricMax ( double &  x,
double &  y,
double &  z 
)
inlineinherited

maximum value of the bounding box of all known space in x, y, z

Definition at line 279 of file maps/COctoMapBase.h.

◆ getMetricMax() [2/2]

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getMetricMax ( double &  x,
double &  y,
double &  z 
) const
inlineinherited

maximum value of the bounding box of all known space in x, y, z

Definition at line 281 of file maps/COctoMapBase.h.

◆ getMetricMin() [1/2]

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getMetricMin ( double &  x,
double &  y,
double &  z 
)
inlineinherited

minimum value of the bounding box of all known space in x, y, z

Definition at line 275 of file maps/COctoMapBase.h.

◆ getMetricMin() [2/2]

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getMetricMin ( double &  x,
double &  y,
double &  z 
) const
inlineinherited

minimum value of the bounding box of all known space in x, y, z

Definition at line 277 of file maps/COctoMapBase.h.

◆ getMetricSize() [1/2]

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getMetricSize ( double &  x,
double &  y,
double &  z 
)
inlineinherited

Size of OcTree (all known space) in meters for x, y and z dimension.

Definition at line 271 of file maps/COctoMapBase.h.

◆ getMetricSize() [2/2]

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getMetricSize ( double &  x,
double &  y,
double &  z 
) const
inlineinherited

Size of OcTree (all known space) in meters for x, y and z dimension.

Definition at line 273 of file maps/COctoMapBase.h.

◆ getNumLeafNodes()

size_t mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getNumLeafNodes ( ) const
inlineinherited

Traverses the tree to calculate the total number of leaf nodes.

Definition at line 287 of file maps/COctoMapBase.h.

◆ getOctomap()

octomap::OcTree & mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getOctomap ( )
inlineinherited

Get a reference to the internal octomap object.

Example:

...
octomap::OcTree &om = map.getOctomap();
OCTREE & getOctomap()
Get a reference to the internal octomap object.
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...

Definition at line 64 of file maps/COctoMapBase.h.

◆ getPointOccupancy()

bool mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getPointOccupancy ( const float  x,
const float  y,
const float  z,
double &  prob_occupancy 
) const
inherited

Get the occupancy probability [0,1] of a point.

Returns
false if the point is not mapped, in which case the returned "prob" is undefined.

Definition at line 216 of file COctoMapBase_impl.h.

◆ getResolution()

double mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getResolution ( ) const
inlineinherited

Definition at line 259 of file maps/COctoMapBase.h.

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId * mrpt::maps::COctoMap::GetRuntimeClass ( ) const
virtual

Reimplemented from mrpt::maps::CMetricMap.

◆ getTreeDepth()

unsigned int mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::getTreeDepth ( ) const
inlineinherited

Definition at line 260 of file maps/COctoMapBase.h.

◆ hasSubscribers()

bool mrpt::utils::CObservable::hasSubscribers ( ) const
inlineprotectedinherited

Can be called by a derived class before preparing an event for publishing with publishEvent to determine if there is no one subscribed, so it can save the wasted time preparing an event that will be not read.

Definition at line 52 of file CObservable.h.

◆ insertObservation()

bool mrpt::maps::CMetricMap::insertObservation ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D robotPose = NULL 
)
inherited

Insert the observation information into this map.

This method must be implemented in derived classes.

Parameters
obsThe observation
robotPoseThe 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use the origin.
See also
CObservation::insertObservationInto

◆ insertObservationPtr()

bool mrpt::maps::CMetricMap::insertObservationPtr ( const mrpt::obs::CObservationPtr obs,
const mrpt::poses::CPose3D robotPose = NULL 
)
inherited

A wrapper for smart pointers, just calls the non-smart pointer version.

◆ insertPointCloud()

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::insertPointCloud ( const CPointsMap ptMap,
const float  sensor_x,
const float  sensor_y,
const float  sensor_z 
)
inherited

Update the octomap with a 2D or 3D scan, given directly as a point cloud and the 3D location of the sensor (the origin of the rays) in this map's frame of reference.

Insertion parameters can be found in insertionOptions.

See also
The generic observation insertion method CMetricMap::insertObservation()

Definition at line 228 of file COctoMapBase_impl.h.

◆ insertRay()

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::insertRay ( const float  end_x,
const float  end_y,
const float  end_z,
const float  sensor_x,
const float  sensor_y,
const float  sensor_z 
)
inlineinherited

Just like insertPointCloud but with a single ray.

Definition at line 231 of file maps/COctoMapBase.h.

◆ internal_build_PointCloud_for_observation()

bool mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::internal_build_PointCloud_for_observation ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D robotPose,
octomap::point3d &  point3d_sensorPt,
octomap::Pointcloud &  ptr_scan 
) const
protectedinherited

Builds the list of 3D points in global coordinates for a generic observation.

Used for both, insertObservation() and computeLikelihood().

Parameters
[out]point3d_sensorPtIs a pointer to a "point3D".
[out]ptr_scanIs in fact a pointer to "octomap::Pointcloud". Not declared as such to avoid headers dependencies in user code.
Returns
false if the observation kind is not applicable.

Definition at line 300 of file COctoMapBase_impl.h.

◆ internal_canComputeObservationLikelihood()

virtual bool mrpt::maps::CMetricMap::internal_canComputeObservationLikelihood ( const mrpt::obs::CObservation obs)
inlineprivatevirtualinherited

Internal method called by canComputeObservationLikelihood()

Reimplemented in mrpt::maps::CMultiMetricMap, and mrpt::maps::COccupancyGridMap2D.

Definition at line 71 of file maps/CMetricMap.h.

References MRPT_UNUSED_PARAM.

◆ internal_clear()

virtual void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::internal_clear ( )
inlineprotectedvirtualinherited

Internal method called by clear()

Implements mrpt::maps::CMetricMap.

Definition at line 293 of file maps/COctoMapBase.h.

◆ internal_computeObservationLikelihood()

double mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::internal_computeObservationLikelihood ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D takenFrom 
)
privatevirtualinherited

Internal method called by computeObservationLikelihood()

Implements mrpt::maps::CMetricMap.

Definition at line 306 of file COctoMapBase_impl.h.

◆ internal_CreateFromMapDefinition()

static mrpt::maps::CMetricMap * mrpt::maps::COctoMap::internal_CreateFromMapDefinition ( const mrpt::maps::TMetricMapInitializer def)
static

◆ internal_insertObservation()

bool mrpt::maps::COctoMap::internal_insertObservation ( const mrpt::obs::CObservation obs,
const mrpt::poses::CPose3D robotPose 
)
protectedvirtual

Internal method called by insertObservation()

Implements mrpt::maps::CMetricMap.

◆ internal_observer_begin()

void mrpt::utils::CObservable::internal_observer_begin ( CObserver )
privateinherited

◆ internal_observer_end()

void mrpt::utils::CObservable::internal_observer_end ( CObserver )
privateinherited

◆ isEmpty()

bool mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::isEmpty ( ) const
virtualinherited

Returns true if the map is empty/no observation has been inserted.

Implements mrpt::maps::CMetricMap.

Definition at line 163 of file COctoMapBase_impl.h.

◆ isPointWithinOctoMap()

bool mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::isPointWithinOctoMap ( const float  x,
const float  y,
const float  z 
) const
inlineinherited

Check whether the given point lies within the volume covered by the octomap (that is, whether it is "mapped")

Definition at line 208 of file maps/COctoMapBase.h.

◆ loadFromProbabilisticPosesAndObservations()

void mrpt::maps::CMetricMap::loadFromProbabilisticPosesAndObservations ( const mrpt::maps::CSimpleMap Map)
inherited

Load the map contents from a CSimpleMap object, erasing all previous content of the map.

This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as given by the "poses::CPosePDF" in the CSimpleMap object.

See also
insertObservation, CSimpleMap
Exceptions
std::exceptionSome internal steps in invoked methods can raise exceptions on invalid parameters, etc...

◆ loadFromSimpleMap()

void mrpt::maps::CMetricMap::loadFromSimpleMap ( const mrpt::maps::CSimpleMap Map)
inlineinherited

Load the map contents from a CSimpleMap object, erasing all previous content of the map.

This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as given by the "poses::CPosePDF" in the CSimpleMap object.

See also
insertObservation, CSimpleMap
Exceptions
std::exceptionSome internal steps in invoked methods can raise exceptions on invalid parameters, etc...

Definition at line 105 of file maps/CMetricMap.h.

◆ MapDefinition()

static mrpt::maps::TMetricMapInitializer * mrpt::maps::COctoMap::MapDefinition ( )
static

Returns default map definition initializer.

See mrpt::maps::TMetricMapInitializer

◆ memoryFullGrid()

size_t mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::memoryFullGrid ( ) const
inlineinherited
Returns
Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)

Definition at line 268 of file maps/COctoMapBase.h.

◆ memoryUsage()

size_t mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::memoryUsage ( ) const
inlineinherited
Returns
Memory usage of the complete octree in bytes (may vary between architectures)

Definition at line 264 of file maps/COctoMapBase.h.

◆ memoryUsageNode()

size_t mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::memoryUsageNode ( ) const
inlineinherited
Returns
Memory usage of the a single octree node

Definition at line 266 of file maps/COctoMapBase.h.

◆ OnPostSuccesfulInsertObs()

virtual void mrpt::maps::CMetricMap::OnPostSuccesfulInsertObs ( const mrpt::obs::CObservation )
inlineprivatevirtualinherited

Hook for each time a "internal_insertObservation" returns "true" This is called automatically from insertObservation() when internal_insertObservation returns true.

Reimplemented in mrpt::maps::COccupancyGridMap2D.

Definition at line 79 of file maps/CMetricMap.h.

◆ publishEvent()

void mrpt::utils::CObservable::publishEvent ( const mrptEvent e) const
protectedinherited

Called when you want this object to emit an event to all the observers currently subscribed to this object.

◆ readFromStream()

void mrpt::maps::COctoMap::readFromStream ( mrpt::utils::CStream in,
int  version 
)
protected

◆ saveMetricMapRepresentationToFile()

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::saveMetricMapRepresentationToFile ( const std::string &  filNamePrefix) const
virtualinherited

This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).

Implements mrpt::maps::CMetricMap.

Definition at line 165 of file COctoMapBase_impl.h.

◆ size()

size_t mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::size ( ) const
inlineinherited
Returns
The number of nodes in the tree

Definition at line 262 of file maps/COctoMapBase.h.

◆ squareDistanceToClosestCorrespondence()

virtual float mrpt::maps::CMetricMap::squareDistanceToClosestCorrespondence ( float  x0,
float  y0 
) const
virtualinherited

Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map.

Reimplemented in mrpt::maps::CPointsMap.

◆ updateVoxel()

void mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::updateVoxel ( const double  x,
const double  y,
const double  z,
bool  occupied 
)
inlineinherited

Manually updates the occupancy of the voxel at (x,y,z) as being occupied (true) or free (false), using the log-odds parameters in insertionOptions.

Definition at line 219 of file maps/COctoMapBase.h.

◆ volume()

double mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::volume ( ) const
inlineinherited

Definition at line 269 of file maps/COctoMapBase.h.

◆ writeToStream()

void mrpt::maps::COctoMap::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
protected

Member Data Documentation

◆ _init_COctoMap

mrpt::utils::CLASSINIT mrpt::maps::COctoMap::_init_COctoMap
staticprotected

Definition at line 38 of file maps/COctoMap.h.

◆ classCMetricMap

const mrpt::utils::TRuntimeClassId mrpt::maps::CMetricMap::classCMetricMap
staticinherited

Definition at line 57 of file maps/CMetricMap.h.

◆ classCOctoMap

mrpt::utils::TRuntimeClassId mrpt::maps::COctoMap::classCOctoMap
static

Definition at line 38 of file maps/COctoMap.h.

◆ classinfo

const mrpt::utils::TRuntimeClassId* mrpt::maps::COctoMap::classinfo
static

Definition at line 38 of file maps/COctoMap.h.

◆ genericMapParams

TMapGenericParams mrpt::maps::CMetricMap::genericMapParams
inherited

Common params to all maps.

Definition at line 230 of file maps/CMetricMap.h.

◆ insertionOptions

TInsertionOptions mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::insertionOptions
inherited

The options used when inserting observations in the map.

Definition at line 139 of file maps/COctoMapBase.h.

◆ likelihoodOptions

TLikelihoodOptions mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::likelihoodOptions
inherited

Definition at line 160 of file maps/COctoMapBase.h.

◆ m_octomap

octomap::OcTree mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::m_octomap
protectedinherited

The actual octo-map object.

Definition at line 302 of file maps/COctoMapBase.h.

◆ m_private_map_register_id

const size_t mrpt::maps::COctoMap::m_private_map_register_id
static

ID used to initialize class registration (just ignore it)

Definition at line 50 of file maps/COctoMap.h.

◆ m_subscribers

std::set<CObserver*> mrpt::utils::CObservable::m_subscribers
privateinherited

Definition at line 42 of file CObservable.h.

◆ renderingOptions

TRenderingOptions mrpt::maps::COctoMapBase< octomap::OcTree , octomap::OcTreeNode >::renderingOptions
inherited

Definition at line 190 of file maps/COctoMapBase.h.




Page generated by Doxygen 1.9.8 for MRPT 1.4.0 SVN: at Thu Dec 14 16:54:58 UTC 2023