PlaceLocation.h
Go to the documentation of this file.
00001 #ifndef _ROS_manipulation_msgs_PlaceLocation_h
00002 #define _ROS_manipulation_msgs_PlaceLocation_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "sensor_msgs/JointState.h"
00009 #include "geometry_msgs/PoseStamped.h"
00010 #include "manipulation_msgs/GripperTranslation.h"
00011 
00012 namespace manipulation_msgs
00013 {
00014 
00015   class PlaceLocation : public ros::Msg
00016   {
00017     public:
00018       const char* id;
00019       sensor_msgs::JointState post_place_posture;
00020       geometry_msgs::PoseStamped place_pose;
00021       manipulation_msgs::GripperTranslation approach;
00022       manipulation_msgs::GripperTranslation retreat;
00023       uint8_t allowed_touch_objects_length;
00024       char* st_allowed_touch_objects;
00025       char* * allowed_touch_objects;
00026 
00027     virtual int serialize(unsigned char *outbuffer) const
00028     {
00029       int offset = 0;
00030       uint32_t length_id = strlen(this->id);
00031       memcpy(outbuffer + offset, &length_id, sizeof(uint32_t));
00032       offset += 4;
00033       memcpy(outbuffer + offset, this->id, length_id);
00034       offset += length_id;
00035       offset += this->post_place_posture.serialize(outbuffer + offset);
00036       offset += this->place_pose.serialize(outbuffer + offset);
00037       offset += this->approach.serialize(outbuffer + offset);
00038       offset += this->retreat.serialize(outbuffer + offset);
00039       *(outbuffer + offset++) = allowed_touch_objects_length;
00040       *(outbuffer + offset++) = 0;
00041       *(outbuffer + offset++) = 0;
00042       *(outbuffer + offset++) = 0;
00043       for( uint8_t i = 0; i < allowed_touch_objects_length; i++){
00044       uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]);
00045       memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t));
00046       offset += 4;
00047       memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi);
00048       offset += length_allowed_touch_objectsi;
00049       }
00050       return offset;
00051     }
00052 
00053     virtual int deserialize(unsigned char *inbuffer)
00054     {
00055       int offset = 0;
00056       uint32_t length_id;
00057       memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t));
00058       offset += 4;
00059       for(unsigned int k= offset; k< offset+length_id; ++k){
00060           inbuffer[k-1]=inbuffer[k];
00061       }
00062       inbuffer[offset+length_id-1]=0;
00063       this->id = (char *)(inbuffer + offset-1);
00064       offset += length_id;
00065       offset += this->post_place_posture.deserialize(inbuffer + offset);
00066       offset += this->place_pose.deserialize(inbuffer + offset);
00067       offset += this->approach.deserialize(inbuffer + offset);
00068       offset += this->retreat.deserialize(inbuffer + offset);
00069       uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++);
00070       if(allowed_touch_objects_lengthT > allowed_touch_objects_length)
00071         this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*));
00072       offset += 3;
00073       allowed_touch_objects_length = allowed_touch_objects_lengthT;
00074       for( uint8_t i = 0; i < allowed_touch_objects_length; i++){
00075       uint32_t length_st_allowed_touch_objects;
00076       memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t));
00077       offset += 4;
00078       for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){
00079           inbuffer[k-1]=inbuffer[k];
00080       }
00081       inbuffer[offset+length_st_allowed_touch_objects-1]=0;
00082       this->st_allowed_touch_objects = (char *)(inbuffer + offset-1);
00083       offset += length_st_allowed_touch_objects;
00084         memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*));
00085       }
00086      return offset;
00087     }
00088 
00089     const char * getType(){ return "manipulation_msgs/PlaceLocation"; };
00090     const char * getMD5(){ return "0139dab9852add0e64233c5fb3b8a25a"; };
00091 
00092   };
00093 
00094 }
00095 #endif


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