Main MRPT website > C++ reference for MRPT 1.4.0
maps/CColouredOctoMap.h
Go to the documentation of this file.
1/* +---------------------------------------------------------------------------+
2 | Mobile Robot Programming Toolkit (MRPT) |
3 | http://www.mrpt.org/ |
4 | |
5 | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6 | See: http://www.mrpt.org/Authors - All rights reserved. |
7 | Released under BSD License. See details in http://www.mrpt.org/License |
8 +---------------------------------------------------------------------------+ */
9
10#ifndef MRPT_CColouredOctoMap_H
11#define MRPT_CColouredOctoMap_H
12
14#include <octomap/octomap.h>
15#include <octomap/ColorOcTree.h>
16#include <mrpt/obs/obs_frwds.h>
17
19
20namespace mrpt
21{
22 namespace maps
23 {
25
26 /** A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ library.
27 * This version stores both, occupancy information and RGB colour data at each octree node. See the base class mrpt::maps::COctoMapBase.
28 *
29 * \sa CMetricMap, the example in "MRPT/samples/octomap_simple"
30 * \ingroup mrpt_maps_grp
31 */
32 class MAPS_IMPEXP CColouredOctoMap : public COctoMapBase<octomap::ColorOcTree,octomap::ColorOcTreeNode>
33 {
34 // This must be added to any CSerializable derived class:
36
37 public:
38 CColouredOctoMap(const double resolution=0.10); //!< Default constructor
39 virtual ~CColouredOctoMap(); //!< Destructor
40
41 /** This allows the user to select the desired method to update voxels colour.
42 SET = Set the colour of the voxel at (x,y,z) directly
43 AVERAGE = Set the colour of the voxel at (x,y,z) as the mean of its previous colour and the new observed one.
44 INTEGRATE = Calculate the new colour of the voxel at (x,y,z) using this formula: prev_color*node_prob + new_color*(0.99-node_prob)
45 If there isn't any previous color, any method is equivalent to SET.
46 INTEGRATE is the default option*/
48 {
49 INTEGRATE = 0,
51 AVERAGE
52 };
53
54 /** Get the RGB colour of a point
55 * \return false if the point is not mapped, in which case the returned colour is undefined. */
56 bool getPointColour(const float x, const float y, const float z, uint8_t& r, uint8_t& g, uint8_t& b) const;
57
58 /** Manually update the colour of the voxel at (x,y,z) */
59 void updateVoxelColour(const double x, const double y, const double z, const uint8_t r, const uint8_t g, const uint8_t b);
60
61 ///Set the method used to update voxels colour
62 void setVoxelColourMethod(TColourUpdate new_method) {m_colour_method = new_method;}
63
64 ///Get the method used to update voxels colour
65 TColourUpdate getVoxelColourMethod() {return m_colour_method;}
66
68
70 double resolution; //!< The finest resolution of the octomap (default: 0.10 meters)
71 mrpt::maps::CColouredOctoMap::TInsertionOptions insertionOpts; //!< Observations insertion options
72 mrpt::maps::CColouredOctoMap::TLikelihoodOptions likelihoodOpts; //!< Probabilistic observation likelihood options
74
75 protected:
76 bool internal_insertObservation(const mrpt::obs::CObservation *obs,const mrpt::poses::CPose3D *robotPose) MRPT_OVERRIDE;
77
78 TColourUpdate m_colour_method; //!Method used to updated voxels colour.
79
80 }; // End of class def.
82
83 } // End of namespace
84
85} // End of namespace
86
87#endif
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
#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 MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
#define MAP_DEFINITION_START(_CLASS_NAME_, _LINKAGE_)
Add a MAP_DEFINITION_START() ... MAP_DEFINITION_END() block inside the declaration of each metric map...
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
TColourUpdate getVoxelColourMethod()
Get the method used to update voxels colour.
virtual ~CColouredOctoMap()
Destructor.
void updateVoxelColour(const double x, const double y, const double z, const uint8_t r, const uint8_t g, const uint8_t b)
Manually update the colour of the voxel at (x,y,z)
virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const MRPT_OVERRIDE
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object.
bool getPointColour(const float x, const float y, const float z, uint8_t &r, uint8_t &g, uint8_t &b) const
Get the RGB colour of a point.
CColouredOctoMap(const double resolution=0.10)
Default constructor.
TColourUpdate
This allows the user to select the desired method to update voxels colour.
void setVoxelColourMethod(TColourUpdate new_method)
Set the method used to update voxels colour.
Declares a virtual base class for all metric maps storage classes.
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
Definition mrpt_macros.h:28
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
unsigned char uint8_t
Definition pstdint.h:143



Page generated by Doxygen 1.9.7 for MRPT 1.4.0 SVN: at Tue Jun 13 14:27:49 UTC 2023