octomap Namespace Reference

Classes

class  OctomapROS
 ROS wrapper class for OctoMap Octrees, providing the most important functionality with ROS / PCL types. The class is templated over the Octree type. Any OcTree derived from octomap::OccupancyOcTreeBase should work. For most cases, OcTreeROS should work best for occupancy maps. More...

Typedefs

typedef OctomapROS< OcTree > OcTreeROS
 The default octomap::OcTree wrapped in ROS. OcTree provides a 3D occupancy map which stores log-odds in OcTreeNodes of floats.

Functions

template<class OctomapT >
static void octomapMapToMsg (const OctomapT &octomap, octomap_ros::OctomapBinary &mapMsg)
 Converts an octomap map structure to a ROS octomap msg as binary data. This will fill the timestamp of the header with the current time, but will not fill in the frame_id.
template<class OctomapT >
static void octomapMapToMsgData (const OctomapT &octomap, std::vector< int8_t > &mapData)
 Converts an octomap map structure to a ROS binary data, which can be put into a dedicated octomap msg.
template<class OctomapT >
static void octomapMsgDataToMap (const std::vector< int8_t > &mapData, OctomapT &octomap)
 Converts ROS binary data to an octomap map structure, e.g. coming from an octomap msg.
template<class OctomapT >
static void octomapMsgToMap (const octomap_ros::OctomapBinary &mapMsg, OctomapT &octomap)
 Converts a ROS octomap msg (binary data) to an octomap map structure.
static template void pointcloudPCLToOctomap (const pcl::PointCloud< pcl::PointXYZ > &pclCloud, Pointcloud &octomapCloud)
template<class PointT >
static void pointcloudPCLToOctomap (const pcl::PointCloud< PointT > &pclCloud, Pointcloud &octomapCloud)
 Conversion from a PCL pointcloud to octomap::Pointcloud, used internally in OctoMap.
static octomap::point3d pointMsgToOctomap (const geometry_msgs::Point &ptMsg)
 Conversion from geometry_msgs::Point to octomap::point3d.
static geometry_msgs::Point pointOctomapToMsg (const point3d &octomapPt)
 Conversion from octomap::point3d to geometry_msgs::Point.
template<class PointT >
static PointT pointOctomapToPCL (const point3d &octomapPt)
static tf::Point pointOctomapToTf (const point3d &octomapPt)
 Conversion from octomap::point3d to tf::Point.
template<class PointT >
static octomap::point3d pointPCLToOctomap (const PointT &p)
 Conversion from pcl::PointT to octomap::point3d.
static template void pointsOctomapToPCL (const point3d_list &points, pcl::PointCloud< pcl::PointXYZ > &cloud)
template<class PointT >
static void pointsOctomapToPCL (const point3d_list &points, pcl::PointCloud< PointT > &cloud)
 Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to pcl PointCloud.
static octomap::point3d pointTfToOctomap (const tf::Point &ptTf)
 Conversion from tf::Point to octomap::point3d.
static tf::Pose poseOctomapToTf (const octomap::pose6d &octomapPose)
 Conversion from octomap::pose6f to tf::Pose.
static octomap::pose6d poseTfToOctomap (const tf::Pose &poseTf)
 Conversion from tf::Pose to octomap::pose6d.
static tf::Quaternion quaternionOctomapToTf (const octomath::Quaternion &octomapQ)
 Conversion from octomap Quaternion to tf::Quaternion.
static octomath::Quaternion quaternionTfToOctomap (const tf::Quaternion &qTf)
 Conversion from tf::Quaternion to octomap Quaternion.

Detailed Description

OctoMap ROS integration

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

Typedef Documentation

typedef OctomapROS<OcTree> octomap::OcTreeROS

The default octomap::OcTree wrapped in ROS. OcTree provides a 3D occupancy map which stores log-odds in OcTreeNodes of floats.

Definition at line 174 of file OctomapROS.h.


Function Documentation

template<class OctomapT >
static void octomap::octomapMapToMsg ( const OctomapT &  octomap,
octomap_ros::OctomapBinary mapMsg 
) [inline, static]

Converts an octomap map structure to a ROS octomap msg as binary data. This will fill the timestamp of the header with the current time, but will not fill in the frame_id.

Parameters:
octomap input OcTree
mapMsg output msg

