rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
sensor_msgs/RegionOfInterest.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_sensor_msgs_RegionOfInterest_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_sensor_msgs_RegionOfInterest_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 | |
akashvibhute | 0:30537dec6e0b | 9 | namespace sensor_msgs |
akashvibhute | 0:30537dec6e0b | 10 | { |
akashvibhute | 0:30537dec6e0b | 11 | |
akashvibhute | 0:30537dec6e0b | 12 | class RegionOfInterest : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 13 | { |
akashvibhute | 0:30537dec6e0b | 14 | public: |
akashvibhute | 0:30537dec6e0b | 15 | uint32_t x_offset; |
akashvibhute | 0:30537dec6e0b | 16 | uint32_t y_offset; |
akashvibhute | 0:30537dec6e0b | 17 | uint32_t height; |
akashvibhute | 0:30537dec6e0b | 18 | uint32_t width; |
akashvibhute | 0:30537dec6e0b | 19 | bool do_rectify; |
akashvibhute | 0:30537dec6e0b | 20 | |
akashvibhute | 0:30537dec6e0b | 21 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 22 | { |
akashvibhute | 0:30537dec6e0b | 23 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 24 | *(outbuffer + offset + 0) = (this->x_offset >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 25 | *(outbuffer + offset + 1) = (this->x_offset >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 26 | *(outbuffer + offset + 2) = (this->x_offset >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 27 | *(outbuffer + offset + 3) = (this->x_offset >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 28 | offset += sizeof(this->x_offset); |
akashvibhute | 0:30537dec6e0b | 29 | *(outbuffer + offset + 0) = (this->y_offset >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 30 | *(outbuffer + offset + 1) = (this->y_offset >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 31 | *(outbuffer + offset + 2) = (this->y_offset >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 32 | *(outbuffer + offset + 3) = (this->y_offset >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 33 | offset += sizeof(this->y_offset); |
akashvibhute | 0:30537dec6e0b | 34 | *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 35 | *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 36 | *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 37 | *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 38 | offset += sizeof(this->height); |
akashvibhute | 0:30537dec6e0b | 39 | *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 40 | *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 41 | *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 42 | *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 43 | offset += sizeof(this->width); |
akashvibhute | 0:30537dec6e0b | 44 | union { |
akashvibhute | 0:30537dec6e0b | 45 | bool real; |
akashvibhute | 0:30537dec6e0b | 46 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 47 | } u_do_rectify; |
akashvibhute | 0:30537dec6e0b | 48 | u_do_rectify.real = this->do_rectify; |
akashvibhute | 0:30537dec6e0b | 49 | *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 50 | offset += sizeof(this->do_rectify); |
akashvibhute | 0:30537dec6e0b | 51 | return offset; |
akashvibhute | 0:30537dec6e0b | 52 | } |
akashvibhute | 0:30537dec6e0b | 53 | |
akashvibhute | 0:30537dec6e0b | 54 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 55 | { |
akashvibhute | 0:30537dec6e0b | 56 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 57 | this->x_offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 58 | this->x_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 59 | this->x_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 60 | this->x_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 61 | offset += sizeof(this->x_offset); |
akashvibhute | 0:30537dec6e0b | 62 | this->y_offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 63 | this->y_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 64 | this->y_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 65 | this->y_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 66 | offset += sizeof(this->y_offset); |
akashvibhute | 0:30537dec6e0b | 67 | this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 68 | this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 69 | this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 70 | this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 71 | offset += sizeof(this->height); |
akashvibhute | 0:30537dec6e0b | 72 | this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 73 | this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 74 | this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 75 | this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 76 | offset += sizeof(this->width); |
akashvibhute | 0:30537dec6e0b | 77 | union { |
akashvibhute | 0:30537dec6e0b | 78 | bool real; |
akashvibhute | 0:30537dec6e0b | 79 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 80 | } u_do_rectify; |
akashvibhute | 0:30537dec6e0b | 81 | u_do_rectify.base = 0; |
akashvibhute | 0:30537dec6e0b | 82 | u_do_rectify.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 83 | this->do_rectify = u_do_rectify.real; |
akashvibhute | 0:30537dec6e0b | 84 | offset += sizeof(this->do_rectify); |
akashvibhute | 0:30537dec6e0b | 85 | return offset; |
akashvibhute | 0:30537dec6e0b | 86 | } |
akashvibhute | 0:30537dec6e0b | 87 | |
akashvibhute | 0:30537dec6e0b | 88 | virtual const char * getType(){ return "sensor_msgs/RegionOfInterest"; }; |
akashvibhute | 0:30537dec6e0b | 89 | virtual const char * getMD5(){ return "bdb633039d588fcccb441a4d43ccfe09"; }; |
akashvibhute | 0:30537dec6e0b | 90 | |
akashvibhute | 0:30537dec6e0b | 91 | }; |
akashvibhute | 0:30537dec6e0b | 92 | |
akashvibhute | 0:30537dec6e0b | 93 | } |
akashvibhute | 0:30537dec6e0b | 94 | #endif |