Go to the documentation of this file.
34 #ifndef OCTOMAP_COLOR_OCTREE_H
35 #define OCTOMAP_COLOR_OCTREE_H
55 Color(uint8_t _r, uint8_t _g, uint8_t _b)
56 :
r(_r),
g(_g),
b(_b) {}
58 return (
r==other.
r &&
g==other.
g &&
b==other.
b);
61 return (
r!=other.
r ||
g!=other.
g ||
b!=other.
b);
82 inline void setColor(uint8_t r, uint8_t g, uint8_t b) {
99 std::istream&
readData(std::istream &s);
100 std::ostream&
writeData(std::ostream &s)
const;
132 uint8_t g, uint8_t b);
136 uint8_t g, uint8_t b) {
144 uint8_t g, uint8_t b);
148 uint8_t g, uint8_t b) {
156 uint8_t g, uint8_t b);
160 uint8_t g, uint8_t b) {
std::string getTreeType() const
returns actual class name as string for identification
bool operator==(const Color &other) const
virtual bool isNodeCollapsible(const ColorOcTreeNode *node) const
void updateColorChildren()
ColorOcTree(double resolution)
Default constructor, sets resolution of leafs.
void setColor(uint8_t r, uint8_t g, uint8_t b)
virtual bool pruneNode(ColorOcTreeNode *node)
ColorOcTreeNode * averageNodeColor(const OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b)
std::ostream & writeData(std::ostream &s) const
T value
stored data (payload)
ColorOcTreeNode * setNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
void updateInnerOccupancy()
ColorOcTreeNode * integrateNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
static StaticMemberInitializer colorOcTreeMemberInit
static member to ensure static initialization (only once)
void copyData(const OcTreeDataNode &from)
ColorOcTreeNode * integrateNodeColor(const OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b)
bool operator!=(const Color &other) const
StaticMemberInitializer()
void copyData(const ColorOcTreeNode &from)
std::ostream & operator<<(std::ostream &out, ColorOcTreeNode::Color const &c)
user friendly output in format (r g b)
Color(uint8_t _r, uint8_t _g, uint8_t _b)
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
static void registerTreeType(AbstractOcTree *tree)
void updateInnerOccupancyRecurs(ColorOcTreeNode *node, unsigned int depth)
void writeColorHistogram(std::string filename)
ColorOcTreeNode::Color getAverageChildColor() const
ColorOcTree * create() const
ColorOcTreeNode(const ColorOcTreeNode &rhs)
ColorOcTreeNode * setNodeColor(const OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b)
bool operator==(const ColorOcTreeNode &rhs) const
double resolution
in meters
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
ColorOcTreeNode * averageNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
std::istream & readData(std::istream &s)
octomap
Author(s): Kai M. Wurm
, Armin Hornung
autogenerated on Tue Dec 12 2023 03:39:40