This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.
Dependencies: rosserial_mbed_lib mbed Servo
geometry_msgs/Point32.h@3:dff241b66f84, 2011-11-12 (annotated)
- Committer:
- nucho
- Date:
- Sat Nov 12 23:53:04 2011 +0000
- Revision:
- 3:dff241b66f84
- Parent:
- 1:098e75fd5ad2
This program supported the revision of 167 of rosserial.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 3:dff241b66f84 | 1 | #ifndef _ROS_geometry_msgs_Point32_h |
nucho | 3:dff241b66f84 | 2 | #define _ROS_geometry_msgs_Point32_h |
nucho | 0:06fc856e99ca | 3 | |
nucho | 0:06fc856e99ca | 4 | #include <stdint.h> |
nucho | 0:06fc856e99ca | 5 | #include <string.h> |
nucho | 0:06fc856e99ca | 6 | #include <stdlib.h> |
nucho | 3:dff241b66f84 | 7 | #include "ros/msg.h" |
nucho | 0:06fc856e99ca | 8 | |
nucho | 0:06fc856e99ca | 9 | namespace geometry_msgs |
nucho | 0:06fc856e99ca | 10 | { |
nucho | 0:06fc856e99ca | 11 | |
nucho | 0:06fc856e99ca | 12 | class Point32 : public ros::Msg |
nucho | 0:06fc856e99ca | 13 | { |
nucho | 0:06fc856e99ca | 14 | public: |
nucho | 0:06fc856e99ca | 15 | float x; |
nucho | 0:06fc856e99ca | 16 | float y; |
nucho | 0:06fc856e99ca | 17 | float z; |
nucho | 0:06fc856e99ca | 18 | |
nucho | 3:dff241b66f84 | 19 | virtual int serialize(unsigned char *outbuffer) const |
nucho | 0:06fc856e99ca | 20 | { |
nucho | 0:06fc856e99ca | 21 | int offset = 0; |
nucho | 0:06fc856e99ca | 22 | union { |
nucho | 0:06fc856e99ca | 23 | float real; |
nucho | 3:dff241b66f84 | 24 | uint32_t base; |
nucho | 0:06fc856e99ca | 25 | } u_x; |
nucho | 0:06fc856e99ca | 26 | u_x.real = this->x; |
nucho | 0:06fc856e99ca | 27 | *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; |
nucho | 0:06fc856e99ca | 28 | *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; |
nucho | 0:06fc856e99ca | 29 | *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; |
nucho | 0:06fc856e99ca | 30 | *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; |
nucho | 0:06fc856e99ca | 31 | offset += sizeof(this->x); |
nucho | 0:06fc856e99ca | 32 | union { |
nucho | 0:06fc856e99ca | 33 | float real; |
nucho | 3:dff241b66f84 | 34 | uint32_t base; |
nucho | 0:06fc856e99ca | 35 | } u_y; |
nucho | 0:06fc856e99ca | 36 | u_y.real = this->y; |
nucho | 0:06fc856e99ca | 37 | *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; |
nucho | 0:06fc856e99ca | 38 | *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; |
nucho | 0:06fc856e99ca | 39 | *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; |
nucho | 0:06fc856e99ca | 40 | *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; |
nucho | 0:06fc856e99ca | 41 | offset += sizeof(this->y); |
nucho | 0:06fc856e99ca | 42 | union { |
nucho | 0:06fc856e99ca | 43 | float real; |
nucho | 3:dff241b66f84 | 44 | uint32_t base; |
nucho | 0:06fc856e99ca | 45 | } u_z; |
nucho | 0:06fc856e99ca | 46 | u_z.real = this->z; |
nucho | 0:06fc856e99ca | 47 | *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF; |
nucho | 0:06fc856e99ca | 48 | *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF; |
nucho | 0:06fc856e99ca | 49 | *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF; |
nucho | 0:06fc856e99ca | 50 | *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF; |
nucho | 0:06fc856e99ca | 51 | offset += sizeof(this->z); |
nucho | 0:06fc856e99ca | 52 | return offset; |
nucho | 0:06fc856e99ca | 53 | } |
nucho | 0:06fc856e99ca | 54 | |
nucho | 0:06fc856e99ca | 55 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 56 | { |
nucho | 0:06fc856e99ca | 57 | int offset = 0; |
nucho | 0:06fc856e99ca | 58 | union { |
nucho | 0:06fc856e99ca | 59 | float real; |
nucho | 3:dff241b66f84 | 60 | uint32_t base; |
nucho | 0:06fc856e99ca | 61 | } u_x; |
nucho | 0:06fc856e99ca | 62 | u_x.base = 0; |
nucho | 3:dff241b66f84 | 63 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:dff241b66f84 | 64 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:dff241b66f84 | 65 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:dff241b66f84 | 66 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:06fc856e99ca | 67 | this->x = u_x.real; |
nucho | 0:06fc856e99ca | 68 | offset += sizeof(this->x); |
nucho | 0:06fc856e99ca | 69 | union { |
nucho | 0:06fc856e99ca | 70 | float real; |
nucho | 3:dff241b66f84 | 71 | uint32_t base; |
nucho | 0:06fc856e99ca | 72 | } u_y; |
nucho | 0:06fc856e99ca | 73 | u_y.base = 0; |
nucho | 3:dff241b66f84 | 74 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:dff241b66f84 | 75 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:dff241b66f84 | 76 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:dff241b66f84 | 77 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:06fc856e99ca | 78 | this->y = u_y.real; |
nucho | 0:06fc856e99ca | 79 | offset += sizeof(this->y); |
nucho | 0:06fc856e99ca | 80 | union { |
nucho | 0:06fc856e99ca | 81 | float real; |
nucho | 3:dff241b66f84 | 82 | uint32_t base; |
nucho | 0:06fc856e99ca | 83 | } u_z; |
nucho | 0:06fc856e99ca | 84 | u_z.base = 0; |
nucho | 3:dff241b66f84 | 85 | u_z.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:dff241b66f84 | 86 | u_z.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:dff241b66f84 | 87 | u_z.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:dff241b66f84 | 88 | u_z.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:06fc856e99ca | 89 | this->z = u_z.real; |
nucho | 0:06fc856e99ca | 90 | offset += sizeof(this->z); |
nucho | 0:06fc856e99ca | 91 | return offset; |
nucho | 0:06fc856e99ca | 92 | } |
nucho | 0:06fc856e99ca | 93 | |
nucho | 0:06fc856e99ca | 94 | virtual const char * getType(){ return "geometry_msgs/Point32"; }; |
nucho | 3:dff241b66f84 | 95 | virtual const char * getMD5(){ return "cc153912f1453b708d221682bc23d9ac"; }; |
nucho | 0:06fc856e99ca | 96 | |
nucho | 0:06fc856e99ca | 97 | }; |
nucho | 0:06fc856e99ca | 98 | |
nucho | 0:06fc856e99ca | 99 | } |
nucho | 0:06fc856e99ca | 100 | #endif |