modify for Hydro version
Fork of rosserial_mbed_lib by
geometry_msgs/Quaternion.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_geometry_msgs_Quaternion_h |
nucho | 3:1cf99502f396 | 2 | #define _ROS_geometry_msgs_Quaternion_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 | |
nucho | 0:77afd7560544 | 9 | namespace geometry_msgs |
nucho | 0:77afd7560544 | 10 | { |
nucho | 0:77afd7560544 | 11 | |
nucho | 0:77afd7560544 | 12 | class Quaternion : public ros::Msg |
nucho | 0:77afd7560544 | 13 | { |
nucho | 0:77afd7560544 | 14 | public: |
nucho | 0:77afd7560544 | 15 | float x; |
nucho | 0:77afd7560544 | 16 | float y; |
nucho | 0:77afd7560544 | 17 | float z; |
nucho | 0:77afd7560544 | 18 | float w; |
nucho | 0:77afd7560544 | 19 | |
nucho | 3:1cf99502f396 | 20 | virtual int serialize(unsigned char *outbuffer) const |
nucho | 0:77afd7560544 | 21 | { |
nucho | 0:77afd7560544 | 22 | int offset = 0; |
nucho | 3:1cf99502f396 | 23 | int32_t * val_x = (long *) &(this->x); |
nucho | 3:1cf99502f396 | 24 | int32_t exp_x = (((*val_x)>>23)&255); |
nucho | 0:77afd7560544 | 25 | if(exp_x != 0) |
nucho | 0:77afd7560544 | 26 | exp_x += 1023-127; |
nucho | 3:1cf99502f396 | 27 | int32_t sig_x = *val_x; |
nucho | 0:77afd7560544 | 28 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 29 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 30 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 31 | *(outbuffer + offset++) = (sig_x<<5) & 0xff; |
nucho | 0:77afd7560544 | 32 | *(outbuffer + offset++) = (sig_x>>3) & 0xff; |
nucho | 0:77afd7560544 | 33 | *(outbuffer + offset++) = (sig_x>>11) & 0xff; |
nucho | 0:77afd7560544 | 34 | *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); |
nucho | 0:77afd7560544 | 35 | *(outbuffer + offset++) = (exp_x>>4) & 0x7F; |
nucho | 0:77afd7560544 | 36 | if(this->x < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 3:1cf99502f396 | 37 | int32_t * val_y = (long *) &(this->y); |
nucho | 3:1cf99502f396 | 38 | int32_t exp_y = (((*val_y)>>23)&255); |
nucho | 0:77afd7560544 | 39 | if(exp_y != 0) |
nucho | 0:77afd7560544 | 40 | exp_y += 1023-127; |
nucho | 3:1cf99502f396 | 41 | int32_t sig_y = *val_y; |
nucho | 0:77afd7560544 | 42 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 43 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 44 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 45 | *(outbuffer + offset++) = (sig_y<<5) & 0xff; |
nucho | 0:77afd7560544 | 46 | *(outbuffer + offset++) = (sig_y>>3) & 0xff; |
nucho | 0:77afd7560544 | 47 | *(outbuffer + offset++) = (sig_y>>11) & 0xff; |
nucho | 0:77afd7560544 | 48 | *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); |
nucho | 0:77afd7560544 | 49 | *(outbuffer + offset++) = (exp_y>>4) & 0x7F; |
nucho | 0:77afd7560544 | 50 | if(this->y < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 3:1cf99502f396 | 51 | int32_t * val_z = (long *) &(this->z); |
nucho | 3:1cf99502f396 | 52 | int32_t exp_z = (((*val_z)>>23)&255); |
nucho | 0:77afd7560544 | 53 | if(exp_z != 0) |
nucho | 0:77afd7560544 | 54 | exp_z += 1023-127; |
nucho | 3:1cf99502f396 | 55 | int32_t sig_z = *val_z; |
nucho | 0:77afd7560544 | 56 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 57 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 58 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 59 | *(outbuffer + offset++) = (sig_z<<5) & 0xff; |
nucho | 0:77afd7560544 | 60 | *(outbuffer + offset++) = (sig_z>>3) & 0xff; |
nucho | 0:77afd7560544 | 61 | *(outbuffer + offset++) = (sig_z>>11) & 0xff; |
nucho | 0:77afd7560544 | 62 | *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); |
nucho | 0:77afd7560544 | 63 | *(outbuffer + offset++) = (exp_z>>4) & 0x7F; |
nucho | 0:77afd7560544 | 64 | if(this->z < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 3:1cf99502f396 | 65 | int32_t * val_w = (long *) &(this->w); |
nucho | 3:1cf99502f396 | 66 | int32_t exp_w = (((*val_w)>>23)&255); |
nucho | 0:77afd7560544 | 67 | if(exp_w != 0) |
nucho | 0:77afd7560544 | 68 | exp_w += 1023-127; |
nucho | 3:1cf99502f396 | 69 | int32_t sig_w = *val_w; |
nucho | 0:77afd7560544 | 70 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 71 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 72 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 73 | *(outbuffer + offset++) = (sig_w<<5) & 0xff; |
nucho | 0:77afd7560544 | 74 | *(outbuffer + offset++) = (sig_w>>3) & 0xff; |
nucho | 0:77afd7560544 | 75 | *(outbuffer + offset++) = (sig_w>>11) & 0xff; |
nucho | 0:77afd7560544 | 76 | *(outbuffer + offset++) = ((exp_w<<4) & 0xF0) | ((sig_w>>19)&0x0F); |
nucho | 0:77afd7560544 | 77 | *(outbuffer + offset++) = (exp_w>>4) & 0x7F; |
nucho | 0:77afd7560544 | 78 | if(this->w < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:77afd7560544 | 79 | return offset; |
nucho | 0:77afd7560544 | 80 | } |
nucho | 0:77afd7560544 | 81 | |
nucho | 0:77afd7560544 | 82 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 83 | { |
nucho | 0:77afd7560544 | 84 | int offset = 0; |
nucho | 3:1cf99502f396 | 85 | uint32_t * val_x = (uint32_t*) &(this->x); |
nucho | 0:77afd7560544 | 86 | offset += 3; |
nucho | 3:1cf99502f396 | 87 | *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 3:1cf99502f396 | 88 | *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 3:1cf99502f396 | 89 | *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 3:1cf99502f396 | 90 | *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 3:1cf99502f396 | 91 | uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 3:1cf99502f396 | 92 | exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 93 | if(exp_x !=0) |
nucho | 0:77afd7560544 | 94 | *val_x |= ((exp_x)-1023+127)<<23; |
nucho | 0:77afd7560544 | 95 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; |
nucho | 3:1cf99502f396 | 96 | uint32_t * val_y = (uint32_t*) &(this->y); |
nucho | 0:77afd7560544 | 97 | offset += 3; |
nucho | 3:1cf99502f396 | 98 | *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 3:1cf99502f396 | 99 | *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 3:1cf99502f396 | 100 | *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 3:1cf99502f396 | 101 | *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 3:1cf99502f396 | 102 | uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 3:1cf99502f396 | 103 | exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 104 | if(exp_y !=0) |
nucho | 0:77afd7560544 | 105 | *val_y |= ((exp_y)-1023+127)<<23; |
nucho | 0:77afd7560544 | 106 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; |
nucho | 3:1cf99502f396 | 107 | uint32_t * val_z = (uint32_t*) &(this->z); |
nucho | 0:77afd7560544 | 108 | offset += 3; |
nucho | 3:1cf99502f396 | 109 | *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 3:1cf99502f396 | 110 | *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 3:1cf99502f396 | 111 | *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 3:1cf99502f396 | 112 | *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 3:1cf99502f396 | 113 | uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 3:1cf99502f396 | 114 | exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 115 | if(exp_z !=0) |
nucho | 0:77afd7560544 | 116 | *val_z |= ((exp_z)-1023+127)<<23; |
nucho | 0:77afd7560544 | 117 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; |
nucho | 3:1cf99502f396 | 118 | uint32_t * val_w = (uint32_t*) &(this->w); |
nucho | 0:77afd7560544 | 119 | offset += 3; |
nucho | 3:1cf99502f396 | 120 | *val_w = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 3:1cf99502f396 | 121 | *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 3:1cf99502f396 | 122 | *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 3:1cf99502f396 | 123 | *val_w |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 3:1cf99502f396 | 124 | uint32_t exp_w = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 3:1cf99502f396 | 125 | exp_w |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 126 | if(exp_w !=0) |
nucho | 0:77afd7560544 | 127 | *val_w |= ((exp_w)-1023+127)<<23; |
nucho | 0:77afd7560544 | 128 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->w = -this->w; |
nucho | 0:77afd7560544 | 129 | return offset; |
nucho | 0:77afd7560544 | 130 | } |
nucho | 0:77afd7560544 | 131 | |
nucho | 0:77afd7560544 | 132 | virtual const char * getType(){ return "geometry_msgs/Quaternion"; }; |
nucho | 3:1cf99502f396 | 133 | virtual const char * getMD5(){ return "a779879fadf0160734f906b8c19c7004"; }; |
nucho | 0:77afd7560544 | 134 | |
nucho | 0:77afd7560544 | 135 | }; |
nucho | 0:77afd7560544 | 136 | |
nucho | 0:77afd7560544 | 137 | } |
nucho | 0:77afd7560544 | 138 | #endif |