Info.h
Go to the documentation of this file.
00001 #ifndef _ROS_rtabmap_Info_h
00002 #define _ROS_rtabmap_Info_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "geometry_msgs/Transform.h"
00010 #include "geometry_msgs/Pose.h"
00011 
00012 namespace rtabmap
00013 {
00014 
00015   class Info : public ros::Msg
00016   {
00017     public:
00018       std_msgs::Header header;
00019       int32_t refId;
00020       int32_t loopClosureId;
00021       int32_t localLoopClosureId;
00022       geometry_msgs::Transform mapCorrection;
00023       geometry_msgs::Transform loopClosureTransform;
00024       geometry_msgs::Pose currentPose;
00025 
00026     virtual int serialize(unsigned char *outbuffer) const
00027     {
00028       int offset = 0;
00029       offset += this->header.serialize(outbuffer + offset);
00030       union {
00031         int32_t real;
00032         uint32_t base;
00033       } u_refId;
00034       u_refId.real = this->refId;
00035       *(outbuffer + offset + 0) = (u_refId.base >> (8 * 0)) & 0xFF;
00036       *(outbuffer + offset + 1) = (u_refId.base >> (8 * 1)) & 0xFF;
00037       *(outbuffer + offset + 2) = (u_refId.base >> (8 * 2)) & 0xFF;
00038       *(outbuffer + offset + 3) = (u_refId.base >> (8 * 3)) & 0xFF;
00039       offset += sizeof(this->refId);
00040       union {
00041         int32_t real;
00042         uint32_t base;
00043       } u_loopClosureId;
00044       u_loopClosureId.real = this->loopClosureId;
00045       *(outbuffer + offset + 0) = (u_loopClosureId.base >> (8 * 0)) & 0xFF;
00046       *(outbuffer + offset + 1) = (u_loopClosureId.base >> (8 * 1)) & 0xFF;
00047       *(outbuffer + offset + 2) = (u_loopClosureId.base >> (8 * 2)) & 0xFF;
00048       *(outbuffer + offset + 3) = (u_loopClosureId.base >> (8 * 3)) & 0xFF;
00049       offset += sizeof(this->loopClosureId);
00050       union {
00051         int32_t real;
00052         uint32_t base;
00053       } u_localLoopClosureId;
00054       u_localLoopClosureId.real = this->localLoopClosureId;
00055       *(outbuffer + offset + 0) = (u_localLoopClosureId.base >> (8 * 0)) & 0xFF;
00056       *(outbuffer + offset + 1) = (u_localLoopClosureId.base >> (8 * 1)) & 0xFF;
00057       *(outbuffer + offset + 2) = (u_localLoopClosureId.base >> (8 * 2)) & 0xFF;
00058       *(outbuffer + offset + 3) = (u_localLoopClosureId.base >> (8 * 3)) & 0xFF;
00059       offset += sizeof(this->localLoopClosureId);
00060       offset += this->mapCorrection.serialize(outbuffer + offset);
00061       offset += this->loopClosureTransform.serialize(outbuffer + offset);
00062       offset += this->currentPose.serialize(outbuffer + offset);
00063       return offset;
00064     }
00065 
00066     virtual int deserialize(unsigned char *inbuffer)
00067     {
00068       int offset = 0;
00069       offset += this->header.deserialize(inbuffer + offset);
00070       union {
00071         int32_t real;
00072         uint32_t base;
00073       } u_refId;
00074       u_refId.base = 0;
00075       u_refId.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00076       u_refId.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00077       u_refId.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00078       u_refId.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00079       this->refId = u_refId.real;
00080       offset += sizeof(this->refId);
00081       union {
00082         int32_t real;
00083         uint32_t base;
00084       } u_loopClosureId;
00085       u_loopClosureId.base = 0;
00086       u_loopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00087       u_loopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00088       u_loopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00089       u_loopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00090       this->loopClosureId = u_loopClosureId.real;
00091       offset += sizeof(this->loopClosureId);
00092       union {
00093         int32_t real;
00094         uint32_t base;
00095       } u_localLoopClosureId;
00096       u_localLoopClosureId.base = 0;
00097       u_localLoopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00098       u_localLoopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00099       u_localLoopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00100       u_localLoopClosureId.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00101       this->localLoopClosureId = u_localLoopClosureId.real;
00102       offset += sizeof(this->localLoopClosureId);
00103       offset += this->mapCorrection.deserialize(inbuffer + offset);
00104       offset += this->loopClosureTransform.deserialize(inbuffer + offset);
00105       offset += this->currentPose.deserialize(inbuffer + offset);
00106      return offset;
00107     }
00108 
00109     const char * getType(){ return "rtabmap/Info"; };
00110     const char * getMD5(){ return "5e0a63a901c65837fce2c2347aaba026"; };
00111 
00112   };
00113 
00114 }
00115 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:49