modify for Hydro version
Fork of rosserial_mbed_lib by
std_msgs/Int64.h@3:1cf99502f396, 2011-11-12 (annotated)
- Committer:
- nucho
- Date:
- Sat Nov 12 23:54:45 2011 +0000
- Revision:
- 3:1cf99502f396
- Parent:
- 1:ff0ec969dad1
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:1cf99502f396 | 1 | #ifndef _ROS_std_msgs_Int64_h |
nucho | 3:1cf99502f396 | 2 | #define _ROS_std_msgs_Int64_h |
nucho | 3:1cf99502f396 | 3 | |
nucho | 3:1cf99502f396 | 4 | #include <stdint.h> |
nucho | 3:1cf99502f396 | 5 | #include <string.h> |
nucho | 3:1cf99502f396 | 6 | #include <stdlib.h> |
nucho | 3:1cf99502f396 | 7 | #include "ros/msg.h" |
nucho | 3:1cf99502f396 | 8 | |
nucho | 3:1cf99502f396 | 9 | namespace std_msgs { |
nucho | 3:1cf99502f396 | 10 | |
nucho | 3:1cf99502f396 | 11 | class Int64 : public ros::Msg { |
nucho | 3:1cf99502f396 | 12 | public: |
nucho | 3:1cf99502f396 | 13 | int64_t data; |
nucho | 3:1cf99502f396 | 14 | |
nucho | 3:1cf99502f396 | 15 | virtual int serialize(unsigned char *outbuffer) const { |
nucho | 3:1cf99502f396 | 16 | int offset = 0; |
nucho | 3:1cf99502f396 | 17 | union { |
nucho | 3:1cf99502f396 | 18 | int64_t real; |
nucho | 3:1cf99502f396 | 19 | uint64_t base; |
nucho | 3:1cf99502f396 | 20 | } u_data; |
nucho | 3:1cf99502f396 | 21 | u_data.real = this->data; |
nucho | 3:1cf99502f396 | 22 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; |
nucho | 3:1cf99502f396 | 23 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; |
nucho | 3:1cf99502f396 | 24 | *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; |
nucho | 3:1cf99502f396 | 25 | *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; |
nucho | 3:1cf99502f396 | 26 | *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF; |
nucho | 3:1cf99502f396 | 27 | *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF; |
nucho | 3:1cf99502f396 | 28 | *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF; |
nucho | 3:1cf99502f396 | 29 | *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF; |
nucho | 3:1cf99502f396 | 30 | |
nucho | 3:1cf99502f396 | 31 | offset += sizeof(this->data); |
nucho | 3:1cf99502f396 | 32 | return offset; |
nucho | 3:1cf99502f396 | 33 | } |
nucho | 3:1cf99502f396 | 34 | |
nucho | 3:1cf99502f396 | 35 | virtual int deserialize(unsigned char *inbuffer) { |
nucho | 3:1cf99502f396 | 36 | int offset = 0; |
nucho | 3:1cf99502f396 | 37 | union { |
nucho | 3:1cf99502f396 | 38 | int64_t real; |
nucho | 3:1cf99502f396 | 39 | uint64_t base; |
nucho | 3:1cf99502f396 | 40 | } u_data; |
nucho | 3:1cf99502f396 | 41 | u_data.base = 0; |
nucho | 3:1cf99502f396 | 42 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:1cf99502f396 | 43 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:1cf99502f396 | 44 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:1cf99502f396 | 45 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 3:1cf99502f396 | 46 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 4))) << (8 * 4); |
nucho | 3:1cf99502f396 | 47 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 5))) << (8 * 5); |
nucho | 3:1cf99502f396 | 48 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 6))) << (8 * 6); |
nucho | 3:1cf99502f396 | 49 | u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 7))) << (8 * 7); |
nucho | 3:1cf99502f396 | 50 | |
nucho | 3:1cf99502f396 | 51 | this->data = u_data.real; |
nucho | 3:1cf99502f396 | 52 | offset += sizeof(this->data); |
nucho | 3:1cf99502f396 | 53 | return offset; |
nucho | 3:1cf99502f396 | 54 | } |
nucho | 3:1cf99502f396 | 55 | |
nucho | 3:1cf99502f396 | 56 | virtual const char * getType() { |
nucho | 3:1cf99502f396 | 57 | return "std_msgs/Int64"; |
nucho | 3:1cf99502f396 | 58 | }; |
nucho | 3:1cf99502f396 | 59 | virtual const char * getMD5() { |
nucho | 3:1cf99502f396 | 60 | return "34add168574510e6e17f5d23ecc077ef"; |
nucho | 3:1cf99502f396 | 61 | }; |
nucho | 3:1cf99502f396 | 62 | |
nucho | 3:1cf99502f396 | 63 | }; |
nucho | 3:1cf99502f396 | 64 | |
nucho | 3:1cf99502f396 | 65 | } |
nucho | 0:77afd7560544 | 66 | #endif |