10 #ifndef MRPT_COctoMapBase_H
11 #define MRPT_COctoMapBase_H
27 class CObservation2DRangeScan;
28 class CObservation3DRangeScan;
45 template <
class OCTREE,
class OCTREE_NODE>
83 const bool o_has_parent = o.
m_parent.get()!=NULL;
159 const std::string §ion);
194 generateGridLines (false),
195 generateOccupiedVoxels (true),
196 visibleOccupiedVoxels (true),
197 generateFreeVoxels (true),
198 visibleFreeVoxels (true)
214 outObj->insert(gl_obj);
231 bool getPointOccupancy(
const float x,
const float y,
const float z,
double &prob_occupancy)
const;
234 void updateVoxel(
const double x,
const double y,
const double z,
bool occupied)
246 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)
268 bool ignoreUnknownCells=
false,
269 double maxRange=-1.0)
const;
void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
void readFromStream(CStream &in)
Binary dump to stream.
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion)
See utils::CLoadableOptions.
size_t memoryUsageNode() const
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion)
See utils::CLoadableOptions.
Options used when evaluating "computeObservationLikelihood".
EIGEN_STRONG_INLINE iterator end()
void dumpToTextStream(CStream &out) const
See utils::CLoadableOptions.
TInsertionOptions & operator=(const TInsertionOptions &o)
double getProbMiss() const
mrpt::utils::ignored_copy_ptr< myself_t > m_parent
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 s...
virtual void internal_clear()
Internal method called by clear()
double maxrange
maximum range for how long individual beams are inserted (default -1: complete beam) ...
void setClampingThresMin(double thresProb)
(key name in .ini files: "clampingThresMin")sets the minimum threshold for occupancy clamping (sensor...
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 setOccupancyThres(double prob)
(key name in .ini files: "occupancyThres") sets the threshold for occupancy (sensor model) (Default=0...
virtual ~TLikelihoodOptions()
double getResolution() const
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
float getProbHitLog() const
OCTREE & getOctomap()
Get a reference to the internal octomap object.
void readFromStream(CStream &in)
Binary dump to stream.
TInsertionOptions()
Especial constructor, not attached to a real COctoMap object: used only in limited situations...
float getProbMissLog() const
COctoMapBase< OCTREE, OCTREE_NODE > myself_t
The type of this MRPT class.
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...
OCTREE octree_t
The type of the octree class in the "octomap" library.
double getClampingThresMin() const
void dumpToTextStream(CStream &out) const
See utils::CLoadableOptions.
virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const =0
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object...
virtual double computeObservationLikelihood(const CObservation *obs, const CPose3D &takenFrom)
Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
This class allows loading and storing values and vectors of different types from a configuration text...
Declares a virtual base class for all metric maps storage classes.
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::slam::COctoMap).
virtual bool isEmpty() const
Returns true if the map is empty/no observation has been inserted.
void getMetricMax(double &x, double &y, double &z) const
maximum value of the bounding box of all known space in x, y, z
unsigned int getTreeDepth() const
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
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().
double getProbHit() const
With this struct options are provided to the observation insertion process.
void writeToStream(CStream &out) const
Binary dump to stream.
void getMetricMin(double &x, double &y, double &z)
minimum value of the bounding box of all known space in x, y, z
Declares a class that represents any robot's observation.
double getOccupancyThres() const
void setProbMiss(double prob)
(key name in .ini files: "probMiss")sets the probablility for a "miss" (will be converted to logodds)...
bool generateOccupiedVoxels
Generate voxels for the occupied volumes (Default=true)
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)...
float getClampingThresMinLog() const
void getMetricMin(double &x, double &y, double &z) const
minimum value of the bounding box of all known space in x, y, z
void setClampingThresMax(double thresProb)
(key name in .ini files: "clampingThresMax")sets the maximum threshold for occupancy clamping (sensor...
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan...
TLikelihoodOptions likelihoodOptions
bool pruning
whether the tree is (losslessly) pruned after insertion (default: true)
size_t memoryUsage() const
float getClampingThresMaxLog() const
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.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
virtual void getAs3DObject(mrpt::opengl::CSetOfObjectsPtr &outObj) const
Returns a 3D object representing the map.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
uint32_t decimation
Speed up the likelihood computation by considering only one out of N rays (default=1) ...
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
OCTREE_NODE octree_node_t
The type of nodes in the octree, in the "octomap" library.
double getClampingThresMax() const
TRenderingOptions renderingOptions
OcTreeKey is a container class for internal key addressing.
TLikelihoodOptions()
Initilization of default parameters.
bool visibleOccupiedVoxels
Set occupied voxels visible (requires generateOccupiedVoxels=true) (Default=true) ...
OCTREE m_octomap
The actual octo-map object.
void getMetricSize(double &x, double &y, double &z) const
Size of OcTree (all known space) in meters for x, y and z dimension.
Options for the conversion of a mrpt::slam::COctoMap into a mrpt::opengl::COctoMapVoxels.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
COctoMapBase(const double resolution=0.10)
Constructor, defines the resolution of the octomap (length of each voxel side)
bool generateFreeVoxels
Generate voxels for the freespace (Default=true)
bool visibleFreeVoxels
Set free voxels visible (requires generateFreeVoxels=true) (Default=true)
static COctoMapVoxelsPtr Create()
void writeToStream(CStream &out) const
Binary dump to stream.
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
A wrapper class for pointers whose copy operations from other objects of the same type are ignored...
size_t memoryFullGrid() const
void getMetricSize(double &x, double &y, double &z)
Size of OcTree (all known space) in meters for x, y and z dimension.
void setProbHit(double prob)
(key name in .ini files: "probHit")sets the probablility for a "hit" (will be converted to logodds) -...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
float getOccupancyThresLog() const
bool generateGridLines
Generate grid lines for all octree nodes, useful to draw the "structure" of the octree, but computationally costly (Default: false)
bool internal_build_PointCloud_for_observation(const CObservation *obs, const CPose3D *robotPose, octomap::point3d &point3d_sensorPt, octomap::Pointcloud &ptr_scan) const
Builds the list of 3D points in global coordinates for a generic observation.
This class represents a three-dimensional vector.