Definition at line 59 of file conversions.h.

template<class OctomapT >
static void octomap::octomapMapToMsgData ( const OctomapT &  octomap,
std::vector< int8_t > &  mapData 
) [inline, static]

Converts an octomap map structure to a ROS binary data, which can be put into a dedicated octomap msg.

Parameters:
octomap input OcTree
mapData binary output data as int8[]

Definition at line 73 of file conversions.h.

template<class OctomapT >
static void octomap::octomapMsgDataToMap ( const std::vector< int8_t > &  mapData,
OctomapT &  octomap 
) [inline, static]

Converts ROS binary data to an octomap map structure, e.g. coming from an octomap msg.

Parameters:
mapData input binary data
octomap output OcTree

Definition at line 104 of file conversions.h.

template<class OctomapT >
static void octomap::octomapMsgToMap ( const octomap_ros::OctomapBinary mapMsg,
OctomapT &  octomap 
) [inline, static]

Converts a ROS octomap msg (binary data) to an octomap map structure.

Parameters:
mapMsg 
octomap 

Definition at line 92 of file conversions.h.

static template void octomap::pointcloudPCLToOctomap ( const pcl::PointCloud< pcl::PointXYZ > &  pclCloud,
Pointcloud &  octomapCloud 
) [inline, static]
template<class PointT >
static void octomap::pointcloudPCLToOctomap ( const pcl::PointCloud< PointT > &  pclCloud,
Pointcloud &  octomapCloud 
) [inline, static]

Conversion from a PCL pointcloud to octomap::Pointcloud, used internally in OctoMap.

Parameters:
pclCloud 
octomapCloud 

Definition at line 135 of file conversions.h.

static octomap::point3d octomap::pointMsgToOctomap ( const geometry_msgs::Point &  ptMsg  )  [inline, static]

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

Definition at line 158 of file conversions.h.

static geometry_msgs::Point octomap::pointOctomapToMsg ( const point3d &  octomapPt  )  [inline, static]

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

Definition at line 148 of file conversions.h.

template<class PointT >
static PointT octomap::pointOctomapToPCL ( const point3d &  octomapPt  )  [inline, static]

Conversion from octomap::point3d to pcl::PointT, templated over pcl::PointT You might have to call this like "pointOctomapToPCL<pcl::PointXYZ>(point3d)"

Definition at line 181 of file conversions.h.

static tf::Point octomap::pointOctomapToTf ( const point3d &  octomapPt  )  [inline, static]

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

Definition at line 163 of file conversions.h.

template<class PointT >
static octomap::point3d octomap::pointPCLToOctomap ( const PointT &  p  )  [inline, static]

Conversion from pcl::PointT to octomap::point3d.

Definition at line 174 of file conversions.h.

static template void octomap::pointsOctomapToPCL ( const point3d_list &  points,
pcl::PointCloud< pcl::PointXYZ > &  cloud 
) [inline, static]
template<class PointT >
static void octomap::pointsOctomapToPCL ( const point3d_list &  points,
pcl::PointCloud< PointT > &  cloud 
) [inline, static]

Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to pcl PointCloud.

Parameters:
points 
scan 

Definition at line 119 of file conversions.h.

static octomap::point3d octomap::pointTfToOctomap ( const tf::Point &  ptTf  )  [inline, static]

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

Definition at line 168 of file conversions.h.

static tf::Pose octomap::poseOctomapToTf ( const octomap::pose6d &  octomapPose  )  [inline, static]

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

Definition at line 196 of file conversions.h.

static octomap::pose6d octomap::poseTfToOctomap ( const tf::Pose &  poseTf  )  [inline, static]

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

Definition at line 201 of file conversions.h.

static tf::Quaternion octomap::quaternionOctomapToTf ( const octomath::Quaternion &  octomapQ  )  [inline, static]

Conversion from octomap Quaternion to tf::Quaternion.

Definition at line 186 of file conversions.h.

static octomath::Quaternion octomap::quaternionTfToOctomap ( const tf::Quaternion &  qTf  )  [inline, static]

Conversion from tf::Quaternion to octomap Quaternion.

Definition at line 191 of file conversions.h.

 All Classes Namespaces Files Functions Variables Typedefs Defines


octomap_ros
Author(s): Armin Hornung
autogenerated on Fri Jan 11 09:39:10 2013