DatabaseModelPose.h
Go to the documentation of this file.
00001 #ifndef _ROS_household_objects_database_msgs_DatabaseModelPose_h
00002 #define _ROS_household_objects_database_msgs_DatabaseModelPose_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "object_recognition_msgs/ObjectType.h"
00009 #include "geometry_msgs/PoseStamped.h"
00010 
00011 namespace household_objects_database_msgs
00012 {
00013 
00014   class DatabaseModelPose : public ros::Msg
00015   {
00016     public:
00017       int32_t model_id;
00018       object_recognition_msgs::ObjectType type;
00019       geometry_msgs::PoseStamped pose;
00020       float confidence;
00021       const char* detector_name;
00022 
00023     virtual int serialize(unsigned char *outbuffer) const
00024     {
00025       int offset = 0;
00026       union {
00027         int32_t real;
00028         uint32_t base;
00029       } u_model_id;
00030       u_model_id.real = this->model_id;
00031       *(outbuffer + offset + 0) = (u_model_id.base >> (8 * 0)) & 0xFF;
00032       *(outbuffer + offset + 1) = (u_model_id.base >> (8 * 1)) & 0xFF;
00033       *(outbuffer + offset + 2) = (u_model_id.base >> (8 * 2)) & 0xFF;
00034       *(outbuffer + offset + 3) = (u_model_id.base >> (8 * 3)) & 0xFF;
00035       offset += sizeof(this->model_id);
00036       offset += this->type.serialize(outbuffer + offset);
00037       offset += this->pose.serialize(outbuffer + offset);
00038       union {
00039         float real;
00040         uint32_t base;
00041       } u_confidence;
00042       u_confidence.real = this->confidence;
00043       *(outbuffer + offset + 0) = (u_confidence.base >> (8 * 0)) & 0xFF;
00044       *(outbuffer + offset + 1) = (u_confidence.base >> (8 * 1)) & 0xFF;
00045       *(outbuffer + offset + 2) = (u_confidence.base >> (8 * 2)) & 0xFF;
00046       *(outbuffer + offset + 3) = (u_confidence.base >> (8 * 3)) & 0xFF;
00047       offset += sizeof(this->confidence);
00048       uint32_t length_detector_name = strlen(this->detector_name);
00049       memcpy(outbuffer + offset, &length_detector_name, sizeof(uint32_t));
00050       offset += 4;
00051       memcpy(outbuffer + offset, this->detector_name, length_detector_name);
00052       offset += length_detector_name;
00053       return offset;
00054     }
00055 
00056     virtual int deserialize(unsigned char *inbuffer)
00057     {
00058       int offset = 0;
00059       union {
00060         int32_t real;
00061         uint32_t base;
00062       } u_model_id;
00063       u_model_id.base = 0;
00064       u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00065       u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00066       u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00067       u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00068       this->model_id = u_model_id.real;
00069       offset += sizeof(this->model_id);
00070       offset += this->type.deserialize(inbuffer + offset);
00071       offset += this->pose.deserialize(inbuffer + offset);
00072       union {
00073         float real;
00074         uint32_t base;
00075       } u_confidence;
00076       u_confidence.base = 0;
00077       u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00078       u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00079       u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00080       u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00081       this->confidence = u_confidence.real;
00082       offset += sizeof(this->confidence);
00083       uint32_t length_detector_name;
00084       memcpy(&length_detector_name, (inbuffer + offset), sizeof(uint32_t));
00085       offset += 4;
00086       for(unsigned int k= offset; k< offset+length_detector_name; ++k){
00087           inbuffer[k-1]=inbuffer[k];
00088       }
00089       inbuffer[offset+length_detector_name-1]=0;
00090       this->detector_name = (char *)(inbuffer + offset-1);
00091       offset += length_detector_name;
00092      return offset;
00093     }
00094 
00095     const char * getType(){ return "household_objects_database_msgs/DatabaseModelPose"; };
00096     const char * getMD5(){ return "6bc39ef48ca57cc7d4341cfc13a5a110"; };
00097 
00098   };
00099 
00100 }
00101 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Fri May 20 2016 03:48:55