38 #ifndef OCTOMAP_MSGS_CONVERT_MSGS_H 
   39 #define OCTOMAP_MSGS_CONVERT_MSGS_H 
   41 #include <octomap/octomap.h> 
   42 #include <octomap_msgs/Octomap.h> 
   43 #include <octomap/ColorOcTree.h> 
   55   static inline octomap::AbstractOcTree* 
fullMsgToMap(
const Octomap& msg){
 
   56     octomap::AbstractOcTree* tree = octomap::AbstractOcTree::createTree(msg.id, msg.resolution);    
 
   58       std::stringstream datastream;
 
   59       if (msg.data.size() > 0){
 
   60         datastream.write((
const char*) &msg.data[0], msg.data.size());
 
   61         tree->readData(datastream);
 
   69   template<
class TreeType>
 
   70   void readTree(TreeType* octree, 
const Octomap& msg){
 
   71     std::stringstream datastream;
 
   72     if (msg.data.size() > 0){
 
   73       datastream.write((
const char*) &msg.data[0], msg.data.size());
 
   74       octree->readBinaryData(datastream);
 
   89     octomap::AbstractOcTree* tree;
 
   90     if (msg.id == 
"ColorOcTree"){
 
   91       octomap::ColorOcTree* octree = 
new octomap::ColorOcTree(msg.resolution);    
 
   95       octomap::OcTree* octree = 
new octomap::OcTree(msg.resolution);    
 
  110   static inline octomap::AbstractOcTree* 
msgToMap(
const Octomap& msg){
 
  129   template <
class OctomapT>
 
  131     std::stringstream datastream;
 
  132     if (!octomap.writeBinaryConst(datastream))
 
  135     std::string datastring = datastream.str();
 
  136     mapData = std::vector<int8_t>(datastring.begin(), datastring.end());
 
  147   template <
class OctomapT>
 
  148   static inline bool fullMapToMsgData(
const OctomapT& octomap, std::vector<int8_t>& mapData){
 
  149     std::stringstream datastream;
 
  150     if (!octomap.write(datastream))
 
  153     std::string datastring = datastream.str();
 
  154     mapData = std::vector<int8_t>(datastring.begin(), datastring.end());
 
  165   template <
class OctomapT>
 
  167     msg.resolution = octomap.getResolution();
 
  168     msg.id = octomap.getTreeType();
 
  171     std::stringstream datastream;
 
  172     if (!octomap.writeBinaryData(datastream))
 
  175     std::string datastring = datastream.str();
 
  176     msg.data = std::vector<int8_t>(datastring.begin(), datastring.end());
 
  187   template <
class OctomapT>
 
  188   static inline bool fullMapToMsg(
const OctomapT& octomap, Octomap& msg){
 
  189     msg.resolution = octomap.getResolution();
 
  190     msg.id = octomap.getTreeType();
 
  193     std::stringstream datastream;
 
  194     if (!octomap.writeData(datastream))
 
  197     std::string datastring = datastream.str();
 
  198     msg.data = std::vector<int8_t>(datastring.begin(), datastring.end());