ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers ModelStates.h Source File

ModelStates.h

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     ModelStates():
00028       name_length(0), name(NULL),
00029       pose_length(0), pose(NULL),
00030       twist_length(0), twist(NULL)
00031     {
00032     }
00033 
00034     virtual int serialize(unsigned char *outbuffer) const
00035     {
00036       int offset = 0;
00037       *(outbuffer + offset++) = name_length;
00038       *(outbuffer + offset++) = 0;
00039       *(outbuffer + offset++) = 0;
00040       *(outbuffer + offset++) = 0;
00041       for( uint8_t i = 0; i < name_length; i++){
00042       uint32_t length_namei = strlen(this->name[i]);
00043       memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
00044       offset += 4;
00045       memcpy(outbuffer + offset, this->name[i], length_namei);
00046       offset += length_namei;
00047       }
00048       *(outbuffer + offset++) = pose_length;
00049       *(outbuffer + offset++) = 0;
00050       *(outbuffer + offset++) = 0;
00051       *(outbuffer + offset++) = 0;
00052       for( uint8_t i = 0; i < pose_length; i++){
00053       offset += this->pose[i].serialize(outbuffer + offset);
00054       }
00055       *(outbuffer + offset++) = twist_length;
00056       *(outbuffer + offset++) = 0;
00057       *(outbuffer + offset++) = 0;
00058       *(outbuffer + offset++) = 0;
00059       for( uint8_t i = 0; i < twist_length; i++){
00060       offset += this->twist[i].serialize(outbuffer + offset);
00061       }
00062       return offset;
00063     }
00064 
00065     virtual int deserialize(unsigned char *inbuffer)
00066     {
00067       int offset = 0;
00068       uint8_t name_lengthT = *(inbuffer + offset++);
00069       if(name_lengthT > name_length)
00070         this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
00071       offset += 3;
00072       name_length = name_lengthT;
00073       for( uint8_t i = 0; i < name_length; i++){
00074       uint32_t length_st_name;
00075       memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
00076       offset += 4;
00077       for(unsigned int k= offset; k< offset+length_st_name; ++k){
00078           inbuffer[k-1]=inbuffer[k];
00079       }
00080       inbuffer[offset+length_st_name-1]=0;
00081       this->st_name = (char *)(inbuffer + offset-1);
00082       offset += length_st_name;
00083         memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
00084       }
00085       uint8_t pose_lengthT = *(inbuffer + offset++);
00086       if(pose_lengthT > pose_length)
00087         this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
00088       offset += 3;
00089       pose_length = pose_lengthT;
00090       for( uint8_t i = 0; i < pose_length; i++){
00091       offset += this->st_pose.deserialize(inbuffer + offset);
00092         memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
00093       }
00094       uint8_t twist_lengthT = *(inbuffer + offset++);
00095       if(twist_lengthT > twist_length)
00096         this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
00097       offset += 3;
00098       twist_length = twist_lengthT;
00099       for( uint8_t i = 0; i < twist_length; i++){
00100       offset += this->st_twist.deserialize(inbuffer + offset);
00101         memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
00102       }
00103      return offset;
00104     }
00105 
00106     const char * getType(){ return "gazebo_msgs/ModelStates"; };
00107     const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; };
00108 
00109   };
00110 
00111 }
00112 #endif