rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

Committer:
akashvibhute
Date:
Sun Feb 15 10:53:43 2015 +0000
Revision:
0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.

Who changed what in which revision?

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