rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
map_msgs/OccupancyGridUpdate.h@0:30537dec6e0b, 2015-02-15 (annotated)
- 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?
User | Revision | Line number | New contents of line |
---|---|---|---|
akashvibhute | 0:30537dec6e0b | 1 | #ifndef _ROS_map_msgs_OccupancyGridUpdate_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_map_msgs_OccupancyGridUpdate_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 map_msgs |
akashvibhute | 0:30537dec6e0b | 11 | { |
akashvibhute | 0:30537dec6e0b | 12 | |
akashvibhute | 0:30537dec6e0b | 13 | class OccupancyGridUpdate : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 14 | { |
akashvibhute | 0:30537dec6e0b | 15 | public: |
akashvibhute | 0:30537dec6e0b | 16 | std_msgs::Header header; |
akashvibhute | 0:30537dec6e0b | 17 | int32_t x; |
akashvibhute | 0:30537dec6e0b | 18 | int32_t y; |
akashvibhute | 0:30537dec6e0b | 19 | uint32_t width; |
akashvibhute | 0:30537dec6e0b | 20 | uint32_t height; |
akashvibhute | 0:30537dec6e0b | 21 | uint8_t data_length; |
akashvibhute | 0:30537dec6e0b | 22 | int8_t st_data; |
akashvibhute | 0:30537dec6e0b | 23 | int8_t * data; |
akashvibhute | 0:30537dec6e0b | 24 | |
akashvibhute | 0:30537dec6e0b | 25 | OccupancyGridUpdate(): |
akashvibhute | 0:30537dec6e0b | 26 | header(), |
akashvibhute | 0:30537dec6e0b | 27 | x(0), |
akashvibhute | 0:30537dec6e0b | 28 | y(0), |
akashvibhute | 0:30537dec6e0b | 29 | width(0), |
akashvibhute | 0:30537dec6e0b | 30 | height(0), |
akashvibhute | 0:30537dec6e0b | 31 | data_length(0), data(NULL) |
akashvibhute | 0:30537dec6e0b | 32 | { |
akashvibhute | 0:30537dec6e0b | 33 | } |
akashvibhute | 0:30537dec6e0b | 34 | |
akashvibhute | 0:30537dec6e0b | 35 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 36 | { |
akashvibhute | 0:30537dec6e0b | 37 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 38 | offset += this->header.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 39 | union { |
akashvibhute | 0:30537dec6e0b | 40 | int32_t real; |
akashvibhute | 0:30537dec6e0b | 41 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 42 | } u_x; |
akashvibhute | 0:30537dec6e0b | 43 | u_x.real = this->x; |
akashvibhute | 0:30537dec6e0b | 44 | *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 45 | *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 46 | *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 47 | *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 48 | offset += sizeof(this->x); |
akashvibhute | 0:30537dec6e0b | 49 | union { |
akashvibhute | 0:30537dec6e0b | 50 | int32_t real; |
akashvibhute | 0:30537dec6e0b | 51 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 52 | } u_y; |
akashvibhute | 0:30537dec6e0b | 53 | u_y.real = this->y; |
akashvibhute | 0:30537dec6e0b | 54 | *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 55 | *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 56 | *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 57 | *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 58 | offset += sizeof(this->y); |
akashvibhute | 0:30537dec6e0b | 59 | *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 60 | *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 61 | *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 62 | *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 63 | offset += sizeof(this->width); |
akashvibhute | 0:30537dec6e0b | 64 | *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 65 | *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 66 | *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 67 | *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 68 | offset += sizeof(this->height); |
akashvibhute | 0:30537dec6e0b | 69 | *(outbuffer + offset++) = data_length; |
akashvibhute | 0:30537dec6e0b | 70 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 71 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 72 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 73 | for( uint8_t i = 0; i < data_length; i++){ |
akashvibhute | 0:30537dec6e0b | 74 | union { |
akashvibhute | 0:30537dec6e0b | 75 | int8_t real; |
akashvibhute | 0:30537dec6e0b | 76 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 77 | } u_datai; |
akashvibhute | 0:30537dec6e0b | 78 | u_datai.real = this->data[i]; |
akashvibhute | 0:30537dec6e0b | 79 | *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 80 | offset += sizeof(this->data[i]); |
akashvibhute | 0:30537dec6e0b | 81 | } |
akashvibhute | 0:30537dec6e0b | 82 | return offset; |
akashvibhute | 0:30537dec6e0b | 83 | } |
akashvibhute | 0:30537dec6e0b | 84 | |
akashvibhute | 0:30537dec6e0b | 85 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 86 | { |
akashvibhute | 0:30537dec6e0b | 87 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 88 | offset += this->header.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 89 | union { |
akashvibhute | 0:30537dec6e0b | 90 | int32_t real; |
akashvibhute | 0:30537dec6e0b | 91 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 92 | } u_x; |
akashvibhute | 0:30537dec6e0b | 93 | u_x.base = 0; |
akashvibhute | 0:30537dec6e0b | 94 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 95 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 96 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 97 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 98 | this->x = u_x.real; |
akashvibhute | 0:30537dec6e0b | 99 | offset += sizeof(this->x); |
akashvibhute | 0:30537dec6e0b | 100 | union { |
akashvibhute | 0:30537dec6e0b | 101 | int32_t real; |
akashvibhute | 0:30537dec6e0b | 102 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 103 | } u_y; |
akashvibhute | 0:30537dec6e0b | 104 | u_y.base = 0; |
akashvibhute | 0:30537dec6e0b | 105 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 106 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 107 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 108 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 109 | this->y = u_y.real; |
akashvibhute | 0:30537dec6e0b | 110 | offset += sizeof(this->y); |
akashvibhute | 0:30537dec6e0b | 111 | this->width = ((uint32_t) (*(inbuffer + offset))); |
akashvibhute | 0:30537dec6e0b | 112 | this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 113 | this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 114 | this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 115 | offset += sizeof(this->width); |
akashvibhute | 0:30537dec6e0b | 116 | this->height = ((uint32_t) (*(inbuffer + offset))); |
akashvibhute | 0:30537dec6e0b | 117 | this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 118 | this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 119 | this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 120 | offset += sizeof(this->height); |
akashvibhute | 0:30537dec6e0b | 121 | uint8_t data_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 122 | if(data_lengthT > data_length) |
akashvibhute | 0:30537dec6e0b | 123 | this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); |
akashvibhute | 0:30537dec6e0b | 124 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 125 | data_length = data_lengthT; |
akashvibhute | 0:30537dec6e0b | 126 | for( uint8_t i = 0; i < data_length; i++){ |
akashvibhute | 0:30537dec6e0b | 127 | union { |
akashvibhute | 0:30537dec6e0b | 128 | int8_t real; |
akashvibhute | 0:30537dec6e0b | 129 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 130 | } u_st_data; |
akashvibhute | 0:30537dec6e0b | 131 | u_st_data.base = 0; |
akashvibhute | 0:30537dec6e0b | 132 | u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 133 | this->st_data = u_st_data.real; |
akashvibhute | 0:30537dec6e0b | 134 | offset += sizeof(this->st_data); |
akashvibhute | 0:30537dec6e0b | 135 | memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); |
akashvibhute | 0:30537dec6e0b | 136 | } |
akashvibhute | 0:30537dec6e0b | 137 | return offset; |
akashvibhute | 0:30537dec6e0b | 138 | } |
akashvibhute | 0:30537dec6e0b | 139 | |
akashvibhute | 0:30537dec6e0b | 140 | const char * getType(){ return "map_msgs/OccupancyGridUpdate"; }; |
akashvibhute | 0:30537dec6e0b | 141 | const char * getMD5(){ return "b295be292b335c34718bd939deebe1c9"; }; |
akashvibhute | 0:30537dec6e0b | 142 | |
akashvibhute | 0:30537dec6e0b | 143 | }; |
akashvibhute | 0:30537dec6e0b | 144 | |
akashvibhute | 0:30537dec6e0b | 145 | } |
akashvibhute | 0:30537dec6e0b | 146 | #endif |