Classes | Typedefs | Functions | Variables
octomap Namespace Reference

Classes

class  AbstractOccupancyOcTree
 
class  AbstractOcTree
 
class  AbstractOcTreeNode
 
class  ColorOcTree
 
class  ColorOcTreeNode
 
class  CountingOcTree
 
class  CountingOcTreeNode
 
class  KeyRay
 
class  MapCollection
 
class  MapNode
 
class  OccupancyOcTreeBase
 
class  OcTree
 
class  OcTreeBase
 
class  OcTreeBaseImpl
 
class  OcTreeDataNode
 
class  OcTreeKey
 
class  OcTreeNode
 
class  OcTreeNodeStamped
 
class  OcTreeStamped
 
class  Pointcloud
 
class  ScanEdge
 
class  ScanGraph
 
class  ScanNode
 

Typedefs

typedef unsigned char byte
 
typedef uint16_t key_type
 
typedef unordered_ns::unordered_map< OcTreeKey, bool, OcTreeKey::KeyHashKeyBoolMap
 
typedef unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHashKeySet
 
typedef std::pair< point3d, double > OcTreeVolume
 A voxel defined by its center point3d and its side length. More...
 
typedef octomath::Vector3 point3d
 Use Vector3 (float precision) as a point3d in octomap. More...
 
typedef std::vector< octomath::Vector3point3d_collection
 
typedef std::list< octomath::Vector3point3d_list
 
typedef octomath::Pose6D pose6d
 Use our Pose6D (float precision) as pose6d in octomap. More...
 

Functions

uint8_t computeChildIdx (const OcTreeKey &key, int depth)
 generate child index (between 0 and 7) from key at given tree depth More...
 
void computeChildKey (unsigned int pos, key_type center_offset_key, const OcTreeKey &parent_key, OcTreeKey &child_key)
 
OcTreeKey computeIndexKey (key_type level, const OcTreeKey &key)
 
float logodds (double probability)
 compute log-odds from probability: More...
 
std::ostream & operator<< (std::ostream &out, ColorOcTreeNode::Color const &c)
 user friendly output in format (r g b) More...
 
double probability (double logodds)
 compute probability from logodds: More...
 

Variables

static const int edgeTable [256]
 
static const int triTable [256][16]
 
static const point3d vertexList [12]
 

Detailed Description

Namespace the OctoMap library and visualization tools

Tables used by the Marching Cubes Algorithm The tables are from Paul Bourke's web page http://paulbourke.net/geometry/polygonise/ Used with permission here under BSD license.

Typedef Documentation

◆ byte

typedef unsigned char octomap::byte

Definition at line 60 of file binvox2bt.cpp.

◆ key_type

typedef uint16_t octomap::key_type

Definition at line 63 of file OcTreeKey.h.

◆ KeyBoolMap

typedef unordered_ns::unordered_map<OcTreeKey, bool, OcTreeKey::KeyHash> octomap::KeyBoolMap

Data structrure to efficiently track changed nodes as a combination of OcTreeKeys and a bool flag (to denote newly created nodes)

Definition at line 136 of file OcTreeKey.h.

◆ KeySet

typedef unordered_ns::unordered_set<OcTreeKey, OcTreeKey::KeyHash> octomap::KeySet

Data structure to efficiently compute the nodes to update from a scan insertion using a hash set.

Note
you need to use boost::unordered_set instead if your compiler does not yet support tr1!

Definition at line 129 of file OcTreeKey.h.

◆ OcTreeVolume

typedef std::pair<point3d, double> octomap::OcTreeVolume

A voxel defined by its center point3d and its side length.

Definition at line 57 of file octomap_types.h.

◆ point3d

Use Vector3 (float precision) as a point3d in octomap.

Definition at line 49 of file octomap_types.h.

◆ point3d_collection

Definition at line 53 of file octomap_types.h.

◆ point3d_list

Definition at line 54 of file octomap_types.h.

◆ pose6d

Use our Pose6D (float precision) as pose6d in octomap.

Definition at line 51 of file octomap_types.h.

Function Documentation

◆ computeChildIdx()

uint8_t octomap::computeChildIdx ( const OcTreeKey key,
int  depth 
)
inline

generate child index (between 0 and 7) from key at given tree depth

Definition at line 207 of file OcTreeKey.h.

◆ computeChildKey()

void octomap::computeChildKey ( unsigned int  pos,
key_type  center_offset_key,
const OcTreeKey parent_key,
OcTreeKey child_key 
)
inline

Computes the key of a child node while traversing the octree, given child index and current key

Parameters
[in]posindex of child node (0..7)
[in]center_offset_keyconstant offset of octree keys
[in]parent_keycurrent (parent) key
[out]child_keycomputed child key

Definition at line 193 of file OcTreeKey.h.

◆ computeIndexKey()

OcTreeKey octomap::computeIndexKey ( key_type  level,
const OcTreeKey key 
)
inline

Generates a unique key for all keys on a certain level of the tree

Parameters
levelfrom the bottom (= tree_depth - depth of key)
keyinput indexing key (at lowest resolution / level)
Returns
key corresponding to the input key at the given level

Definition at line 228 of file OcTreeKey.h.

◆ logodds()

float octomap::logodds ( double  probability)
inline

compute log-odds from probability:

Definition at line 42 of file octomap_utils.h.

◆ operator<<()

std::ostream & octomap::operator<< ( std::ostream &  out,
ColorOcTreeNode::Color const &  c 
)

user friendly output in format (r g b)

Definition at line 253 of file ColorOcTree.cpp.

◆ probability()

double octomap::probability ( double  logodds)
inline

compute probability from logodds:

Definition at line 47 of file octomap_utils.h.

Variable Documentation

◆ edgeTable

const int octomap::edgeTable[256]
static

Definition at line 44 of file MCTables.h.

◆ triTable

const int octomap::triTable[256][16]
static

Definition at line 78 of file MCTables.h.

◆ vertexList

const point3d octomap::vertexList[12]
static
Initial value:
=
{
point3d(1, 0, -1),
point3d(0, -1, -1),
point3d(-1, 0, -1),
point3d(0, 1, -1),
point3d(1, 0, 1),
point3d(0, -1, 1),
point3d(-1, 0, 1),
point3d(0, 1, 1),
point3d(1, 1, 0),
point3d(1, -1, 0),
point3d(-1, -1, 0),
point3d(-1, 1, 0),
}

Definition at line 336 of file MCTables.h.

octomap::point3d
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition: octomap_types.h:49


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Mar 21 2024 02:40:30