Public Types | Public Member Functions | Protected Attributes
octomap::ButOctomapROS< 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 <ButOctomapRos.h>

List of all members.

Public Types

typedef OctreeT::NodeType NodeType
 Type of the wrapped octree's nodes.
typedef boost::shared_ptr
< OctreeT > 
OctreePtr
typedef OctreeT OcTreeType
 Type of the wrapped octree.

Public Member Functions

 ButOctomapROS (double resolution)
 ButOctomapROS (OctreeT *tree)
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.
OctreeT & getTree ()
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 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)
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 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 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).
OctreeT::NodeType * search (const tf::Point &point) const
void setTree (OctreeT *tree)
virtual ~ButOctomapROS ()

Protected Attributes

OctreePtr octree
 the wrapped OctoMap octree

Detailed Description

template<class OctreeT>
class octomap::ButOctomapROS< 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 75 of file ButOctomapRos.h.


Member Typedef Documentation

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

Type of the wrapped octree's nodes.

Definition at line 171 of file ButOctomapRos.h.

template<class OctreeT >
typedef boost::shared_ptr<OctreeT> octomap::ButOctomapROS< OctreeT >::OctreePtr

Definition at line 172 of file ButOctomapRos.h.

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

Type of the wrapped octree.

Definition at line 170 of file ButOctomapRos.h.


Constructor & Destructor Documentation

template<class OctreeT >
octomap::ButOctomapROS< OctreeT >::ButOctomapROS ( double  resolution)

Definition at line 197 of file ButOctomapRos.h.

template<class OctreeT >
octomap::ButOctomapROS< OctreeT >::ButOctomapROS ( OctreeT *  tree)

Definition at line 204 of file ButOctomapRos.h.

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

Definition at line 79 of file ButOctomapRos.h.


Member Function Documentation

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

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:
originAny type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
directionAny type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
endAny type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
ignoreUnknownCellswhether unknown cells are ignored. If false (default), the raycast aborts when an unkown cell is hit.
maxRangeMaximum range after which the raycast is aborted (<= 0: no limit, default)
Returns:
whether or not an occupied cell was hit

Definition at line 276 of file ButOctomapRos.h.

template<class OctreeT >
OctreeT& octomap::ButOctomapROS< OctreeT >::getTree ( ) [inline]

Definition at line 174 of file ButOctomapRos.h.

template<class OctreeT >
template<class PointT >
bool octomap::ButOctomapROS< OctreeT >::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.

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

Definition at line 267 of file ButOctomapRos.h.

template<class OctreeT >
template<class PointT >
void octomap::ButOctomapROS< OctreeT >::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)

Parameters:
scanPointCloud2 of measurement endpoints
originOrigin of the scan. Any type of Point that has x,y,z member (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
pruningwhether the tree is (losslessly) pruned after insertion (default: true)
dirtywhether 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 255 of file ButOctomapRos.h.

template<class OctreeT >
template<class PCLPointT , class PointT >
void octomap::ButOctomapROS< OctreeT >::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)

Parameters:
scanpcl PointCloud of arbitrary type. Only the members x,y,z of the Points are used.
originOrigin of the scan. Any type of Point that has x,y,z members (e.g. pcl::PointXYZ or a geometry_msgs::Point) works.
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
pruningwhether 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 223 of file ButOctomapRos.h.

template<class OctreeT >
template<class PCLPointT , class PCLQuaternionT >
void octomap::ButOctomapROS< 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 
)

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

Parameters:
pcPointcloud (measurement endpoints) relative to frame origin
sensor_originorigin of sensor relative to frame origin
frame_origin_transTranslation of reference frame origin, determines transform to be applied to cloud and sensor origin
frame_origin_rotRotation (as quaternion) of reference frame origin, determines transform to be applied to cloud and sensor origin
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
pruningwhether 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 236 of file ButOctomapRos.h.

template<class OctreeT >
template<class PointT >
OctreeT::NodeType * octomap::ButOctomapROS< OctreeT >::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).

Parameters:
pointThe 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 293 of file ButOctomapRos.h.

template<class OctreeT >
OctreeT::NodeType * octomap::ButOctomapROS< OctreeT >::search ( const tf::Point point) const

Definition at line 298 of file ButOctomapRos.h.

template<class OctreeT >
void octomap::ButOctomapROS< OctreeT >::setTree ( OctreeT *  tree)

Definition at line 211 of file ButOctomapRos.h.


Member Data Documentation

template<class OctreeT >
OctreePtr octomap::ButOctomapROS< OctreeT >::octree [protected]

the wrapped OctoMap octree

Definition at line 179 of file ButOctomapRos.h.


The documentation for this class was generated from the following file:


srs_env_model
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Tomas Lokaj, Jan Gorig, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:50:50