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
sensor_msgs/Imu.h@3:dff241b66f84, 2011-11-12 (annotated)
- Committer:
- nucho
- Date:
- Sat Nov 12 23:53:04 2011 +0000
- Revision:
- 3:dff241b66f84
- Parent:
- 0:06fc856e99ca
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_sensor_msgs_Imu_h |
nucho | 3:dff241b66f84 | 2 | #define _ROS_sensor_msgs_Imu_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 | #include "std_msgs/Header.h" |
nucho | 0:06fc856e99ca | 9 | #include "geometry_msgs/Quaternion.h" |
nucho | 0:06fc856e99ca | 10 | #include "geometry_msgs/Vector3.h" |
nucho | 0:06fc856e99ca | 11 | |
nucho | 0:06fc856e99ca | 12 | namespace sensor_msgs |
nucho | 0:06fc856e99ca | 13 | { |
nucho | 0:06fc856e99ca | 14 | |
nucho | 0:06fc856e99ca | 15 | class Imu : public ros::Msg |
nucho | 0:06fc856e99ca | 16 | { |
nucho | 0:06fc856e99ca | 17 | public: |
nucho | 0:06fc856e99ca | 18 | std_msgs::Header header; |
nucho | 0:06fc856e99ca | 19 | geometry_msgs::Quaternion orientation; |
nucho | 0:06fc856e99ca | 20 | float orientation_covariance[9]; |
nucho | 0:06fc856e99ca | 21 | geometry_msgs::Vector3 angular_velocity; |
nucho | 0:06fc856e99ca | 22 | float angular_velocity_covariance[9]; |
nucho | 0:06fc856e99ca | 23 | geometry_msgs::Vector3 linear_acceleration; |
nucho | 0:06fc856e99ca | 24 | float linear_acceleration_covariance[9]; |
nucho | 0:06fc856e99ca | 25 | |
nucho | 3:dff241b66f84 | 26 | virtual int serialize(unsigned char *outbuffer) const |
nucho | 0:06fc856e99ca | 27 | { |
nucho | 0:06fc856e99ca | 28 | int offset = 0; |
nucho | 0:06fc856e99ca | 29 | offset += this->header.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 30 | offset += this->orientation.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 31 | unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance; |
nucho | 3:dff241b66f84 | 32 | for( uint8_t i = 0; i < 9; i++){ |
nucho | 3:dff241b66f84 | 33 | int32_t * val_orientation_covariancei = (long *) &(this->orientation_covariance[i]); |
nucho | 3:dff241b66f84 | 34 | int32_t exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255); |
nucho | 0:06fc856e99ca | 35 | if(exp_orientation_covariancei != 0) |
nucho | 0:06fc856e99ca | 36 | exp_orientation_covariancei += 1023-127; |
nucho | 3:dff241b66f84 | 37 | int32_t sig_orientation_covariancei = *val_orientation_covariancei; |
nucho | 0:06fc856e99ca | 38 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 39 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 40 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 41 | *(outbuffer + offset++) = (sig_orientation_covariancei<<5) & 0xff; |
nucho | 0:06fc856e99ca | 42 | *(outbuffer + offset++) = (sig_orientation_covariancei>>3) & 0xff; |
nucho | 0:06fc856e99ca | 43 | *(outbuffer + offset++) = (sig_orientation_covariancei>>11) & 0xff; |
nucho | 0:06fc856e99ca | 44 | *(outbuffer + offset++) = ((exp_orientation_covariancei<<4) & 0xF0) | ((sig_orientation_covariancei>>19)&0x0F); |
nucho | 0:06fc856e99ca | 45 | *(outbuffer + offset++) = (exp_orientation_covariancei>>4) & 0x7F; |
nucho | 0:06fc856e99ca | 46 | if(this->orientation_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:06fc856e99ca | 47 | } |
nucho | 0:06fc856e99ca | 48 | offset += this->angular_velocity.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 49 | unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance; |
nucho | 3:dff241b66f84 | 50 | for( uint8_t i = 0; i < 9; i++){ |
nucho | 3:dff241b66f84 | 51 | int32_t * val_angular_velocity_covariancei = (long *) &(this->angular_velocity_covariance[i]); |
nucho | 3:dff241b66f84 | 52 | int32_t exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255); |
nucho | 0:06fc856e99ca | 53 | if(exp_angular_velocity_covariancei != 0) |
nucho | 0:06fc856e99ca | 54 | exp_angular_velocity_covariancei += 1023-127; |
nucho | 3:dff241b66f84 | 55 | int32_t sig_angular_velocity_covariancei = *val_angular_velocity_covariancei; |
nucho | 0:06fc856e99ca | 56 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 57 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 58 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 59 | *(outbuffer + offset++) = (sig_angular_velocity_covariancei<<5) & 0xff; |
nucho | 0:06fc856e99ca | 60 | *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>3) & 0xff; |
nucho | 0:06fc856e99ca | 61 | *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>11) & 0xff; |
nucho | 0:06fc856e99ca | 62 | *(outbuffer + offset++) = ((exp_angular_velocity_covariancei<<4) & 0xF0) | ((sig_angular_velocity_covariancei>>19)&0x0F); |
nucho | 0:06fc856e99ca | 63 | *(outbuffer + offset++) = (exp_angular_velocity_covariancei>>4) & 0x7F; |
nucho | 0:06fc856e99ca | 64 | if(this->angular_velocity_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:06fc856e99ca | 65 | } |
nucho | 0:06fc856e99ca | 66 | offset += this->linear_acceleration.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 67 | unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance; |
nucho | 3:dff241b66f84 | 68 | for( uint8_t i = 0; i < 9; i++){ |
nucho | 3:dff241b66f84 | 69 | int32_t * val_linear_acceleration_covariancei = (long *) &(this->linear_acceleration_covariance[i]); |
nucho | 3:dff241b66f84 | 70 | int32_t exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255); |
nucho | 0:06fc856e99ca | 71 | if(exp_linear_acceleration_covariancei != 0) |
nucho | 0:06fc856e99ca | 72 | exp_linear_acceleration_covariancei += 1023-127; |
nucho | 3:dff241b66f84 | 73 | int32_t sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei; |
nucho | 0:06fc856e99ca | 74 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 75 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 76 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 77 | *(outbuffer + offset++) = (sig_linear_acceleration_covariancei<<5) & 0xff; |
nucho | 0:06fc856e99ca | 78 | *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>3) & 0xff; |
nucho | 0:06fc856e99ca | 79 | *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>11) & 0xff; |
nucho | 0:06fc856e99ca | 80 | *(outbuffer + offset++) = ((exp_linear_acceleration_covariancei<<4) & 0xF0) | ((sig_linear_acceleration_covariancei>>19)&0x0F); |
nucho | 0:06fc856e99ca | 81 | *(outbuffer + offset++) = (exp_linear_acceleration_covariancei>>4) & 0x7F; |
nucho | 0:06fc856e99ca | 82 | if(this->linear_acceleration_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:06fc856e99ca | 83 | } |
nucho | 0:06fc856e99ca | 84 | return offset; |
nucho | 0:06fc856e99ca | 85 | } |
nucho | 0:06fc856e99ca | 86 | |
nucho | 0:06fc856e99ca | 87 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 88 | { |
nucho | 0:06fc856e99ca | 89 | int offset = 0; |
nucho | 0:06fc856e99ca | 90 | offset += this->header.deserialize(inbuffer + offset); |
nucho | 0:06fc856e99ca | 91 | offset += this->orientation.deserialize(inbuffer + offset); |
nucho | 3:dff241b66f84 | 92 | uint8_t * orientation_covariance_val = (uint8_t*) this->orientation_covariance; |
nucho | 3:dff241b66f84 | 93 | for( uint8_t i = 0; i < 9; i++){ |
nucho | 3:dff241b66f84 | 94 | uint32_t * val_orientation_covariancei = (uint32_t*) &(this->orientation_covariance[i]); |
nucho | 0:06fc856e99ca | 95 | offset += 3; |
nucho | 3:dff241b66f84 | 96 | *val_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 3:dff241b66f84 | 97 | *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 3:dff241b66f84 | 98 | *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 3:dff241b66f84 | 99 | *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 3:dff241b66f84 | 100 | uint32_t exp_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 3:dff241b66f84 | 101 | exp_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:06fc856e99ca | 102 | if(exp_orientation_covariancei !=0) |
nucho | 0:06fc856e99ca | 103 | *val_orientation_covariancei |= ((exp_orientation_covariancei)-1023+127)<<23; |
nucho | 0:06fc856e99ca | 104 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->orientation_covariance[i] = -this->orientation_covariance[i]; |
nucho | 0:06fc856e99ca | 105 | } |
nucho | 0:06fc856e99ca | 106 | offset += this->angular_velocity.deserialize(inbuffer + offset); |
nucho | 3:dff241b66f84 | 107 | uint8_t * angular_velocity_covariance_val = (uint8_t*) this->angular_velocity_covariance; |
nucho | 3:dff241b66f84 | 108 | for( uint8_t i = 0; i < 9; i++){ |
nucho | 3:dff241b66f84 | 109 | uint32_t * val_angular_velocity_covariancei = (uint32_t*) &(this->angular_velocity_covariance[i]); |
nucho | 0:06fc856e99ca | 110 | offset += 3; |
nucho | 3:dff241b66f84 | 111 | *val_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 3:dff241b66f84 | 112 | *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 3:dff241b66f84 | 113 | *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 3:dff241b66f84 | 114 | *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 3:dff241b66f84 | 115 | uint32_t exp_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 3:dff241b66f84 | 116 | exp_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:06fc856e99ca | 117 | if(exp_angular_velocity_covariancei !=0) |
nucho | 0:06fc856e99ca | 118 | *val_angular_velocity_covariancei |= ((exp_angular_velocity_covariancei)-1023+127)<<23; |
nucho | 0:06fc856e99ca | 119 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->angular_velocity_covariance[i] = -this->angular_velocity_covariance[i]; |
nucho | 0:06fc856e99ca | 120 | } |
nucho | 0:06fc856e99ca | 121 | offset += this->linear_acceleration.deserialize(inbuffer + offset); |
nucho | 3:dff241b66f84 | 122 | uint8_t * linear_acceleration_covariance_val = (uint8_t*) this->linear_acceleration_covariance; |
nucho | 3:dff241b66f84 | 123 | for( uint8_t i = 0; i < 9; i++){ |
nucho | 3:dff241b66f84 | 124 | uint32_t * val_linear_acceleration_covariancei = (uint32_t*) &(this->linear_acceleration_covariance[i]); |
nucho | 0:06fc856e99ca | 125 | offset += 3; |
nucho | 3:dff241b66f84 | 126 | *val_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 3:dff241b66f84 | 127 | *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 3:dff241b66f84 | 128 | *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 3:dff241b66f84 | 129 | *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 3:dff241b66f84 | 130 | uint32_t exp_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 3:dff241b66f84 | 131 | exp_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:06fc856e99ca | 132 | if(exp_linear_acceleration_covariancei !=0) |
nucho | 0:06fc856e99ca | 133 | *val_linear_acceleration_covariancei |= ((exp_linear_acceleration_covariancei)-1023+127)<<23; |
nucho | 0:06fc856e99ca | 134 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->linear_acceleration_covariance[i] = -this->linear_acceleration_covariance[i]; |
nucho | 0:06fc856e99ca | 135 | } |
nucho | 0:06fc856e99ca | 136 | return offset; |
nucho | 0:06fc856e99ca | 137 | } |
nucho | 0:06fc856e99ca | 138 | |
nucho | 3:dff241b66f84 | 139 | virtual const char * getType(){ return "sensor_msgs/Imu"; }; |
nucho | 3:dff241b66f84 | 140 | virtual const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; }; |
nucho | 0:06fc856e99ca | 141 | |
nucho | 0:06fc856e99ca | 142 | }; |
nucho | 0:06fc856e99ca | 143 | |
nucho | 0:06fc856e99ca | 144 | } |
nucho | 0:06fc856e99ca | 145 | #endif |