Go to the documentation of this file.00001 #ifndef _ROS_gazebo_msgs_ModelStates_h
00002 #define _ROS_gazebo_msgs_ModelStates_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "geometry_msgs/Pose.h"
00009 #include "geometry_msgs/Twist.h"
00010
00011 namespace gazebo_msgs
00012 {
00013
00014 class ModelStates : public ros::Msg
00015 {
00016 public:
00017 uint8_t name_length;
00018 char* st_name;
00019 char* * name;
00020 uint8_t pose_length;
00021 geometry_msgs::Pose st_pose;
00022 geometry_msgs::Pose * pose;
00023 uint8_t twist_length;
00024 geometry_msgs::Twist st_twist;
00025 geometry_msgs::Twist * twist;
00026
00027 virtual int serialize(unsigned char *outbuffer) const
00028 {
00029 int offset = 0;
00030 *(outbuffer + offset++) = name_length;
00031 *(outbuffer + offset++) = 0;
00032 *(outbuffer + offset++) = 0;
00033 *(outbuffer + offset++) = 0;
00034 for( uint8_t i = 0; i < name_length; i++){
00035 uint32_t length_namei = strlen( (const char*) this->name[i]);
00036 memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
00037 offset += 4;
00038 memcpy(outbuffer + offset, this->name[i], length_namei);
00039 offset += length_namei;
00040 }
00041 *(outbuffer + offset++) = pose_length;
00042 *(outbuffer + offset++) = 0;
00043 *(outbuffer + offset++) = 0;
00044 *(outbuffer + offset++) = 0;
00045 for( uint8_t i = 0; i < pose_length; i++){
00046 offset += this->pose[i].serialize(outbuffer + offset);
00047 }
00048 *(outbuffer + offset++) = twist_length;
00049 *(outbuffer + offset++) = 0;
00050 *(outbuffer + offset++) = 0;
00051 *(outbuffer + offset++) = 0;
00052 for( uint8_t i = 0; i < twist_length; i++){
00053 offset += this->twist[i].serialize(outbuffer + offset);
00054 }
00055 return offset;
00056 }
00057
00058 virtual int deserialize(unsigned char *inbuffer)
00059 {
00060 int offset = 0;
00061 uint8_t name_lengthT = *(inbuffer + offset++);
00062 if(name_lengthT > name_length)
00063 this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
00064 offset += 3;
00065 name_length = name_lengthT;
00066 for( uint8_t i = 0; i < name_length; i++){
00067 uint32_t length_st_name;
00068 memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
00069 offset += 4;
00070 for(unsigned int k= offset; k< offset+length_st_name; ++k){
00071 inbuffer[k-1]=inbuffer[k];
00072 }
00073 inbuffer[offset+length_st_name-1]=0;
00074 this->st_name = (char *)(inbuffer + offset-1);
00075 offset += length_st_name;
00076 memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
00077 }
00078 uint8_t pose_lengthT = *(inbuffer + offset++);
00079 if(pose_lengthT > pose_length)
00080 this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
00081 offset += 3;
00082 pose_length = pose_lengthT;
00083 for( uint8_t i = 0; i < pose_length; i++){
00084 offset += this->st_pose.deserialize(inbuffer + offset);
00085 memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
00086 }
00087 uint8_t twist_lengthT = *(inbuffer + offset++);
00088 if(twist_lengthT > twist_length)
00089 this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
00090 offset += 3;
00091 twist_length = twist_lengthT;
00092 for( uint8_t i = 0; i < twist_length; i++){
00093 offset += this->st_twist.deserialize(inbuffer + offset);
00094 memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
00095 }
00096 return offset;
00097 }
00098
00099 const char * getType(){ return "gazebo_msgs/ModelStates"; };
00100 const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; };
00101
00102 };
00103
00104 }
00105 #endif