RecognizedObject.h
Go to the documentation of this file.
00001 #ifndef _ROS_object_recognition_msgs_RecognizedObject_h
00002 #define _ROS_object_recognition_msgs_RecognizedObject_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 "object_recognition_msgs/ObjectType.h"
00010 #include "sensor_msgs/PointCloud2.h"
00011 #include "shape_msgs/Mesh.h"
00012 #include "geometry_msgs/Point.h"
00013 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00014 
00015 namespace object_recognition_msgs
00016 {
00017 
00018   class RecognizedObject : public ros::Msg
00019   {
00020     public:
00021       std_msgs::Header header;
00022       object_recognition_msgs::ObjectType type;
00023       float confidence;
00024       uint8_t point_clouds_length;
00025       sensor_msgs::PointCloud2 st_point_clouds;
00026       sensor_msgs::PointCloud2 * point_clouds;
00027       shape_msgs::Mesh bounding_mesh;
00028       uint8_t bounding_contours_length;
00029       geometry_msgs::Point st_bounding_contours;
00030       geometry_msgs::Point * bounding_contours;
00031       geometry_msgs::PoseWithCovarianceStamped pose;
00032 
00033     virtual int serialize(unsigned char *outbuffer) const
00034     {
00035       int offset = 0;
00036       offset += this->header.serialize(outbuffer + offset);
00037       offset += this->type.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       *(outbuffer + offset++) = point_clouds_length;
00049       *(outbuffer + offset++) = 0;
00050       *(outbuffer + offset++) = 0;
00051       *(outbuffer + offset++) = 0;
00052       for( uint8_t i = 0; i < point_clouds_length; i++){
00053       offset += this->point_clouds[i].serialize(outbuffer + offset);
00054       }
00055       offset += this->bounding_mesh.serialize(outbuffer + offset);
00056       *(outbuffer + offset++) = bounding_contours_length;
00057       *(outbuffer + offset++) = 0;
00058       *(outbuffer + offset++) = 0;
00059       *(outbuffer + offset++) = 0;
00060       for( uint8_t i = 0; i < bounding_contours_length; i++){
00061       offset += this->bounding_contours[i].serialize(outbuffer + offset);
00062       }
00063       offset += this->pose.serialize(outbuffer + offset);
00064       return offset;
00065     }
00066 
00067     virtual int deserialize(unsigned char *inbuffer)
00068     {
00069       int offset = 0;
00070       offset += this->header.deserialize(inbuffer + offset);
00071       offset += this->type.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       uint8_t point_clouds_lengthT = *(inbuffer + offset++);
00084       if(point_clouds_lengthT > point_clouds_length)
00085         this->point_clouds = (sensor_msgs::PointCloud2*)realloc(this->point_clouds, point_clouds_lengthT * sizeof(sensor_msgs::PointCloud2));
00086       offset += 3;
00087       point_clouds_length = point_clouds_lengthT;
00088       for( uint8_t i = 0; i < point_clouds_length; i++){
00089       offset += this->st_point_clouds.deserialize(inbuffer + offset);
00090         memcpy( &(this->point_clouds[i]), &(this->st_point_clouds), sizeof(sensor_msgs::PointCloud2));
00091       }
00092       offset += this->bounding_mesh.deserialize(inbuffer + offset);
00093       uint8_t bounding_contours_lengthT = *(inbuffer + offset++);
00094       if(bounding_contours_lengthT > bounding_contours_length)
00095         this->bounding_contours = (geometry_msgs::Point*)realloc(this->bounding_contours, bounding_contours_lengthT * sizeof(geometry_msgs::Point));
00096       offset += 3;
00097       bounding_contours_length = bounding_contours_lengthT;
00098       for( uint8_t i = 0; i < bounding_contours_length; i++){
00099       offset += this->st_bounding_contours.deserialize(inbuffer + offset);
00100         memcpy( &(this->bounding_contours[i]), &(this->st_bounding_contours), sizeof(geometry_msgs::Point));
00101       }
00102       offset += this->pose.deserialize(inbuffer + offset);
00103      return offset;
00104     }
00105 
00106     const char * getType(){ return "object_recognition_msgs/RecognizedObject"; };
00107     const char * getMD5(){ return "f92c4cb29ba11f26c5f7219de97e900d"; };
00108 
00109   };
00110 
00111 }
00112 #endif


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