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::AbstractOcTree * | 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. | |
template<class TreeType > | |
void | readTree (TreeType *octree, const Octomap &msg) |
OctoMap ROS message conversions / [de-] serialization
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.
Definition at line 166 of file conversions.h.
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.
Definition at line 130 of file conversions.h.
static octomap::AbstractOcTree* 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 85 of file conversions.h.
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.
Definition at line 188 of file conversions.h.
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.
Definition at line 148 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 55 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 110 of file conversions.h.
void octomap_msgs::readTree | ( | TreeType * | octree, |
const Octomap & | msg | ||
) |
Definition at line 70 of file conversions.h.