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