Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers WorldState.h Source File

WorldState.h

00001 #ifndef _ROS_gazebo_msgs_WorldState_h
00002 #define _ROS_gazebo_msgs_WorldState_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 "geometry_msgs/Pose.h"
00010 #include "geometry_msgs/Twist.h"
00011 #include "geometry_msgs/Wrench.h"
00012 
00013 namespace gazebo_msgs
00014 {
00015 
00016   class WorldState : public ros::Msg
00017   {
00018     public:
00019       typedef std_msgs::Header _header_type;
00020       _header_type header;
00021       uint32_t name_length;
00022       typedef char* _name_type;
00023       _name_type st_name;
00024       _name_type * name;
00025       uint32_t pose_length;
00026       typedef geometry_msgs::Pose _pose_type;
00027       _pose_type st_pose;
00028       _pose_type * pose;
00029       uint32_t twist_length;
00030       typedef geometry_msgs::Twist _twist_type;
00031       _twist_type st_twist;
00032       _twist_type * twist;
00033       uint32_t wrench_length;
00034       typedef geometry_msgs::Wrench _wrench_type;
00035       _wrench_type st_wrench;
00036       _wrench_type * wrench;
00037 
00038     WorldState():
00039       header(),
00040       name_length(0), name(NULL),
00041       pose_length(0), pose(NULL),
00042       twist_length(0), twist(NULL),
00043       wrench_length(0), wrench(NULL)
00044     {
00045     }
00046 
00047     virtual int serialize(unsigned char *outbuffer) const
00048     {
00049       int offset = 0;
00050       offset += this->header.serialize(outbuffer + offset);
00051       *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF;
00052       *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
00053       *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
00054       *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
00055       offset += sizeof(this->name_length);
00056       for( uint32_t i = 0; i < name_length; i++){
00057       uint32_t length_namei = strlen(this->name[i]);
00058       varToArr(outbuffer + offset, length_namei);
00059       offset += 4;
00060       memcpy(outbuffer + offset, this->name[i], length_namei);
00061       offset += length_namei;
00062       }
00063       *(outbuffer + offset + 0) = (this->pose_length >> (8 * 0)) & 0xFF;
00064       *(outbuffer + offset + 1) = (this->pose_length >> (8 * 1)) & 0xFF;
00065       *(outbuffer + offset + 2) = (this->pose_length >> (8 * 2)) & 0xFF;
00066       *(outbuffer + offset + 3) = (this->pose_length >> (8 * 3)) & 0xFF;
00067       offset += sizeof(this->pose_length);
00068       for( uint32_t i = 0; i < pose_length; i++){
00069       offset += this->pose[i].serialize(outbuffer + offset);
00070       }
00071       *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF;
00072       *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF;
00073       *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF;
00074       *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF;
00075       offset += sizeof(this->twist_length);
00076       for( uint32_t i = 0; i < twist_length; i++){
00077       offset += this->twist[i].serialize(outbuffer + offset);
00078       }
00079       *(outbuffer + offset + 0) = (this->wrench_length >> (8 * 0)) & 0xFF;
00080       *(outbuffer + offset + 1) = (this->wrench_length >> (8 * 1)) & 0xFF;
00081       *(outbuffer + offset + 2) = (this->wrench_length >> (8 * 2)) & 0xFF;
00082       *(outbuffer + offset + 3) = (this->wrench_length >> (8 * 3)) & 0xFF;
00083       offset += sizeof(this->wrench_length);
00084       for( uint32_t i = 0; i < wrench_length; i++){
00085       offset += this->wrench[i].serialize(outbuffer + offset);
00086       }
00087       return offset;
00088     }
00089 
00090     virtual int deserialize(unsigned char *inbuffer)
00091     {
00092       int offset = 0;
00093       offset += this->header.deserialize(inbuffer + offset);
00094       uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 
00095       name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
00096       name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
00097       name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
00098       offset += sizeof(this->name_length);
00099       if(name_lengthT > name_length)
00100         this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
00101       name_length = name_lengthT;
00102       for( uint32_t i = 0; i < name_length; i++){
00103       uint32_t length_st_name;
00104       arrToVar(length_st_name, (inbuffer + offset));
00105       offset += 4;
00106       for(unsigned int k= offset; k< offset+length_st_name; ++k){
00107           inbuffer[k-1]=inbuffer[k];
00108       }
00109       inbuffer[offset+length_st_name-1]=0;
00110       this->st_name = (char *)(inbuffer + offset-1);
00111       offset += length_st_name;
00112         memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
00113       }
00114       uint32_t pose_lengthT = ((uint32_t) (*(inbuffer + offset))); 
00115       pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
00116       pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
00117       pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
00118       offset += sizeof(this->pose_length);
00119       if(pose_lengthT > pose_length)
00120         this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
00121       pose_length = pose_lengthT;
00122       for( uint32_t i = 0; i < pose_length; i++){
00123       offset += this->st_pose.deserialize(inbuffer + offset);
00124         memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
00125       }
00126       uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); 
00127       twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
00128       twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
00129       twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
00130       offset += sizeof(this->twist_length);
00131       if(twist_lengthT > twist_length)
00132         this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
00133       twist_length = twist_lengthT;
00134       for( uint32_t i = 0; i < twist_length; i++){
00135       offset += this->st_twist.deserialize(inbuffer + offset);
00136         memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
00137       }
00138       uint32_t wrench_lengthT = ((uint32_t) (*(inbuffer + offset))); 
00139       wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
00140       wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
00141       wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
00142       offset += sizeof(this->wrench_length);
00143       if(wrench_lengthT > wrench_length)
00144         this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench));
00145       wrench_length = wrench_lengthT;
00146       for( uint32_t i = 0; i < wrench_length; i++){
00147       offset += this->st_wrench.deserialize(inbuffer + offset);
00148         memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench));
00149       }
00150      return offset;
00151     }
00152 
00153     const char * getType(){ return "gazebo_msgs/WorldState"; };
00154     const char * getMD5(){ return "de1a9de3ab7ba97ac0e9ec01a4eb481e"; };
00155 
00156   };
00157 
00158 }
00159 #endif