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_std_msgs_Int32MultiArray_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_std_msgs_Int32MultiArray_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 #include "std_msgs/MultiArrayLayout.h"
akashvibhute 0:30537dec6e0b 9
akashvibhute 0:30537dec6e0b 10 namespace std_msgs
akashvibhute 0:30537dec6e0b 11 {
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 class Int32MultiArray : public ros::Msg
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15 public:
akashvibhute 0:30537dec6e0b 16 std_msgs::MultiArrayLayout layout;
akashvibhute 0:30537dec6e0b 17 uint8_t data_length;
akashvibhute 0:30537dec6e0b 18 int32_t st_data;
akashvibhute 0:30537dec6e0b 19 int32_t * data;
akashvibhute 0:30537dec6e0b 20
akashvibhute 0:30537dec6e0b 21 Int32MultiArray():
akashvibhute 0:30537dec6e0b 22 layout(),
akashvibhute 0:30537dec6e0b 23 data_length(0), data(NULL)
akashvibhute 0:30537dec6e0b 24 {
akashvibhute 0:30537dec6e0b 25 }
akashvibhute 0:30537dec6e0b 26
akashvibhute 0:30537dec6e0b 27 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 28 {
akashvibhute 0:30537dec6e0b 29 int offset = 0;
akashvibhute 0:30537dec6e0b 30 offset += this->layout.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 31 *(outbuffer + offset++) = data_length;
akashvibhute 0:30537dec6e0b 32 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 33 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 34 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 35 for( uint8_t i = 0; i < data_length; i++){
akashvibhute 0:30537dec6e0b 36 union {
akashvibhute 0:30537dec6e0b 37 int32_t real;
akashvibhute 0:30537dec6e0b 38 uint32_t base;
akashvibhute 0:30537dec6e0b 39 } u_datai;
akashvibhute 0:30537dec6e0b 40 u_datai.real = this->data[i];
akashvibhute 0:30537dec6e0b 41 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 42 *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 43 *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 44 *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 45 offset += sizeof(this->data[i]);
akashvibhute 0:30537dec6e0b 46 }
akashvibhute 0:30537dec6e0b 47 return offset;
akashvibhute 0:30537dec6e0b 48 }
akashvibhute 0:30537dec6e0b 49
akashvibhute 0:30537dec6e0b 50 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 51 {
akashvibhute 0:30537dec6e0b 52 int offset = 0;
akashvibhute 0:30537dec6e0b 53 offset += this->layout.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 54 uint8_t data_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 55 if(data_lengthT > data_length)
akashvibhute 0:30537dec6e0b 56 this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t));
akashvibhute 0:30537dec6e0b 57 offset += 3;
akashvibhute 0:30537dec6e0b 58 data_length = data_lengthT;
akashvibhute 0:30537dec6e0b 59 for( uint8_t i = 0; i < data_length; i++){
akashvibhute 0:30537dec6e0b 60 union {
akashvibhute 0:30537dec6e0b 61 int32_t real;
akashvibhute 0:30537dec6e0b 62 uint32_t base;
akashvibhute 0:30537dec6e0b 63 } u_st_data;
akashvibhute 0:30537dec6e0b 64 u_st_data.base = 0;
akashvibhute 0:30537dec6e0b 65 u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 66 u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 67 u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 68 u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 69 this->st_data = u_st_data.real;
akashvibhute 0:30537dec6e0b 70 offset += sizeof(this->st_data);
akashvibhute 0:30537dec6e0b 71 memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t));
akashvibhute 0:30537dec6e0b 72 }
akashvibhute 0:30537dec6e0b 73 return offset;
akashvibhute 0:30537dec6e0b 74 }
akashvibhute 0:30537dec6e0b 75
akashvibhute 0:30537dec6e0b 76 const char * getType(){ return "std_msgs/Int32MultiArray"; };
akashvibhute 0:30537dec6e0b 77 const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; };
akashvibhute 0:30537dec6e0b 78
akashvibhute 0:30537dec6e0b 79 };
akashvibhute 0:30537dec6e0b 80
akashvibhute 0:30537dec6e0b 81 }
akashvibhute 0:30537dec6e0b 82 #endif