Namespaces | Classes | Typedefs | Functions | Variables
octomap Namespace Reference

Namespaces

 ColorOcTreeNode
 
 OcTreeKey
 

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::KeyHash > KeyBoolMap
 
typedef unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHash > KeySet
 
typedef std::pair< point3d, double > OcTreeVolume
 
typedef octomath::Vector3 point3d
 
typedef std::vector< octomath::Vector3point3d_collection
 
typedef std::list< octomath::Vector3point3d_list
 
typedef octomath::Pose6D pose6d
 

Functions

uint8_t computeChildIdx (const OcTreeKey &key, int depth)
 
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)
 
std::ostream & operator<< (std::ostream &out, ColorOcTreeNode::Color const &c)
 
void pointCloud2ToOctomap (const sensor_msgs::PointCloud2 &cloud, Pointcloud &octomapCloud)
 Conversion from a sensor_msgs::PointCLoud2 to octomap::Pointcloud, used internally in OctoMap. More...
 
static octomap::point3d pointMsgToOctomap (const geometry_msgs::Point &ptMsg)
 Conversion from geometry_msgs::Point to octomap::point3d. More...
 
static geometry_msgs::Point pointOctomapToMsg (const point3d &octomapPt)
 Conversion from octomap::point3d to geometry_msgs::Point. More...
 
static tf::Point pointOctomapToTf (const point3d &octomapPt)
 Conversion from octomap::point3d to tf::Point. More...
 
void pointsOctomapToPointCloud2 (const point3d_list &points, sensor_msgs::PointCloud2 &cloud)
 Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to sensor_msgs::PointCloud2. More...
 
static octomap::point3d pointTfToOctomap (const tf::Point &ptTf)
 Conversion from tf::Point to octomap::point3d. More...
 
static tf::Pose poseOctomapToTf (const octomap::pose6d &octomapPose)
 Conversion from octomap::pose6f to tf::Pose. More...
 
static octomap::pose6d poseTfToOctomap (const tf::Pose &poseTf)
 Conversion from tf::Pose to octomap::pose6d. More...
 
double probability (double logodds)
 
static tf::Quaternion quaternionOctomapToTf (const octomath::Quaternion &octomapQ)
 Conversion from octomap Quaternion to tf::Quaternion. More...
 
static octomath::Quaternion quaternionTfToOctomap (const tf::Quaternion &qTf)
 Conversion from tf::Quaternion to octomap Quaternion. More...
 

Variables

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

Detailed Description

OctoMap ROS integration

Author
A. Hornung, University of Freiburg, Copyright (C) 2011-2012.
See also
http://www.ros.org/wiki/octomap_ros License: BSD

OctoMap ROS integration

Author
A. Hornung, University of Freiburg, Copyright (C) 2011.
See also
http://www.ros.org/wiki/octomap_ros License: BSD

Function Documentation

◆ pointCloud2ToOctomap()

void octomap::pointCloud2ToOctomap ( const sensor_msgs::PointCloud2 &  cloud,
Pointcloud octomapCloud 
)

Conversion from a sensor_msgs::PointCLoud2 to octomap::Pointcloud, used internally in OctoMap.

Parameters
cloud
octomapCloud

Definition at line 92 of file conversions.cpp.

◆ pointMsgToOctomap()

static octomap::point3d octomap::pointMsgToOctomap ( const geometry_msgs::Point ptMsg)
inlinestatic

Conversion from geometry_msgs::Point to octomap::point3d.

Definition at line 76 of file conversions.h.

◆ pointOctomapToMsg()

static geometry_msgs::Point octomap::pointOctomapToMsg ( const point3d octomapPt)
inlinestatic

Conversion from octomap::point3d to geometry_msgs::Point.

Definition at line 66 of file conversions.h.

◆ pointOctomapToTf()

static tf::Point octomap::pointOctomapToTf ( const point3d octomapPt)
inlinestatic

Conversion from octomap::point3d to tf::Point.

Definition at line 81 of file conversions.h.

◆ pointsOctomapToPointCloud2()

void octomap::pointsOctomapToPointCloud2 ( const point3d_list points,
sensor_msgs::PointCloud2 &  cloud 
)

Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to sensor_msgs::PointCloud2.

Parameters
points
cloud

Definition at line 52 of file conversions.cpp.

◆ pointTfToOctomap()

static octomap::point3d octomap::pointTfToOctomap ( const tf::Point ptTf)
inlinestatic

Conversion from tf::Point to octomap::point3d.

Definition at line 86 of file conversions.h.

◆ poseOctomapToTf()

static tf::Pose octomap::poseOctomapToTf ( const octomap::pose6d octomapPose)
inlinestatic

Conversion from octomap::pose6f to tf::Pose.

Definition at line 101 of file conversions.h.

◆ poseTfToOctomap()

static octomap::pose6d octomap::poseTfToOctomap ( const tf::Pose poseTf)
inlinestatic

Conversion from tf::Pose to octomap::pose6d.

Definition at line 106 of file conversions.h.

◆ quaternionOctomapToTf()

static tf::Quaternion octomap::quaternionOctomapToTf ( const octomath::Quaternion octomapQ)
inlinestatic

Conversion from octomap Quaternion to tf::Quaternion.

Definition at line 91 of file conversions.h.

◆ quaternionTfToOctomap()

static octomath::Quaternion octomap::quaternionTfToOctomap ( const tf::Quaternion qTf)
inlinestatic

Conversion from tf::Quaternion to octomap Quaternion.

Definition at line 96 of file conversions.h.



octomap_ros
Author(s): Armin Hornung
autogenerated on Fri Mar 24 2023 02:43:30