Classes | Typedefs | Functions
octomap Namespace Reference

Classes

class  OctomapROS
 DEPRECATED wrapper class for OctoMap Octrees. Is is recommended to use the OctoMap libary and octomap_ros/conversions.h directly instead! 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

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-2012.
See also:
http://www.ros.org/wiki/octomap_ros License: BSD

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

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 175 of file OctomapROS.h.


Function Documentation

static template void octomap::pointcloudPCLToOctomap ( const pcl::PointCloud< pcl::PointXYZ > &  pclCloud,
Pointcloud &  octomapCloud 
) [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 77 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 100 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 90 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 123 of file conversions.h.

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

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

Definition at line 105 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 116 of file conversions.h.

static template void octomap::pointsOctomapToPCL ( const point3d_list &  points,
pcl::PointCloud< pcl::PointXYZ > &  cloud 
) [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 61 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 110 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 138 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 143 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 128 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 133 of file conversions.h.

 All Classes Namespaces Files Functions Variables Typedefs Defines


octomap_ros
Author(s): Armin Hornung
autogenerated on Sun Dec 23 2012 13:27:44