ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.
map_msgs/ProjectedMap.h@2:65cba0dcf634, 2022-01-27 (annotated)
- Committer:
- gosari
- Date:
- Thu Jan 27 11:36:16 2022 +0000
- Revision:
- 2:65cba0dcf634
- Parent:
- 0:9e9b7db60fd5
for message communication with mbed
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_map_msgs_ProjectedMap_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_map_msgs_ProjectedMap_h |
garyservin | 0:9e9b7db60fd5 | 3 | |
garyservin | 0:9e9b7db60fd5 | 4 | #include <stdint.h> |
garyservin | 0:9e9b7db60fd5 | 5 | #include <string.h> |
garyservin | 0:9e9b7db60fd5 | 6 | #include <stdlib.h> |
garyservin | 0:9e9b7db60fd5 | 7 | #include "ros/msg.h" |
garyservin | 0:9e9b7db60fd5 | 8 | #include "nav_msgs/OccupancyGrid.h" |
garyservin | 0:9e9b7db60fd5 | 9 | |
garyservin | 0:9e9b7db60fd5 | 10 | namespace map_msgs |
garyservin | 0:9e9b7db60fd5 | 11 | { |
garyservin | 0:9e9b7db60fd5 | 12 | |
garyservin | 0:9e9b7db60fd5 | 13 | class ProjectedMap : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 14 | { |
garyservin | 0:9e9b7db60fd5 | 15 | public: |
garyservin | 0:9e9b7db60fd5 | 16 | typedef nav_msgs::OccupancyGrid _map_type; |
garyservin | 0:9e9b7db60fd5 | 17 | _map_type map; |
garyservin | 0:9e9b7db60fd5 | 18 | typedef double _min_z_type; |
garyservin | 0:9e9b7db60fd5 | 19 | _min_z_type min_z; |
garyservin | 0:9e9b7db60fd5 | 20 | typedef double _max_z_type; |
garyservin | 0:9e9b7db60fd5 | 21 | _max_z_type max_z; |
garyservin | 0:9e9b7db60fd5 | 22 | |
garyservin | 0:9e9b7db60fd5 | 23 | ProjectedMap(): |
garyservin | 0:9e9b7db60fd5 | 24 | map(), |
garyservin | 0:9e9b7db60fd5 | 25 | min_z(0), |
garyservin | 0:9e9b7db60fd5 | 26 | max_z(0) |
garyservin | 0:9e9b7db60fd5 | 27 | { |
garyservin | 0:9e9b7db60fd5 | 28 | } |
garyservin | 0:9e9b7db60fd5 | 29 | |
garyservin | 0:9e9b7db60fd5 | 30 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 31 | { |
garyservin | 0:9e9b7db60fd5 | 32 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 33 | offset += this->map.serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 34 | union { |
garyservin | 0:9e9b7db60fd5 | 35 | double real; |
garyservin | 0:9e9b7db60fd5 | 36 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 37 | } u_min_z; |
garyservin | 0:9e9b7db60fd5 | 38 | u_min_z.real = this->min_z; |
garyservin | 0:9e9b7db60fd5 | 39 | *(outbuffer + offset + 0) = (u_min_z.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 40 | *(outbuffer + offset + 1) = (u_min_z.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 41 | *(outbuffer + offset + 2) = (u_min_z.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 42 | *(outbuffer + offset + 3) = (u_min_z.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 43 | *(outbuffer + offset + 4) = (u_min_z.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 44 | *(outbuffer + offset + 5) = (u_min_z.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 45 | *(outbuffer + offset + 6) = (u_min_z.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 46 | *(outbuffer + offset + 7) = (u_min_z.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 47 | offset += sizeof(this->min_z); |
garyservin | 0:9e9b7db60fd5 | 48 | union { |
garyservin | 0:9e9b7db60fd5 | 49 | double real; |
garyservin | 0:9e9b7db60fd5 | 50 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 51 | } u_max_z; |
garyservin | 0:9e9b7db60fd5 | 52 | u_max_z.real = this->max_z; |
garyservin | 0:9e9b7db60fd5 | 53 | *(outbuffer + offset + 0) = (u_max_z.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 54 | *(outbuffer + offset + 1) = (u_max_z.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 55 | *(outbuffer + offset + 2) = (u_max_z.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 56 | *(outbuffer + offset + 3) = (u_max_z.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 57 | *(outbuffer + offset + 4) = (u_max_z.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 58 | *(outbuffer + offset + 5) = (u_max_z.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 59 | *(outbuffer + offset + 6) = (u_max_z.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 60 | *(outbuffer + offset + 7) = (u_max_z.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 61 | offset += sizeof(this->max_z); |
garyservin | 0:9e9b7db60fd5 | 62 | return offset; |
garyservin | 0:9e9b7db60fd5 | 63 | } |
garyservin | 0:9e9b7db60fd5 | 64 | |
garyservin | 0:9e9b7db60fd5 | 65 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 66 | { |
garyservin | 0:9e9b7db60fd5 | 67 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 68 | offset += this->map.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 69 | union { |
garyservin | 0:9e9b7db60fd5 | 70 | double real; |
garyservin | 0:9e9b7db60fd5 | 71 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 72 | } u_min_z; |
garyservin | 0:9e9b7db60fd5 | 73 | u_min_z.base = 0; |
garyservin | 0:9e9b7db60fd5 | 74 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 75 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 76 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 77 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 78 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 79 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 80 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 81 | u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 82 | this->min_z = u_min_z.real; |
garyservin | 0:9e9b7db60fd5 | 83 | offset += sizeof(this->min_z); |
garyservin | 0:9e9b7db60fd5 | 84 | union { |
garyservin | 0:9e9b7db60fd5 | 85 | double real; |
garyservin | 0:9e9b7db60fd5 | 86 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 87 | } u_max_z; |
garyservin | 0:9e9b7db60fd5 | 88 | u_max_z.base = 0; |
garyservin | 0:9e9b7db60fd5 | 89 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 90 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 91 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 92 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 93 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 94 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 95 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 96 | u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 97 | this->max_z = u_max_z.real; |
garyservin | 0:9e9b7db60fd5 | 98 | offset += sizeof(this->max_z); |
garyservin | 0:9e9b7db60fd5 | 99 | return offset; |
garyservin | 0:9e9b7db60fd5 | 100 | } |
garyservin | 0:9e9b7db60fd5 | 101 | |
garyservin | 0:9e9b7db60fd5 | 102 | const char * getType(){ return "map_msgs/ProjectedMap"; }; |
garyservin | 0:9e9b7db60fd5 | 103 | const char * getMD5(){ return "7bbe8f96e45089681dc1ea7d023cbfca"; }; |
garyservin | 0:9e9b7db60fd5 | 104 | |
garyservin | 0:9e9b7db60fd5 | 105 | }; |
garyservin | 0:9e9b7db60fd5 | 106 | |
garyservin | 0:9e9b7db60fd5 | 107 | } |
garyservin | 0:9e9b7db60fd5 | 108 | #endif |