modify for Hydro version
Fork of rosserial_mbed_lib by
Diff: sensor_msgs/CameraInfo.h
- Revision:
- 3:1cf99502f396
- Parent:
- 0:77afd7560544
diff -r bb6bb835fde4 -r 1cf99502f396 sensor_msgs/CameraInfo.h --- a/sensor_msgs/CameraInfo.h Sun Oct 16 09:35:11 2011 +0000 +++ b/sensor_msgs/CameraInfo.h Sat Nov 12 23:54:45 2011 +0000 @@ -1,10 +1,10 @@ -#ifndef ros_CameraInfo_h -#define ros_CameraInfo_h +#ifndef _ROS_sensor_msgs_CameraInfo_h +#define _ROS_sensor_msgs_CameraInfo_h #include <stdint.h> #include <string.h> #include <stdlib.h> -#include "../ros/msg.h" +#include "ros/msg.h" #include "std_msgs/Header.h" #include "sensor_msgs/RegionOfInterest.h" @@ -15,44 +15,34 @@ { public: std_msgs::Header header; - unsigned long height; - unsigned long width; + uint32_t height; + uint32_t width; char * distortion_model; - unsigned char D_length; + uint8_t D_length; float st_D; float * D; float K[9]; float R[9]; float P[12]; - unsigned long binning_x; - unsigned long binning_y; + uint32_t binning_x; + uint32_t binning_y; sensor_msgs::RegionOfInterest roi; - virtual int serialize(unsigned char *outbuffer) + virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); - union { - unsigned long real; - unsigned long base; - } u_height; - u_height.real = this->height; - *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF; - *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF; - *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; offset += sizeof(this->height); - union { - unsigned long real; - unsigned long base; - } u_width; - u_width.real = this->width; - *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF; - *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF; - *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; offset += sizeof(this->width); - long * length_distortion_model = (long *)(outbuffer + offset); + uint32_t * length_distortion_model = (uint32_t *)(outbuffer + offset); *length_distortion_model = strlen( (const char*) this->distortion_model); offset += 4; memcpy(outbuffer + offset, this->distortion_model, *length_distortion_model); @@ -61,12 +51,12 @@ *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; - for( unsigned char i = 0; i < D_length; i++){ - long * val_Di = (long *) &(this->D[i]); - long exp_Di = (((*val_Di)>>23)&255); + for( uint8_t i = 0; i < D_length; i++){ + int32_t * val_Di = (long *) &(this->D[i]); + int32_t exp_Di = (((*val_Di)>>23)&255); if(exp_Di != 0) exp_Di += 1023-127; - long sig_Di = *val_Di; + int32_t sig_Di = *val_Di; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -78,12 +68,12 @@ if(this->D[i] < 0) *(outbuffer + offset -1) |= 0x80; } unsigned char * K_val = (unsigned char *) this->K; - for( unsigned char i = 0; i < 9; i++){ - long * val_Ki = (long *) &(this->K[i]); - long exp_Ki = (((*val_Ki)>>23)&255); + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_Ki = (long *) &(this->K[i]); + int32_t exp_Ki = (((*val_Ki)>>23)&255); if(exp_Ki != 0) exp_Ki += 1023-127; - long sig_Ki = *val_Ki; + int32_t sig_Ki = *val_Ki; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -95,12 +85,12 @@ if(this->K[i] < 0) *(outbuffer + offset -1) |= 0x80; } unsigned char * R_val = (unsigned char *) this->R; - for( unsigned char i = 0; i < 9; i++){ - long * val_Ri = (long *) &(this->R[i]); - long exp_Ri = (((*val_Ri)>>23)&255); + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_Ri = (long *) &(this->R[i]); + int32_t exp_Ri = (((*val_Ri)>>23)&255); if(exp_Ri != 0) exp_Ri += 1023-127; - long sig_Ri = *val_Ri; + int32_t sig_Ri = *val_Ri; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -112,12 +102,12 @@ if(this->R[i] < 0) *(outbuffer + offset -1) |= 0x80; } unsigned char * P_val = (unsigned char *) this->P; - for( unsigned char i = 0; i < 12; i++){ - long * val_Pi = (long *) &(this->P[i]); - long exp_Pi = (((*val_Pi)>>23)&255); + for( uint8_t i = 0; i < 12; i++){ + int32_t * val_Pi = (long *) &(this->P[i]); + int32_t exp_Pi = (((*val_Pi)>>23)&255); if(exp_Pi != 0) exp_Pi += 1023-127; - long sig_Pi = *val_Pi; + int32_t sig_Pi = *val_Pi; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -128,25 +118,15 @@ *(outbuffer + offset++) = (exp_Pi>>4) & 0x7F; if(this->P[i] < 0) *(outbuffer + offset -1) |= 0x80; } - union { - unsigned long real; - unsigned long base; - } u_binning_x; - u_binning_x.real = this->binning_x; - *(outbuffer + offset + 0) = (u_binning_x.base >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (u_binning_x.base >> (8 * 1)) & 0xFF; - *(outbuffer + offset + 2) = (u_binning_x.base >> (8 * 2)) & 0xFF; - *(outbuffer + offset + 3) = (u_binning_x.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF; offset += sizeof(this->binning_x); - union { - unsigned long real; - unsigned long base; - } u_binning_y; - u_binning_y.real = this->binning_y; - *(outbuffer + offset + 0) = (u_binning_y.base >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (u_binning_y.base >> (8 * 1)) & 0xFF; - *(outbuffer + offset + 2) = (u_binning_y.base >> (8 * 2)) & 0xFF; - *(outbuffer + offset + 3) = (u_binning_y.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF; offset += sizeof(this->binning_y); offset += this->roi.serialize(outbuffer + offset); return offset; @@ -156,124 +136,101 @@ { int offset = 0; offset += this->header.deserialize(inbuffer + offset); - union { - unsigned long real; - unsigned long base; - } u_height; - u_height.base = 0; - u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0); - u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1); - u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2); - u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3); - this->height = u_height.real; + this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->height); - union { - unsigned long real; - unsigned long base; - } u_width; - u_width.base = 0; - u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0); - u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1); - u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2); - u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3); - this->width = u_width.real; + this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->width); uint32_t length_distortion_model = *(uint32_t *)(inbuffer + offset); offset += 4; for(unsigned int k= offset; k< offset+length_distortion_model; ++k){ inbuffer[k-1]=inbuffer[k]; - } + } inbuffer[offset+length_distortion_model-1]=0; this->distortion_model = (char *)(inbuffer + offset-1); offset += length_distortion_model; - unsigned char D_lengthT = *(inbuffer + offset++); + uint8_t D_lengthT = *(inbuffer + offset++); if(D_lengthT > D_length) this->D = (float*)realloc(this->D, D_lengthT * sizeof(float)); offset += 3; D_length = D_lengthT; - for( unsigned char i = 0; i < D_length; i++){ - unsigned long * val_st_D = (unsigned long*) &(this->st_D); + for( uint8_t i = 0; i < D_length; i++){ + uint32_t * val_st_D = (uint32_t*) &(this->st_D); offset += 3; - *val_st_D = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_st_D = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_st_D = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_D = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_st_D !=0) *val_st_D |= ((exp_st_D)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_D = -this->st_D; memcpy( &(this->D[i]), &(this->st_D), sizeof(float)); } - unsigned char * K_val = (unsigned char *) this->K; - for( unsigned char i = 0; i < 9; i++){ - unsigned long * val_Ki = (unsigned long*) &(this->K[i]); + uint8_t * K_val = (uint8_t*) this->K; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_Ki = (uint32_t*) &(this->K[i]); offset += 3; - *val_Ki = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_Ki = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_Ki = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_Ki = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_Ki !=0) *val_Ki |= ((exp_Ki)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->K[i] = -this->K[i]; } - unsigned char * R_val = (unsigned char *) this->R; - for( unsigned char i = 0; i < 9; i++){ - unsigned long * val_Ri = (unsigned long*) &(this->R[i]); + uint8_t * R_val = (uint8_t*) this->R; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_Ri = (uint32_t*) &(this->R[i]); offset += 3; - *val_Ri = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_Ri = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_Ri = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_Ri = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_Ri !=0) *val_Ri |= ((exp_Ri)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->R[i] = -this->R[i]; } - unsigned char * P_val = (unsigned char *) this->P; - for( unsigned char i = 0; i < 12; i++){ - unsigned long * val_Pi = (unsigned long*) &(this->P[i]); + uint8_t * P_val = (uint8_t*) this->P; + for( uint8_t i = 0; i < 12; i++){ + uint32_t * val_Pi = (uint32_t*) &(this->P[i]); offset += 3; - *val_Pi = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_Pi = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_Pi = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_Pi = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_Pi !=0) *val_Pi |= ((exp_Pi)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->P[i] = -this->P[i]; } - union { - unsigned long real; - unsigned long base; - } u_binning_x; - u_binning_x.base = 0; - u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 0))) << (8 * 0); - u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 1))) << (8 * 1); - u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 2))) << (8 * 2); - u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 3))) << (8 * 3); - this->binning_x = u_binning_x.real; + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->binning_x); - union { - unsigned long real; - unsigned long base; - } u_binning_y; - u_binning_y.base = 0; - u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 0))) << (8 * 0); - u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 1))) << (8 * 1); - u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 2))) << (8 * 2); - u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 3))) << (8 * 3); - this->binning_y = u_binning_y.real; + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->binning_y); offset += this->roi.deserialize(inbuffer + offset); return offset; } - virtual const char * getType(){ return "sensor_msgs/CameraInfo"; }; + virtual const char * getType(){ return "sensor_msgs/CameraInfo"; }; + virtual const char * getMD5(){ return "c9a58c1b0b154e0e6da7578cb991d214"; }; };