modify for Hydro version
Fork of rosserial_mbed_lib by
sensor_msgs/Range.h@4:684f39d0c346, 2012-02-29 (annotated)
- Committer:
- nucho
- Date:
- Wed Feb 29 23:00:21 2012 +0000
- Revision:
- 4:684f39d0c346
- Parent:
- 3:1cf99502f396
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 3:1cf99502f396 | 1 | #ifndef _ROS_sensor_msgs_Range_h |
nucho | 3:1cf99502f396 | 2 | #define _ROS_sensor_msgs_Range_h |
nucho | 0:77afd7560544 | 3 | |
nucho | 0:77afd7560544 | 4 | #include <stdint.h> |
nucho | 0:77afd7560544 | 5 | #include <string.h> |
nucho | 0:77afd7560544 | 6 | #include <stdlib.h> |
nucho | 3:1cf99502f396 | 7 | #include "ros/msg.h" |
nucho | 0:77afd7560544 | 8 | #include "std_msgs/Header.h" |
nucho | 0:77afd7560544 | 9 | |
nucho | 0:77afd7560544 | 10 | namespace sensor_msgs |
nucho | 0:77afd7560544 | 11 | { |
nucho | 0:77afd7560544 | 12 | |
nucho | 0:77afd7560544 | 13 | class Range : public ros::Msg |
nucho | 0:77afd7560544 | 14 | { |
nucho | 0:77afd7560544 | 15 | public: |
nucho | 0:77afd7560544 | 16 | std_msgs::Header header; |
nucho | 3:1cf99502f396 | 17 | uint8_t radiation_type; |
nucho | 0:77afd7560544 | 18 | float field_of_view; |
nucho | 0:77afd7560544 | 19 | float min_range; |
nucho | 0:77afd7560544 | 20 | float max_range; |
nucho | 0:77afd7560544 | 21 | float range; |
nucho | 0:77afd7560544 | 22 | enum { ULTRASOUND = 0 }; |
nucho | 0:77afd7560544 | 23 | enum { INFRARED = 1 }; |
nucho | 0:77afd7560544 | 24 | |
nucho | 3:1cf99502f396 | 25 | virtual int serialize(unsigned char *outbuffer) const |
nucho | 0:77afd7560544 | 26 | { |
nucho | 0:77afd7560544 | 27 | int offset = 0; |
nucho | 0:77afd7560544 | 28 | offset += this->header.serialize(outbuffer + offset); |
nucho | 3:1cf99502f396 | 29 | *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 30 | offset += sizeof(this->radiation_type); |
nucho | 0:77afd7560544 | 31 | union { |
nucho | 0:77afd7560544 | 32 | float real; |
nucho | 3:1cf99502f396 | 33 | uint32_t base; |
nucho | 0:77afd7560544 | 34 | } u_field_of_view; |
nucho | 0:77afd7560544 | 35 | u_field_of_view.real = this->field_of_view; |
nucho | 0:77afd7560544 | 36 | *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 37 | *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 38 | *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 39 | *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 40 | offset += sizeof(this->field_of_view); |
nucho | 0:77afd7560544 | 41 | union { |
nucho | 0:77afd7560544 | 42 | float real; |
nucho | 3:1cf99502f396 | 43 | uint32_t base; |
nucho | 0:77afd7560544 | 44 | } u_min_range; |
nucho | 0:77afd7560544 | 45 | u_min_range.real = this->min_range; |
nucho | 0:77afd7560544 | 46 | *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 47 | *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 48 | *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 49 | *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 50 | offset += sizeof(this->min_range); |
nucho | 0:77afd7560544 | 51 | union { |
nucho | 0:77afd7560544 | 52 | float real; |
nucho | 3:1cf99502f396 | 53 | uint32_t base; |
nucho | 0:77afd7560544 | 54 | } u_max_range; |
nucho | 0:77afd7560544 | 55 | u_max_range.real = this->max_range; |
nucho | 0:77afd7560544 | 56 | *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 57 | *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 58 | *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 59 | *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 60 | offset += sizeof(this->max_range); |
nucho | 0:77afd7560544 | 61 | union { |
nucho | 0:77afd7560544 | 62 | float real; |
nucho | 3:1cf99502f396 | 63 | uint32_t base; |
nucho | 0:77afd7560544 | 64 | } u_range; |
nucho | 0:77afd7560544 | 65 | u_range.real = this->range; |
nucho | 0:77afd7560544 | 66 | *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 67 | *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 68 | *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 69 | *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 70 | offset += sizeof(this->range); |
nucho | 0:77afd7560544 | 71 | return offset; |
nucho | 0:77afd7560544 | 72 | } |
nucho | 0:77afd7560544 | 73 | |
nucho | 0:77afd7560544 | 74 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 75 | { |
nucho | 0:77afd7560544 | 76 | int offset = 0; |
nucho | 0:77afd7560544 | 77 | offset += this->header.deserialize(inbuffer + offset); |
nucho | 3:1cf99502f396 | 78 | this->radiation_type |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 79 | offset += sizeof(this->radiation_type); |
nucho | 0:77afd7560544 | 80 | union { |
nucho | 0:77afd7560544 | 81 | float real; |
nucho | 3:1cf99502f396 | 82 | uint32_t base; |
nucho | 0:77afd7560544 | 83 | } u_field_of_view; |
nucho | 0:77afd7560544 | 84 | u_field_of_view.base = 0; |
nucho | 3:1cf99502f396 | 85 | u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:1cf99502f396 | 86 | u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:1cf99502f396 | 87 | u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:1cf99502f396 | 88 | u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 89 | this->field_of_view = u_field_of_view.real; |
nucho | 0:77afd7560544 | 90 | offset += sizeof(this->field_of_view); |
nucho | 0:77afd7560544 | 91 | union { |
nucho | 0:77afd7560544 | 92 | float real; |
nucho | 3:1cf99502f396 | 93 | uint32_t base; |
nucho | 0:77afd7560544 | 94 | } u_min_range; |
nucho | 0:77afd7560544 | 95 | u_min_range.base = 0; |
nucho | 3:1cf99502f396 | 96 | u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:1cf99502f396 | 97 | u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:1cf99502f396 | 98 | u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:1cf99502f396 | 99 | u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 100 | this->min_range = u_min_range.real; |
nucho | 0:77afd7560544 | 101 | offset += sizeof(this->min_range); |
nucho | 0:77afd7560544 | 102 | union { |
nucho | 0:77afd7560544 | 103 | float real; |
nucho | 3:1cf99502f396 | 104 | uint32_t base; |
nucho | 0:77afd7560544 | 105 | } u_max_range; |
nucho | 0:77afd7560544 | 106 | u_max_range.base = 0; |
nucho | 3:1cf99502f396 | 107 | u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:1cf99502f396 | 108 | u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:1cf99502f396 | 109 | u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:1cf99502f396 | 110 | u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 111 | this->max_range = u_max_range.real; |
nucho | 0:77afd7560544 | 112 | offset += sizeof(this->max_range); |
nucho | 0:77afd7560544 | 113 | union { |
nucho | 0:77afd7560544 | 114 | float real; |
nucho | 3:1cf99502f396 | 115 | uint32_t base; |
nucho | 0:77afd7560544 | 116 | } u_range; |
nucho | 0:77afd7560544 | 117 | u_range.base = 0; |
nucho | 3:1cf99502f396 | 118 | u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:1cf99502f396 | 119 | u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:1cf99502f396 | 120 | u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:1cf99502f396 | 121 | u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 122 | this->range = u_range.real; |
nucho | 0:77afd7560544 | 123 | offset += sizeof(this->range); |
nucho | 0:77afd7560544 | 124 | return offset; |
nucho | 0:77afd7560544 | 125 | } |
nucho | 0:77afd7560544 | 126 | |
nucho | 0:77afd7560544 | 127 | virtual const char * getType(){ return "sensor_msgs/Range"; }; |
nucho | 3:1cf99502f396 | 128 | virtual const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; }; |
nucho | 0:77afd7560544 | 129 | |
nucho | 0:77afd7560544 | 130 | }; |
nucho | 0:77afd7560544 | 131 | |
nucho | 0:77afd7560544 | 132 | } |
nucho | 0:77afd7560544 | 133 | #endif |