GraspableObjectList.h
Go to the documentation of this file.
00001 #ifndef _ROS_manipulation_msgs_GraspableObjectList_h
00002 #define _ROS_manipulation_msgs_GraspableObjectList_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "manipulation_msgs/GraspableObject.h"
00009 #include "sensor_msgs/Image.h"
00010 #include "sensor_msgs/CameraInfo.h"
00011 #include "shape_msgs/Mesh.h"
00012 #include "geometry_msgs/Pose.h"
00013 
00014 namespace manipulation_msgs
00015 {
00016 
00017   class GraspableObjectList : public ros::Msg
00018   {
00019     public:
00020       uint8_t graspable_objects_length;
00021       manipulation_msgs::GraspableObject st_graspable_objects;
00022       manipulation_msgs::GraspableObject * graspable_objects;
00023       sensor_msgs::Image image;
00024       sensor_msgs::CameraInfo camera_info;
00025       uint8_t meshes_length;
00026       shape_msgs::Mesh st_meshes;
00027       shape_msgs::Mesh * meshes;
00028       geometry_msgs::Pose reference_to_camera;
00029 
00030     virtual int serialize(unsigned char *outbuffer) const
00031     {
00032       int offset = 0;
00033       *(outbuffer + offset++) = graspable_objects_length;
00034       *(outbuffer + offset++) = 0;
00035       *(outbuffer + offset++) = 0;
00036       *(outbuffer + offset++) = 0;
00037       for( uint8_t i = 0; i < graspable_objects_length; i++){
00038       offset += this->graspable_objects[i].serialize(outbuffer + offset);
00039       }
00040       offset += this->image.serialize(outbuffer + offset);
00041       offset += this->camera_info.serialize(outbuffer + offset);
00042       *(outbuffer + offset++) = meshes_length;
00043       *(outbuffer + offset++) = 0;
00044       *(outbuffer + offset++) = 0;
00045       *(outbuffer + offset++) = 0;
00046       for( uint8_t i = 0; i < meshes_length; i++){
00047       offset += this->meshes[i].serialize(outbuffer + offset);
00048       }
00049       offset += this->reference_to_camera.serialize(outbuffer + offset);
00050       return offset;
00051     }
00052 
00053     virtual int deserialize(unsigned char *inbuffer)
00054     {
00055       int offset = 0;
00056       uint8_t graspable_objects_lengthT = *(inbuffer + offset++);
00057       if(graspable_objects_lengthT > graspable_objects_length)
00058         this->graspable_objects = (manipulation_msgs::GraspableObject*)realloc(this->graspable_objects, graspable_objects_lengthT * sizeof(manipulation_msgs::GraspableObject));
00059       offset += 3;
00060       graspable_objects_length = graspable_objects_lengthT;
00061       for( uint8_t i = 0; i < graspable_objects_length; i++){
00062       offset += this->st_graspable_objects.deserialize(inbuffer + offset);
00063         memcpy( &(this->graspable_objects[i]), &(this->st_graspable_objects), sizeof(manipulation_msgs::GraspableObject));
00064       }
00065       offset += this->image.deserialize(inbuffer + offset);
00066       offset += this->camera_info.deserialize(inbuffer + offset);
00067       uint8_t meshes_lengthT = *(inbuffer + offset++);
00068       if(meshes_lengthT > meshes_length)
00069         this->meshes = (shape_msgs::Mesh*)realloc(this->meshes, meshes_lengthT * sizeof(shape_msgs::Mesh));
00070       offset += 3;
00071       meshes_length = meshes_lengthT;
00072       for( uint8_t i = 0; i < meshes_length; i++){
00073       offset += this->st_meshes.deserialize(inbuffer + offset);
00074         memcpy( &(this->meshes[i]), &(this->st_meshes), sizeof(shape_msgs::Mesh));
00075       }
00076       offset += this->reference_to_camera.deserialize(inbuffer + offset);
00077      return offset;
00078     }
00079 
00080     const char * getType(){ return "manipulation_msgs/GraspableObjectList"; };
00081     const char * getMD5(){ return "d67571f2982f1b7115de1e0027319109"; };
00082 
00083   };
00084 
00085 }
00086 #endif


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