octomap::OctomapROS< OctreeT > Class Template Reference

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...

#include <OctomapROS.h>

List of all members.

Public Types

typedef OctreeT::NodeType NodeType
 Type of the wrapped octree's nodes.
typedef OctreeT OcTreeType
 Type of the wrapped octree.

Public Member Functions

template<class PointT >
bool castRay (const PointT &origin, const PointT &direction, PointT &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
 Performs raycasting in 3d.
template<class PointT >
bool insertRay (const PointT &origin, const PointT &end, double maxRange=-1.0)
 Insert one ray between origin and end into the tree. The last node will be marked as occupied, all others on the ray as free.
template<class PCLPointT , class PCLQuaternionT >
void insertScan (const pcl::PointCloud< PCLPointT > &scan, const PCLPointT &sensor_origin, const PCLPointT &frame_origin_trans, const PCLQuaternionT &frame_origin_rot, double maxrange=-1., bool pruning=true, bool dirty=false)
 Integrate a 3d scan in relative coordinates, transform scan before tree update.
template<class PCLPointT , class PointT >
void insertScan (const pcl::PointCloud< PCLPointT > &scan, const PointT &origin, double maxrange=-1., bool pruning=true, bool dirty=false)
 Integrate a Pointcloud measurement (in global reference frame).
template<class PointT >
void insertScan (const sensor_msgs::PointCloud2 &scan, const PointT &origin, double maxrange=-1., bool pruning=true, bool dirty=false)
 Integrate a Pointcloud measurement (ROS msg, in global reference frame).
 OctomapROS (OctreeT tree)
 OctomapROS (double resolution)
OctreeT::NodeType * search (const tf::Point &point) const
template<class PointT >
OctreeT::NodeType * search (const PointT &point) const
 Search for a Node in the octree at a given coordinate. You need to check if a node is found at all (returned pointer != NULL).
virtual ~OctomapROS ()

Public Attributes

OctreeT octree
 the wrapped OctoMap octree

Detailed Description

template<class OctreeT>
class octomap::OctomapROS< OctreeT >

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.

Definition at line 66 of file OctomapROS.h.


Member Typedef Documentation

template<class OctreeT >
typedef OctreeT::NodeType octomap::OctomapROS< OctreeT >::NodeType

Type of the wrapped octree's nodes.

Definition at line 153 of file OctomapROS.h.

template<class OctreeT >
typedef OctreeT octomap::OctomapROS< OctreeT >::OcTreeType

Type of the wrapped octree.

Definition at line 152 of file OctomapROS.h.


Constructor & Destructor Documentation

template<class OctreeT >
octomap::OctomapROS< OctreeT >::OctomapROS ( double  resolution  )  [inline]

Definition at line 183 of file OctomapROS.h.

template<class OctreeT >
octomap::OctomapROS< OctreeT >::OctomapROS ( OctreeT  tree  ) 
template<class OctreeT >
virtual octomap::OctomapROS< OctreeT >::~OctomapROS (  )  [inline, virtual]

Definition at line 58 of file OctomapROS.h.


Member Function Documentation

template<class OctreeT >
template<class PointT >
bool octomap::OctomapROS< OctreeT >::castRay ( const PointT &  origin,
const PointT &  direction,
PointT &  end,
bool  ignoreUnknownCells = false,
double  maxRange = -1.0 
) const [inline]

Performs raycasting in 3d.

A ray is cast from origin with a given direction, the first occupied cell is returned (as center coordinate). If the starting coordinate is already occupied in the tree, this coordinate will be returned as a hit.

Parameters:
origin Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
direction Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
end Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
ignoreUnknownCells whether unknown cells are ignored. If false (default), the raycast aborts when an unkown cell is hit.
maxRange Maximum range after which the raycast is aborted (<= 0: no limit, default)
Returns:
whether or not an occupied cell was hit

Definition at line 246 of file OctomapROS.h.

template<class OctreeT >
template<class PointT >
bool octomap::OctomapROS< OctreeT >::insertRay ( const PointT &  origin,
const PointT &  end,
double  maxRange = -1.0 
) [inline]

Insert one ray between origin and end into the tree. The last node will be marked as occupied, all others on the ray as free.

Parameters:
origin Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
end Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
maxRange 
Returns:

Definition at line 237 of file OctomapROS.h.

template<class OctreeT >
template<class PCLPointT , class PCLQuaternionT >
void octomap::OctomapROS< OctreeT >::insertScan ( const pcl::PointCloud< PCLPointT > &  scan,
const PCLPointT &  sensor_origin,
const PCLPointT &  frame_origin_trans,
const PCLQuaternionT &  frame_origin_rot,
double  maxrange = -1.,
bool  pruning = true,
bool  dirty = false 
) [inline]

Integrate a 3d scan in relative coordinates, transform scan before tree update.

Parameters:
pc Pointcloud (measurement endpoints) relative to frame origin
sensor_origin origin of sensor relative to frame origin
frame_origin_trans Translation of reference frame origin, determines transform to be applied to cloud and sensor origin
frame_origin_rot Rotation (as quaternion) of reference frame origin, determines transform to be applied to cloud and sensor origin
maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
pruning whether the tree is (losslessly) pruned after insertion (default: true) This speeds up the insertion by not updating inner nodes, but you need to call octree.updateInnerOccupancy() when done.

Definition at line 206 of file OctomapROS.h.

template<class OctreeT >
template<class PCLPointT , class PointT >
void octomap::OctomapROS< OctreeT >::insertScan ( const pcl::PointCloud< PCLPointT > &  scan,
const PointT &  origin,
double  maxrange = -1.,
bool  pruning = true,
bool  dirty = false 
) [inline]

Integrate a Pointcloud measurement (in global reference frame).

Parameters:
scan pcl PointCloud of arbitrary type. Only the members x,y,z of the Points are used.
origin Origin of the scan. Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
pruning whether the tree is (losslessly) pruned after insertion (default: true) This speeds up the insertion by not updating inner nodes, but you need to call octree.updateInnerOccupancy() when done.

Definition at line 193 of file OctomapROS.h.

template<class OctreeT >
template<class PointT >
void octomap::OctomapROS< OctreeT >::insertScan ( const sensor_msgs::PointCloud2 &  scan,
const PointT &  origin,
double  maxrange = -1.,
bool  pruning = true,
bool  dirty = false 
) [inline]

Integrate a Pointcloud measurement (ROS msg, in global reference frame).

Parameters:
scan PointCloud2 of measurement endpoints
origin Origin of the scan. Any type of Point that has x,y,z member (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
pruning whether the tree is (losslessly) pruned after insertion (default: true)
dirty whether the tree is left 'dirty' after the update (default: false). This speeds up the insertion by not updating inner nodes, but you need to call octree.updateInnerOccupancy() when done.

Definition at line 225 of file OctomapROS.h.

template<class OctreeT >
OctreeT::NodeType * octomap::OctomapROS< OctreeT >::search ( const tf::Point &  point  )  const [inline]

Definition at line 268 of file OctomapROS.h.

template<class OctreeT >
template<class PointT >
OctreeT::NodeType * octomap::OctomapROS< OctreeT >::search ( const PointT &  point  )  const [inline]

Search for a Node in the octree at a given coordinate. You need to check if a node is found at all (returned pointer != NULL).

Parameters:
point The searched coordinate. Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
Returns:
Pointer to the octree node at the coordinate if it exists, NULL if it doesn't.

Definition at line 263 of file OctomapROS.h.


Member Data Documentation

template<class OctreeT >
OctreeT octomap::OctomapROS< OctreeT >::octree

the wrapped OctoMap octree

Definition at line 150 of file OctomapROS.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Defines


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