Gary Servin / ros_lib_indigo

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 UInt32MultiArray.h Source File

UInt32MultiArray.h

00001 #ifndef _ROS_std_msgs_UInt32MultiArray_h
00002 #define _ROS_std_msgs_UInt32MultiArray_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/MultiArrayLayout.h"
00009 
00010 namespace std_msgs
00011 {
00012 
00013   class UInt32MultiArray : public ros::Msg
00014   {
00015     public:
00016       std_msgs::MultiArrayLayout layout;
00017       uint8_t data_length;
00018       uint32_t st_data;
00019       uint32_t * data;
00020 
00021     UInt32MultiArray():
00022       layout(),
00023       data_length(0), data(NULL)
00024     {
00025     }
00026 
00027     virtual int serialize(unsigned char *outbuffer) const
00028     {
00029       int offset = 0;
00030       offset += this->layout.serialize(outbuffer + offset);
00031       *(outbuffer + offset++) = data_length;
00032       *(outbuffer + offset++) = 0;
00033       *(outbuffer + offset++) = 0;
00034       *(outbuffer + offset++) = 0;
00035       for( uint8_t i = 0; i < data_length; i++){
00036       *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
00037       *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF;
00038       *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF;
00039       *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF;
00040       offset += sizeof(this->data[i]);
00041       }
00042       return offset;
00043     }
00044 
00045     virtual int deserialize(unsigned char *inbuffer)
00046     {
00047       int offset = 0;
00048       offset += this->layout.deserialize(inbuffer + offset);
00049       uint8_t data_lengthT = *(inbuffer + offset++);
00050       if(data_lengthT > data_length)
00051         this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t));
00052       offset += 3;
00053       data_length = data_lengthT;
00054       for( uint8_t i = 0; i < data_length; i++){
00055       this->st_data =  ((uint32_t) (*(inbuffer + offset)));
00056       this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00057       this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00058       this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00059       offset += sizeof(this->st_data);
00060         memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t));
00061       }
00062      return offset;
00063     }
00064 
00065     const char * getType(){ return "std_msgs/UInt32MultiArray"; };
00066     const char * getMD5(){ return "4d6a180abc9be191b96a7eda6c8a233d"; };
00067 
00068   };
00069 
00070 }
00071 #endif