rosserial for Hydro
Fork of rosserial_mbed_lib by
Diff: sensor_msgs/CompressedImage.h
- Revision:
- 3:1cf99502f396
- Parent:
- 0:77afd7560544
--- a/sensor_msgs/CompressedImage.h Sun Oct 16 09:35:11 2011 +0000 +++ b/sensor_msgs/CompressedImage.h Sat Nov 12 23:54:45 2011 +0000 @@ -1,10 +1,10 @@ -#ifndef ros_CompressedImage_h -#define ros_CompressedImage_h +#ifndef _ROS_sensor_msgs_CompressedImage_h +#define _ROS_sensor_msgs_CompressedImage_h #include <stdint.h> #include <string.h> #include <stdlib.h> -#include "../ros/msg.h" +#include "ros/msg.h" #include "std_msgs/Header.h" namespace sensor_msgs @@ -15,15 +15,15 @@ public: std_msgs::Header header; char * format; - unsigned char data_length; - unsigned char st_data; - unsigned char * data; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; - virtual int serialize(unsigned char *outbuffer) + virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); - long * length_format = (long *)(outbuffer + offset); + uint32_t * length_format = (uint32_t *)(outbuffer + offset); *length_format = strlen( (const char*) this->format); offset += 4; memcpy(outbuffer + offset, this->format, *length_format); @@ -32,13 +32,8 @@ *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; - for( unsigned char i = 0; i < data_length; i++){ - union { - unsigned char real; - unsigned char base; - } u_datai; - u_datai.real = this->data[i]; - *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; offset += sizeof(this->data[i]); } return offset; @@ -52,30 +47,25 @@ offset += 4; for(unsigned int k= offset; k< offset+length_format; ++k){ inbuffer[k-1]=inbuffer[k]; - } + } inbuffer[offset+length_format-1]=0; this->format = (char *)(inbuffer + offset-1); offset += length_format; - unsigned char data_lengthT = *(inbuffer + offset++); + uint8_t data_lengthT = *(inbuffer + offset++); if(data_lengthT > data_length) - this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char)); + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); offset += 3; data_length = data_lengthT; - for( unsigned char i = 0; i < data_length; i++){ - union { - unsigned char real; - unsigned char base; - } u_st_data; - u_st_data.base = 0; - u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0); - this->st_data = u_st_data.real; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); offset += sizeof(this->st_data); - memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char)); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); } return offset; } - virtual const char * getType(){ return "sensor_msgs/CompressedImage"; }; + virtual const char * getType(){ return "sensor_msgs/CompressedImage"; }; + virtual const char * getMD5(){ return "8f7a12909da2c9d3332d540a0977563f"; }; };