#include <OctoMap.h>
Public Types | |
enum | OccupancyType { kTypeUnknown = -1, kTypeEmpty = 0, kTypeGround = 1, kTypeObstacle = 100 } |
Public Member Functions | |
bool | createChild (unsigned int i) |
void | expandNode () |
RtabmapColorOcTreeNode * | getChild (unsigned int i) |
const RtabmapColorOcTreeNode * | getChild (unsigned int i) const |
int | getNodeRefId () const |
int | getOccupancyType () const |
const octomap::point3d & | getPointRef () const |
bool | pruneNode () |
RtabmapColorOcTreeNode () | |
RtabmapColorOcTreeNode (const RtabmapColorOcTreeNode &rhs) | |
void | setNodeRefId (int nodeRefId) |
void | setOccupancyType (char type) |
void | setPointRef (const octomap::point3d &point) |
Private Attributes | |
int | nodeRefId_ |
octomap::point3d | pointRef_ |
int | type_ |
Friends | |
class | RtabmapColorOcTree |
rtabmap::RtabmapColorOcTreeNode::RtabmapColorOcTreeNode | ( | const RtabmapColorOcTreeNode & | rhs | ) | [inline] |
bool rtabmap::RtabmapColorOcTreeNode::createChild | ( | unsigned int | i | ) |
Reimplemented from octomap::ColorOcTreeNode.
Definition at line 96 of file OctoMap.cpp.
Reimplemented from octomap::ColorOcTreeNode.
Definition at line 82 of file OctoMap.cpp.
RtabmapColorOcTreeNode * rtabmap::RtabmapColorOcTreeNode::getChild | ( | unsigned int | i | ) |
Reimplemented from octomap::ColorOcTreeNode.
Definition at line 43 of file OctoMap.cpp.
const RtabmapColorOcTreeNode * rtabmap::RtabmapColorOcTreeNode::getChild | ( | unsigned int | i | ) | const |
Reimplemented from octomap::ColorOcTreeNode.
Definition at line 51 of file OctoMap.cpp.
int rtabmap::RtabmapColorOcTreeNode::getNodeRefId | ( | ) | const [inline] |
int rtabmap::RtabmapColorOcTreeNode::getOccupancyType | ( | ) | const [inline] |
const octomap::point3d& rtabmap::RtabmapColorOcTreeNode::getPointRef | ( | ) | const [inline] |
Reimplemented from octomap::ColorOcTreeNode.
Definition at line 61 of file OctoMap.cpp.
void rtabmap::RtabmapColorOcTreeNode::setNodeRefId | ( | int | nodeRefId | ) | [inline] |
void rtabmap::RtabmapColorOcTreeNode::setOccupancyType | ( | char | type | ) | [inline] |
void rtabmap::RtabmapColorOcTreeNode::setPointRef | ( | const octomap::point3d & | point | ) | [inline] |
friend class RtabmapColorOcTree [friend] |
int rtabmap::RtabmapColorOcTreeNode::nodeRefId_ [private] |
int rtabmap::RtabmapColorOcTreeNode::type_ [private] |