|
| RtabmapColorOcTreeNode * | averageNodeColor (const octomap::OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b) |
| |
| RtabmapColorOcTreeNode * | averageNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b) |
| |
| RtabmapColorOcTree * | create () const |
| |
| std::string | getTreeType () const |
| |
| RtabmapColorOcTreeNode * | integrateNodeColor (const octomap::OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b) |
| |
| RtabmapColorOcTreeNode * | integrateNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b) |
| |
| virtual bool | isNodeCollapsible (const RtabmapColorOcTreeNode *node) const |
| |
| virtual bool | pruneNode (RtabmapColorOcTreeNode *node) |
| |
| | RtabmapColorOcTree (double resolution) |
| | Default constructor, sets resolution of leafs. More...
|
| |
| RtabmapColorOcTreeNode * | setNodeColor (const octomap::OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b) |
| |
| RtabmapColorOcTreeNode * | setNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b) |
| |
| void | updateInnerOccupancy () |
| |
| virtual | ~RtabmapColorOcTree () |
| |
| bool | bbxSet () const |
| |
| virtual bool | castRay (const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const |
| |
| KeyBoolMap::const_iterator | changedKeysBegin () const |
| |
| KeyBoolMap::const_iterator | changedKeysEnd () const |
| |
| void | computeDiscreteUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) |
| |
| void | computeUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) |
| |
| void | enableChangeDetection (bool enable) |
| |
| point3d | getBBXBounds () const |
| |
| point3d | getBBXCenter () const |
| |
| point3d | getBBXMax () const |
| |
| point3d | getBBXMin () const |
| |
| bool | getNormals (const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const |
| |
| virtual bool | getRayIntersection (const point3d &origin, const point3d &direction, const point3d ¢er, point3d &intersection, double delta=0.0) const |
| |
| bool | inBBX (const point3d &p) const |
| |
| bool | inBBX (const OcTreeKey &key) const |
| |
| virtual void | insertPointCloud (const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
| |
| virtual void | insertPointCloud (const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
| |
| virtual void | insertPointCloud (const ScanNode &scan, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
| |
| virtual void | insertPointCloudRays (const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false) |
| |
| virtual bool | insertRay (const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false) |
| |
| virtual void | integrateHit (RtabmapColorOcTreeNode *occupancyNode) const |
| |
| virtual void | integrateMiss (RtabmapColorOcTreeNode *occupancyNode) const |
| |
| bool | isChangeDetectionEnabled () const |
| |
| virtual void | nodeToMaxLikelihood (RtabmapColorOcTreeNode *occupancyNode) const |
| |
| virtual void | nodeToMaxLikelihood (RtabmapColorOcTreeNode &occupancyNode) const |
| |
| size_t | numChangesDetected () const |
| |
| | OccupancyOcTreeBase (double resolution) |
| |
| | OccupancyOcTreeBase (const OccupancyOcTreeBase< RtabmapColorOcTreeNode > &rhs) |
| |
| | OCTOMAP_DEPRECATED (virtual void insertScanNaive(const Pointcloud &scan, const point3d &sensor_origin, double maxrange, bool lazy_eval=false)) |
| |
| | OCTOMAP_DEPRECATED (virtual void insertScan(const ScanNode &scan, double maxrange=-1., bool pruning=true, bool lazy_eval=false)) |
| |
| | OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false)) |
| |
| | OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false)) |
| |
| std::istream & | readBinaryData (std::istream &s) |
| |
| std::istream & | readBinaryNode (std::istream &s, RtabmapColorOcTreeNode *node) const |
| |
| void | resetChangeDetection () |
| |
| void | setBBXMax (point3d &max) |
| |
| void | setBBXMin (point3d &min) |
| |
| virtual RtabmapColorOcTreeNode * | setNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false) |
| |
| virtual RtabmapColorOcTreeNode * | setNodeValue (const point3d &value, float log_odds_value, bool lazy_eval=false) |
| |
| virtual RtabmapColorOcTreeNode * | setNodeValue (double x, double y, double z, float log_odds_value, bool lazy_eval=false) |
| |
| virtual void | toMaxLikelihood () |
| |
| void | updateInnerOccupancy () |
| |
| virtual RtabmapColorOcTreeNode * | updateNode (double x, double y, double z, float log_odds_update, bool lazy_eval=false) |
| |
| virtual RtabmapColorOcTreeNode * | updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false) |
| |
| virtual RtabmapColorOcTreeNode * | updateNode (const point3d &value, float log_odds_update, bool lazy_eval=false) |
| |
| virtual RtabmapColorOcTreeNode * | updateNode (const point3d &value, bool occupied, bool lazy_eval=false) |
| |
| virtual RtabmapColorOcTreeNode * | updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false) |
| |
| virtual RtabmapColorOcTreeNode * | updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false) |
| |
| virtual void | updateNodeLogOdds (RtabmapColorOcTreeNode *occupancyNode, const float &update) const |
| |
| void | useBBXLimit (bool enable) |
| |
| std::ostream & | writeBinaryData (std::ostream &s) const |
| |
| std::ostream & | writeBinaryNode (std::ostream &s, const RtabmapColorOcTreeNode *node) const |
| |
| virtual | ~OccupancyOcTreeBase () |
| |
| OcTreeKey | adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const |
| |
| unsigned short int | adjustKeyAtDepth (unsigned short int key, unsigned int depth) const |
| |
| iterator | begin (unsigned char maxDepth=0) const |
| |
| leaf_iterator | begin_leafs (unsigned char maxDepth=0) const |
| |
| leaf_bbx_iterator | begin_leafs_bbx (const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const |
| |
| leaf_bbx_iterator | begin_leafs_bbx (const point3d &min, const point3d &max, unsigned char maxDepth=0) const |
| |
| tree_iterator | begin_tree (unsigned char maxDepth=0) const |
| |
| size_t | calcNumNodes () const |
| |
| void | clear () |
| |
| bool | computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray) |
| |
| bool | computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const |
| |
| OcTreeKey | coordToKey (const point3d &coord, unsigned depth) const |
| |
| OcTreeKey | coordToKey (double x, double y, double z, unsigned depth) const |
| |
| unsigned short int | coordToKey (double coordinate) const |
| |
| unsigned short int | coordToKey (double coordinate, unsigned depth) const |
| |
| OcTreeKey | coordToKey (const point3d &coord) const |
| |
| OcTreeKey | coordToKey (double x, double y, double z) const |
| |
| bool | coordToKeyChecked (const point3d &coord, OcTreeKey &key) const |
| |
| bool | coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &key) const |
| |
| bool | coordToKeyChecked (double x, double y, double z, OcTreeKey &key) const |
| |
| bool | coordToKeyChecked (double x, double y, double z, unsigned depth, OcTreeKey &key) const |
| |
| bool | coordToKeyChecked (double coordinate, unsigned short int &key) const |
| |
| bool | coordToKeyChecked (double coordinate, unsigned depth, unsigned short int &key) const |
| |
| bool | deleteNode (double x, double y, double z, unsigned int depth=0) |
| |
| bool | deleteNode (const point3d &value, unsigned int depth=0) |
| |
| bool | deleteNode (const OcTreeKey &key, unsigned int depth=0) |
| |
| const iterator | end () const |
| |
| const leaf_iterator | end_leafs () const |
| |
| const leaf_bbx_iterator | end_leafs_bbx () const |
| |
| const tree_iterator | end_tree () const |
| |
| virtual void | expand () |
| |
| virtual void | getMetricMax (double &x, double &y, double &z) |
| |
| void | getMetricMax (double &x, double &y, double &z) const |
| |
| virtual void | getMetricMin (double &x, double &y, double &z) |
| |
| void | getMetricMin (double &x, double &y, double &z) const |
| |
| virtual void | getMetricSize (double &x, double &y, double &z) |
| |
| virtual void | getMetricSize (double &x, double &y, double &z) const |
| |
| double | getNodeSize (unsigned depth) const |
| |
| size_t | getNumLeafNodes () const |
| |
| double | getResolution () const |
| |
| RtabmapColorOcTreeNode * | getRoot () const |
| |
| unsigned int | getTreeDepth () const |
| |
| std::string | getTreeType () const |
| |
| void | getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const |
| |
| point3d | keyToCoord (const OcTreeKey &key) const |
| |
| double | keyToCoord (unsigned short int key, unsigned depth) const |
| |
| double | keyToCoord (unsigned short int key) const |
| |
| point3d | keyToCoord (const OcTreeKey &key, unsigned depth) const |
| |
| unsigned long long | memoryFullGrid () const |
| |
| virtual size_t | memoryUsage () const |
| |
| virtual size_t | memoryUsageNode () const |
| |
| | OcTreeBaseImpl (const OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree > &rhs) |
| |
| | OcTreeBaseImpl (double resolution) |
| |
| bool | operator== (const OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree > &rhs) const |
| |
| virtual void | prune () |
| |
| std::istream & | readData (std::istream &s) |
| |
| RtabmapColorOcTreeNode * | search (const OcTreeKey &key, unsigned int depth=0) const |
| |
| RtabmapColorOcTreeNode * | search (const point3d &value, unsigned int depth=0) const |
| |
| RtabmapColorOcTreeNode * | search (double x, double y, double z, unsigned int depth=0) const |
| |
| void | setResolution (double r) |
| |
| virtual size_t | size () const |
| |
| void | swapContent (OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree > &rhs) |
| |
| double | volume () |
| |
| std::ostream & | writeData (std::ostream &s) const |
| |
| virtual | ~OcTreeBaseImpl () |
| |