Functions
octomap_msgs Namespace Reference

Functions

template<class OctomapT >
static bool binaryMapToMsg (const OctomapT &octomap, Octomap &msg)
 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.
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 * binaryMsgToMap (const Octomap &msg)
 Creates a new octree by deserializing from msg, 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 fullMapToMsg (const OctomapT &octomap, Octomap &msg)
 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.
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 * fullMsgToMap (const Octomap &msg)
 Creates a new octree by deserializing from a message that contains the full map information (i.e., binary is false) and returns an AbstractOcTree* to it. You will need to free the memory when you're done.
static octomap::AbstractOcTree * msgToMap (const Octomap &msg)
 Convert an octomap representation to a new octree (full probabilities or binary). You will need to free the memory. Return NULL on error.

Detailed Description

OctoMap ROS message conversions / [de-] serialization

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

Function Documentation

template<class OctomapT >
static bool octomap_msgs::binaryMapToMsg ( const OctomapT &  octomap,
Octomap &  msg 
) [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 149 of file conversions.h.

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 113 of file conversions.h.

static octomap::OcTree* octomap_msgs::binaryMsgToMap ( const Octomap &  msg) [inline, static]

Creates a new octree by deserializing from msg, 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 72 of file conversions.h.

template<class OctomapT >
static bool octomap_msgs::fullMapToMsg ( const OctomapT &  octomap,
Octomap &  msg 
) [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 171 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 131 of file conversions.h.

static octomap::AbstractOcTree* octomap_msgs::fullMsgToMap ( const Octomap &  msg) [inline, static]

Creates a new octree by deserializing from a message that contains the full map information (i.e., binary is false) and returns an AbstractOcTree* to it. You will need to free the memory when you're done.

Definition at line 54 of file conversions.h.

static octomap::AbstractOcTree* octomap_msgs::msgToMap ( const Octomap &  msg) [inline, static]

Convert an octomap representation to a new octree (full probabilities or binary). You will need to free the memory. Return NULL on error.

Definition at line 93 of file conversions.h.



octomap_msgs
Author(s): Armin Hornung
autogenerated on Fri Aug 28 2015 11:49:59