modify for Hydro version
Fork of rosserial_mbed_lib by
geometry_msgs/Point.h@6:3c54bc7badd4, 2013-10-26 (annotated)
- Committer:
- jjzak
- Date:
- Sat Oct 26 15:39:01 2013 +0000
- Revision:
- 6:3c54bc7badd4
modify for Hydro version;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
jjzak | 6:3c54bc7badd4 | 1 | #ifndef _ROS_geometry_msgs_Point_h |
jjzak | 6:3c54bc7badd4 | 2 | #define _ROS_geometry_msgs_Point_h |
jjzak | 6:3c54bc7badd4 | 3 | |
jjzak | 6:3c54bc7badd4 | 4 | #include <stdint.h> |
jjzak | 6:3c54bc7badd4 | 5 | #include <string.h> |
jjzak | 6:3c54bc7badd4 | 6 | #include <stdlib.h> |
jjzak | 6:3c54bc7badd4 | 7 | #include "ros/msg.h" |
jjzak | 6:3c54bc7badd4 | 8 | |
jjzak | 6:3c54bc7badd4 | 9 | namespace geometry_msgs |
jjzak | 6:3c54bc7badd4 | 10 | { |
jjzak | 6:3c54bc7badd4 | 11 | |
jjzak | 6:3c54bc7badd4 | 12 | class Point : public ros::Msg |
jjzak | 6:3c54bc7badd4 | 13 | { |
jjzak | 6:3c54bc7badd4 | 14 | public: |
jjzak | 6:3c54bc7badd4 | 15 | float x; |
jjzak | 6:3c54bc7badd4 | 16 | float y; |
jjzak | 6:3c54bc7badd4 | 17 | float z; |
jjzak | 6:3c54bc7badd4 | 18 | |
jjzak | 6:3c54bc7badd4 | 19 | virtual int serialize(unsigned char *outbuffer) const |
jjzak | 6:3c54bc7badd4 | 20 | { |
jjzak | 6:3c54bc7badd4 | 21 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 22 | int32_t * val_x = (int32_t *) &(this->x); |
jjzak | 6:3c54bc7badd4 | 23 | int32_t exp_x = (((*val_x)>>23)&255); |
jjzak | 6:3c54bc7badd4 | 24 | if(exp_x != 0) |
jjzak | 6:3c54bc7badd4 | 25 | exp_x += 1023-127; |
jjzak | 6:3c54bc7badd4 | 26 | int32_t sig_x = *val_x; |
jjzak | 6:3c54bc7badd4 | 27 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 28 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 29 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 30 | *(outbuffer + offset++) = (sig_x<<5) & 0xff; |
jjzak | 6:3c54bc7badd4 | 31 | *(outbuffer + offset++) = (sig_x>>3) & 0xff; |
jjzak | 6:3c54bc7badd4 | 32 | *(outbuffer + offset++) = (sig_x>>11) & 0xff; |
jjzak | 6:3c54bc7badd4 | 33 | *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); |
jjzak | 6:3c54bc7badd4 | 34 | *(outbuffer + offset++) = (exp_x>>4) & 0x7F; |
jjzak | 6:3c54bc7badd4 | 35 | if(this->x < 0) *(outbuffer + offset -1) |= 0x80; |
jjzak | 6:3c54bc7badd4 | 36 | int32_t * val_y = (int32_t *) &(this->y); |
jjzak | 6:3c54bc7badd4 | 37 | int32_t exp_y = (((*val_y)>>23)&255); |
jjzak | 6:3c54bc7badd4 | 38 | if(exp_y != 0) |
jjzak | 6:3c54bc7badd4 | 39 | exp_y += 1023-127; |
jjzak | 6:3c54bc7badd4 | 40 | int32_t sig_y = *val_y; |
jjzak | 6:3c54bc7badd4 | 41 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 42 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 43 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 44 | *(outbuffer + offset++) = (sig_y<<5) & 0xff; |
jjzak | 6:3c54bc7badd4 | 45 | *(outbuffer + offset++) = (sig_y>>3) & 0xff; |
jjzak | 6:3c54bc7badd4 | 46 | *(outbuffer + offset++) = (sig_y>>11) & 0xff; |
jjzak | 6:3c54bc7badd4 | 47 | *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); |
jjzak | 6:3c54bc7badd4 | 48 | *(outbuffer + offset++) = (exp_y>>4) & 0x7F; |
jjzak | 6:3c54bc7badd4 | 49 | if(this->y < 0) *(outbuffer + offset -1) |= 0x80; |
jjzak | 6:3c54bc7badd4 | 50 | int32_t * val_z = (int32_t *) &(this->z); |
jjzak | 6:3c54bc7badd4 | 51 | int32_t exp_z = (((*val_z)>>23)&255); |
jjzak | 6:3c54bc7badd4 | 52 | if(exp_z != 0) |
jjzak | 6:3c54bc7badd4 | 53 | exp_z += 1023-127; |
jjzak | 6:3c54bc7badd4 | 54 | int32_t sig_z = *val_z; |
jjzak | 6:3c54bc7badd4 | 55 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 56 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 57 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 58 | *(outbuffer + offset++) = (sig_z<<5) & 0xff; |
jjzak | 6:3c54bc7badd4 | 59 | *(outbuffer + offset++) = (sig_z>>3) & 0xff; |
jjzak | 6:3c54bc7badd4 | 60 | *(outbuffer + offset++) = (sig_z>>11) & 0xff; |
jjzak | 6:3c54bc7badd4 | 61 | *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); |
jjzak | 6:3c54bc7badd4 | 62 | *(outbuffer + offset++) = (exp_z>>4) & 0x7F; |
jjzak | 6:3c54bc7badd4 | 63 | if(this->z < 0) *(outbuffer + offset -1) |= 0x80; |
jjzak | 6:3c54bc7badd4 | 64 | return offset; |
jjzak | 6:3c54bc7badd4 | 65 | } |
jjzak | 6:3c54bc7badd4 | 66 | |
jjzak | 6:3c54bc7badd4 | 67 | virtual int deserialize(unsigned char *inbuffer) |
jjzak | 6:3c54bc7badd4 | 68 | { |
jjzak | 6:3c54bc7badd4 | 69 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 70 | uint32_t * val_x = (uint32_t*) &(this->x); |
jjzak | 6:3c54bc7badd4 | 71 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 72 | *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
jjzak | 6:3c54bc7badd4 | 73 | *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
jjzak | 6:3c54bc7badd4 | 74 | *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
jjzak | 6:3c54bc7badd4 | 75 | *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
jjzak | 6:3c54bc7badd4 | 76 | uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
jjzak | 6:3c54bc7badd4 | 77 | exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
jjzak | 6:3c54bc7badd4 | 78 | if(exp_x !=0) |
jjzak | 6:3c54bc7badd4 | 79 | *val_x |= ((exp_x)-1023+127)<<23; |
jjzak | 6:3c54bc7badd4 | 80 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; |
jjzak | 6:3c54bc7badd4 | 81 | uint32_t * val_y = (uint32_t*) &(this->y); |
jjzak | 6:3c54bc7badd4 | 82 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 83 | *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
jjzak | 6:3c54bc7badd4 | 84 | *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
jjzak | 6:3c54bc7badd4 | 85 | *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
jjzak | 6:3c54bc7badd4 | 86 | *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
jjzak | 6:3c54bc7badd4 | 87 | uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
jjzak | 6:3c54bc7badd4 | 88 | exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
jjzak | 6:3c54bc7badd4 | 89 | if(exp_y !=0) |
jjzak | 6:3c54bc7badd4 | 90 | *val_y |= ((exp_y)-1023+127)<<23; |
jjzak | 6:3c54bc7badd4 | 91 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; |
jjzak | 6:3c54bc7badd4 | 92 | uint32_t * val_z = (uint32_t*) &(this->z); |
jjzak | 6:3c54bc7badd4 | 93 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 94 | *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
jjzak | 6:3c54bc7badd4 | 95 | *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
jjzak | 6:3c54bc7badd4 | 96 | *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
jjzak | 6:3c54bc7badd4 | 97 | *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
jjzak | 6:3c54bc7badd4 | 98 | uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
jjzak | 6:3c54bc7badd4 | 99 | exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
jjzak | 6:3c54bc7badd4 | 100 | if(exp_z !=0) |
jjzak | 6:3c54bc7badd4 | 101 | *val_z |= ((exp_z)-1023+127)<<23; |
jjzak | 6:3c54bc7badd4 | 102 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; |
jjzak | 6:3c54bc7badd4 | 103 | return offset; |
jjzak | 6:3c54bc7badd4 | 104 | } |
jjzak | 6:3c54bc7badd4 | 105 | |
jjzak | 6:3c54bc7badd4 | 106 | const char * getType(){ return "geometry_msgs/Point"; }; |
jjzak | 6:3c54bc7badd4 | 107 | const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; |
jjzak | 6:3c54bc7badd4 | 108 | |
jjzak | 6:3c54bc7badd4 | 109 | }; |
jjzak | 6:3c54bc7badd4 | 110 | |
jjzak | 6:3c54bc7badd4 | 111 | } |
jjzak | 6:3c54bc7badd4 | 112 | #endif |