Functions
octomap_msgs Namespace Reference

Functions

template<class OctomapT >
static bool binaryMapToMsgData (const OctomapT &octomap, std::vector< int8_t > &mapData)
 Serialization of an octree into binary data e.g. for messages and services. Compact binary version (stores only max-likelihood free or occupied, .bt file format). The data will be much smaller if you call octomap.toMaxLikelihood() and octomap.prune() before.
static octomap::OcTree * binaryMsgDataToMap (const std::vector< int8_t > &mapData)
 Creates a new octree by deserializing from the binary stream mapData, e.g. from a message or service (binary: only free and occupied .bt file format). This creates a new OcTree object and returns a pointer to it. You will need to free the memory when you're done.
template<class OctomapT >
static bool fullMapToMsgData (const OctomapT &octomap, std::vector< int8_t > &mapData)
 Serialization of an octree into binary data e.g. for messages and services. Full probability version (stores complete state of tree, .ot file format). The data will be much smaller if you call octomap.toMaxLikelihood() and octomap.prune() before.
static octomap::AbstractOcTree * fullMsgDataToMap (const std::vector< int8_t > &mapData)
 Creates a new octree by deserializing from the binary stream mapData, e.g. from a message or service (full probabilities, .ot file format). This calls the general file factory of OctoMap, creates a new object and return an AbstractOcTree* to it. You will need to free the memory when you're done.

Detailed Description

OctoMap ROS message conversions / [de-] serialization

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

Function Documentation

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

Serialization of an octree into binary data e.g. for messages and services. Compact binary version (stores only max-likelihood free or occupied, .bt file format). The data will be much smaller if you call octomap.toMaxLikelihood() and octomap.prune() before.

Returns:
success of serialization

Definition at line 89 of file conversions.h.

static octomap::OcTree* octomap_msgs::binaryMsgDataToMap ( const std::vector< int8_t > &  mapData) [inline, static]

Creates a new octree by deserializing from the binary stream mapData, e.g. from a message or service (binary: only free and occupied .bt file format). This creates a new OcTree object and returns a pointer to it. You will need to free the memory when you're done.

Definition at line 67 of file conversions.h.

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

Serialization of an octree into binary data e.g. for messages and services. Full probability version (stores complete state of tree, .ot file format). The data will be much smaller if you call octomap.toMaxLikelihood() and octomap.prune() before.

Returns:
success of serialization

Definition at line 107 of file conversions.h.

static octomap::AbstractOcTree* octomap_msgs::fullMsgDataToMap ( const std::vector< int8_t > &  mapData) [inline, static]

Creates a new octree by deserializing from the binary stream mapData, e.g. from a message or service (full probabilities, .ot file format). This calls the general file factory of OctoMap, creates a new object and return an AbstractOcTree* to it. You will need to free the memory when you're done.

Definition at line 54 of file conversions.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


octomap_msgs
Author(s): Armin Hornung
autogenerated on Tue Jul 9 2013 10:21:10