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_octomap_msgs_Octomap_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_octomap_msgs_Octomap_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/Header.h"
akashvibhute 0:30537dec6e0b 9
akashvibhute 0:30537dec6e0b 10 namespace octomap_msgs
akashvibhute 0:30537dec6e0b 11 {
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 class Octomap : public ros::Msg
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15 public:
akashvibhute 0:30537dec6e0b 16 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 17 bool binary;
akashvibhute 0:30537dec6e0b 18 const char* id;
akashvibhute 0:30537dec6e0b 19 float resolution;
akashvibhute 0:30537dec6e0b 20 uint8_t data_length;
akashvibhute 0:30537dec6e0b 21 int8_t st_data;
akashvibhute 0:30537dec6e0b 22 int8_t * data;
akashvibhute 0:30537dec6e0b 23
akashvibhute 0:30537dec6e0b 24 Octomap():
akashvibhute 0:30537dec6e0b 25 header(),
akashvibhute 0:30537dec6e0b 26 binary(0),
akashvibhute 0:30537dec6e0b 27 id(""),
akashvibhute 0:30537dec6e0b 28 resolution(0),
akashvibhute 0:30537dec6e0b 29 data_length(0), data(NULL)
akashvibhute 0:30537dec6e0b 30 {
akashvibhute 0:30537dec6e0b 31 }
akashvibhute 0:30537dec6e0b 32
akashvibhute 0:30537dec6e0b 33 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 34 {
akashvibhute 0:30537dec6e0b 35 int offset = 0;
akashvibhute 0:30537dec6e0b 36 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 37 union {
akashvibhute 0:30537dec6e0b 38 bool real;
akashvibhute 0:30537dec6e0b 39 uint8_t base;
akashvibhute 0:30537dec6e0b 40 } u_binary;
akashvibhute 0:30537dec6e0b 41 u_binary.real = this->binary;
akashvibhute 0:30537dec6e0b 42 *(outbuffer + offset + 0) = (u_binary.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 43 offset += sizeof(this->binary);
akashvibhute 0:30537dec6e0b 44 uint32_t length_id = strlen(this->id);
akashvibhute 0:30537dec6e0b 45 memcpy(outbuffer + offset, &length_id, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 46 offset += 4;
akashvibhute 0:30537dec6e0b 47 memcpy(outbuffer + offset, this->id, length_id);
akashvibhute 0:30537dec6e0b 48 offset += length_id;
akashvibhute 0:30537dec6e0b 49 offset += serializeAvrFloat64(outbuffer + offset, this->resolution);
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset++) = data_length;
akashvibhute 0:30537dec6e0b 51 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 53 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 54 for( uint8_t i = 0; i < data_length; i++){
akashvibhute 0:30537dec6e0b 55 union {
akashvibhute 0:30537dec6e0b 56 int8_t real;
akashvibhute 0:30537dec6e0b 57 uint8_t base;
akashvibhute 0:30537dec6e0b 58 } u_datai;
akashvibhute 0:30537dec6e0b 59 u_datai.real = this->data[i];
akashvibhute 0:30537dec6e0b 60 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 61 offset += sizeof(this->data[i]);
akashvibhute 0:30537dec6e0b 62 }
akashvibhute 0:30537dec6e0b 63 return offset;
akashvibhute 0:30537dec6e0b 64 }
akashvibhute 0:30537dec6e0b 65
akashvibhute 0:30537dec6e0b 66 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 67 {
akashvibhute 0:30537dec6e0b 68 int offset = 0;
akashvibhute 0:30537dec6e0b 69 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 70 union {
akashvibhute 0:30537dec6e0b 71 bool real;
akashvibhute 0:30537dec6e0b 72 uint8_t base;
akashvibhute 0:30537dec6e0b 73 } u_binary;
akashvibhute 0:30537dec6e0b 74 u_binary.base = 0;
akashvibhute 0:30537dec6e0b 75 u_binary.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 76 this->binary = u_binary.real;
akashvibhute 0:30537dec6e0b 77 offset += sizeof(this->binary);
akashvibhute 0:30537dec6e0b 78 uint32_t length_id;
akashvibhute 0:30537dec6e0b 79 memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 80 offset += 4;
akashvibhute 0:30537dec6e0b 81 for(unsigned int k= offset; k< offset+length_id; ++k){
akashvibhute 0:30537dec6e0b 82 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 83 }
akashvibhute 0:30537dec6e0b 84 inbuffer[offset+length_id-1]=0;
akashvibhute 0:30537dec6e0b 85 this->id = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 86 offset += length_id;
akashvibhute 0:30537dec6e0b 87 offset += deserializeAvrFloat64(inbuffer + offset, &(this->resolution));
akashvibhute 0:30537dec6e0b 88 uint8_t data_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 89 if(data_lengthT > data_length)
akashvibhute 0:30537dec6e0b 90 this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
akashvibhute 0:30537dec6e0b 91 offset += 3;
akashvibhute 0:30537dec6e0b 92 data_length = data_lengthT;
akashvibhute 0:30537dec6e0b 93 for( uint8_t i = 0; i < data_length; i++){
akashvibhute 0:30537dec6e0b 94 union {
akashvibhute 0:30537dec6e0b 95 int8_t real;
akashvibhute 0:30537dec6e0b 96 uint8_t base;
akashvibhute 0:30537dec6e0b 97 } u_st_data;
akashvibhute 0:30537dec6e0b 98 u_st_data.base = 0;
akashvibhute 0:30537dec6e0b 99 u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 100 this->st_data = u_st_data.real;
akashvibhute 0:30537dec6e0b 101 offset += sizeof(this->st_data);
akashvibhute 0:30537dec6e0b 102 memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
akashvibhute 0:30537dec6e0b 103 }
akashvibhute 0:30537dec6e0b 104 return offset;
akashvibhute 0:30537dec6e0b 105 }
akashvibhute 0:30537dec6e0b 106
akashvibhute 0:30537dec6e0b 107 const char * getType(){ return "octomap_msgs/Octomap"; };
akashvibhute 0:30537dec6e0b 108 const char * getMD5(){ return "9a45536b45c5e409cd49f04bb2d9999f"; };
akashvibhute 0:30537dec6e0b 109
akashvibhute 0:30537dec6e0b 110 };
akashvibhute 0:30537dec6e0b 111
akashvibhute 0:30537dec6e0b 112 }
akashvibhute 0:30537dec6e0b 113 #endif