modify for Hydro version
Fork of rosserial_mbed_lib by
nav_msgs/OccupancyGrid.h@6:3c54bc7badd4, 2013-10-26 (annotated)
- Committer:
- jjzak
- Date:
- Sat Oct 26 15:39:01 2013 +0000
- Revision:
- 6:3c54bc7badd4
modify for Hydro version;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
jjzak | 6:3c54bc7badd4 | 1 | #ifndef _ROS_nav_msgs_OccupancyGrid_h |
jjzak | 6:3c54bc7badd4 | 2 | #define _ROS_nav_msgs_OccupancyGrid_h |
jjzak | 6:3c54bc7badd4 | 3 | |
jjzak | 6:3c54bc7badd4 | 4 | #include <stdint.h> |
jjzak | 6:3c54bc7badd4 | 5 | #include <string.h> |
jjzak | 6:3c54bc7badd4 | 6 | #include <stdlib.h> |
jjzak | 6:3c54bc7badd4 | 7 | #include "ros/msg.h" |
jjzak | 6:3c54bc7badd4 | 8 | #include "std_msgs/Header.h" |
jjzak | 6:3c54bc7badd4 | 9 | #include "nav_msgs/MapMetaData.h" |
jjzak | 6:3c54bc7badd4 | 10 | |
jjzak | 6:3c54bc7badd4 | 11 | namespace nav_msgs |
jjzak | 6:3c54bc7badd4 | 12 | { |
jjzak | 6:3c54bc7badd4 | 13 | |
jjzak | 6:3c54bc7badd4 | 14 | class OccupancyGrid : public ros::Msg |
jjzak | 6:3c54bc7badd4 | 15 | { |
jjzak | 6:3c54bc7badd4 | 16 | public: |
jjzak | 6:3c54bc7badd4 | 17 | std_msgs::Header header; |
jjzak | 6:3c54bc7badd4 | 18 | nav_msgs::MapMetaData info; |
jjzak | 6:3c54bc7badd4 | 19 | uint8_t data_length; |
jjzak | 6:3c54bc7badd4 | 20 | int8_t st_data; |
jjzak | 6:3c54bc7badd4 | 21 | int8_t * data; |
jjzak | 6:3c54bc7badd4 | 22 | |
jjzak | 6:3c54bc7badd4 | 23 | virtual int serialize(unsigned char *outbuffer) const |
jjzak | 6:3c54bc7badd4 | 24 | { |
jjzak | 6:3c54bc7badd4 | 25 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 26 | offset += this->header.serialize(outbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 27 | offset += this->info.serialize(outbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 28 | *(outbuffer + offset++) = data_length; |
jjzak | 6:3c54bc7badd4 | 29 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 30 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 31 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 32 | for( uint8_t i = 0; i < data_length; i++){ |
jjzak | 6:3c54bc7badd4 | 33 | union { |
jjzak | 6:3c54bc7badd4 | 34 | int8_t real; |
jjzak | 6:3c54bc7badd4 | 35 | uint8_t base; |
jjzak | 6:3c54bc7badd4 | 36 | } u_datai; |
jjzak | 6:3c54bc7badd4 | 37 | u_datai.real = this->data[i]; |
jjzak | 6:3c54bc7badd4 | 38 | *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 39 | offset += sizeof(this->data[i]); |
jjzak | 6:3c54bc7badd4 | 40 | } |
jjzak | 6:3c54bc7badd4 | 41 | return offset; |
jjzak | 6:3c54bc7badd4 | 42 | } |
jjzak | 6:3c54bc7badd4 | 43 | |
jjzak | 6:3c54bc7badd4 | 44 | virtual int deserialize(unsigned char *inbuffer) |
jjzak | 6:3c54bc7badd4 | 45 | { |
jjzak | 6:3c54bc7badd4 | 46 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 47 | offset += this->header.deserialize(inbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 48 | offset += this->info.deserialize(inbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 49 | uint8_t data_lengthT = *(inbuffer + offset++); |
jjzak | 6:3c54bc7badd4 | 50 | if(data_lengthT > data_length) |
jjzak | 6:3c54bc7badd4 | 51 | this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); |
jjzak | 6:3c54bc7badd4 | 52 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 53 | data_length = data_lengthT; |
jjzak | 6:3c54bc7badd4 | 54 | for( uint8_t i = 0; i < data_length; i++){ |
jjzak | 6:3c54bc7badd4 | 55 | union { |
jjzak | 6:3c54bc7badd4 | 56 | int8_t real; |
jjzak | 6:3c54bc7badd4 | 57 | uint8_t base; |
jjzak | 6:3c54bc7badd4 | 58 | } u_st_data; |
jjzak | 6:3c54bc7badd4 | 59 | u_st_data.base = 0; |
jjzak | 6:3c54bc7badd4 | 60 | u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
jjzak | 6:3c54bc7badd4 | 61 | this->st_data = u_st_data.real; |
jjzak | 6:3c54bc7badd4 | 62 | offset += sizeof(this->st_data); |
jjzak | 6:3c54bc7badd4 | 63 | memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); |
jjzak | 6:3c54bc7badd4 | 64 | } |
jjzak | 6:3c54bc7badd4 | 65 | return offset; |
jjzak | 6:3c54bc7badd4 | 66 | } |
jjzak | 6:3c54bc7badd4 | 67 | |
jjzak | 6:3c54bc7badd4 | 68 | const char * getType(){ return "nav_msgs/OccupancyGrid"; }; |
jjzak | 6:3c54bc7badd4 | 69 | const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; }; |
jjzak | 6:3c54bc7badd4 | 70 | |
jjzak | 6:3c54bc7badd4 | 71 | }; |
jjzak | 6:3c54bc7badd4 | 72 | |
jjzak | 6:3c54bc7badd4 | 73 | } |
jjzak | 6:3c54bc7badd4 | 74 | #endif |