modify for Hydro version

Dependencies:   MODSERIAL

Fork of rosserial_mbed_lib by nucho

Committer:
jjzak
Date:
Sat Oct 26 15:39:01 2013 +0000
Revision:
6:3c54bc7badd4
modify for Hydro version;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
jjzak 6:3c54bc7badd4 1 #ifndef _ROS_sensor_msgs_ChannelFloat32_h
jjzak 6:3c54bc7badd4 2 #define _ROS_sensor_msgs_ChannelFloat32_h
jjzak 6:3c54bc7badd4 3
jjzak 6:3c54bc7badd4 4 #include <stdint.h>
jjzak 6:3c54bc7badd4 5 #include <string.h>
jjzak 6:3c54bc7badd4 6 #include <stdlib.h>
jjzak 6:3c54bc7badd4 7 #include "ros/msg.h"
jjzak 6:3c54bc7badd4 8
jjzak 6:3c54bc7badd4 9 namespace sensor_msgs
jjzak 6:3c54bc7badd4 10 {
jjzak 6:3c54bc7badd4 11
jjzak 6:3c54bc7badd4 12 class ChannelFloat32 : public ros::Msg
jjzak 6:3c54bc7badd4 13 {
jjzak 6:3c54bc7badd4 14 public:
jjzak 6:3c54bc7badd4 15 char * name;
jjzak 6:3c54bc7badd4 16 uint8_t values_length;
jjzak 6:3c54bc7badd4 17 float st_values;
jjzak 6:3c54bc7badd4 18 float * values;
jjzak 6:3c54bc7badd4 19
jjzak 6:3c54bc7badd4 20 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 21 {
jjzak 6:3c54bc7badd4 22 int offset = 0;
jjzak 6:3c54bc7badd4 23 uint32_t length_name = strlen( (const char*) this->name);
jjzak 6:3c54bc7badd4 24 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
jjzak 6:3c54bc7badd4 25 offset += 4;
jjzak 6:3c54bc7badd4 26 memcpy(outbuffer + offset, this->name, length_name);
jjzak 6:3c54bc7badd4 27 offset += length_name;
jjzak 6:3c54bc7badd4 28 *(outbuffer + offset++) = values_length;
jjzak 6:3c54bc7badd4 29 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 30 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 31 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 32 for( uint8_t i = 0; i < values_length; i++){
jjzak 6:3c54bc7badd4 33 union {
jjzak 6:3c54bc7badd4 34 float real;
jjzak 6:3c54bc7badd4 35 uint32_t base;
jjzak 6:3c54bc7badd4 36 } u_valuesi;
jjzak 6:3c54bc7badd4 37 u_valuesi.real = this->values[i];
jjzak 6:3c54bc7badd4 38 *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 39 *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF;
jjzak 6:3c54bc7badd4 40 *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF;
jjzak 6:3c54bc7badd4 41 *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF;
jjzak 6:3c54bc7badd4 42 offset += sizeof(this->values[i]);
jjzak 6:3c54bc7badd4 43 }
jjzak 6:3c54bc7badd4 44 return offset;
jjzak 6:3c54bc7badd4 45 }
jjzak 6:3c54bc7badd4 46
jjzak 6:3c54bc7badd4 47 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 48 {
jjzak 6:3c54bc7badd4 49 int offset = 0;
jjzak 6:3c54bc7badd4 50 uint32_t length_name;
jjzak 6:3c54bc7badd4 51 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
jjzak 6:3c54bc7badd4 52 offset += 4;
jjzak 6:3c54bc7badd4 53 for(unsigned int k= offset; k< offset+length_name; ++k){
jjzak 6:3c54bc7badd4 54 inbuffer[k-1]=inbuffer[k];
jjzak 6:3c54bc7badd4 55 }
jjzak 6:3c54bc7badd4 56 inbuffer[offset+length_name-1]=0;
jjzak 6:3c54bc7badd4 57 this->name = (char *)(inbuffer + offset-1);
jjzak 6:3c54bc7badd4 58 offset += length_name;
jjzak 6:3c54bc7badd4 59 uint8_t values_lengthT = *(inbuffer + offset++);
jjzak 6:3c54bc7badd4 60 if(values_lengthT > values_length)
jjzak 6:3c54bc7badd4 61 this->values = (float*)realloc(this->values, values_lengthT * sizeof(float));
jjzak 6:3c54bc7badd4 62 offset += 3;
jjzak 6:3c54bc7badd4 63 values_length = values_lengthT;
jjzak 6:3c54bc7badd4 64 for( uint8_t i = 0; i < values_length; i++){
jjzak 6:3c54bc7badd4 65 union {
jjzak 6:3c54bc7badd4 66 float real;
jjzak 6:3c54bc7badd4 67 uint32_t base;
jjzak 6:3c54bc7badd4 68 } u_st_values;
jjzak 6:3c54bc7badd4 69 u_st_values.base = 0;
jjzak 6:3c54bc7badd4 70 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
jjzak 6:3c54bc7badd4 71 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
jjzak 6:3c54bc7badd4 72 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
jjzak 6:3c54bc7badd4 73 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
jjzak 6:3c54bc7badd4 74 this->st_values = u_st_values.real;
jjzak 6:3c54bc7badd4 75 offset += sizeof(this->st_values);
jjzak 6:3c54bc7badd4 76 memcpy( &(this->values[i]), &(this->st_values), sizeof(float));
jjzak 6:3c54bc7badd4 77 }
jjzak 6:3c54bc7badd4 78 return offset;
jjzak 6:3c54bc7badd4 79 }
jjzak 6:3c54bc7badd4 80
jjzak 6:3c54bc7badd4 81 const char * getType(){ return "sensor_msgs/ChannelFloat32"; };
jjzak 6:3c54bc7badd4 82 const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; };
jjzak 6:3c54bc7badd4 83
jjzak 6:3c54bc7badd4 84 };
jjzak 6:3c54bc7badd4 85
jjzak 6:3c54bc7badd4 86 }
jjzak 6:3c54bc7badd4 87 #endif