Imu.h
Go to the documentation of this file.
00001 #ifndef _ROS_sensor_msgs_Imu_h
00002 #define _ROS_sensor_msgs_Imu_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "geometry_msgs/Quaternion.h"
00010 #include "geometry_msgs/Vector3.h"
00011 
00012 namespace sensor_msgs
00013 {
00014 
00015   class Imu : public ros::Msg
00016   {
00017     public:
00018       std_msgs::Header header;
00019       geometry_msgs::Quaternion orientation;
00020       float orientation_covariance[9];
00021       geometry_msgs::Vector3 angular_velocity;
00022       float angular_velocity_covariance[9];
00023       geometry_msgs::Vector3 linear_acceleration;
00024       float linear_acceleration_covariance[9];
00025 
00026     virtual int serialize(unsigned char *outbuffer) const
00027     {
00028       int offset = 0;
00029       offset += this->header.serialize(outbuffer + offset);
00030       offset += this->orientation.serialize(outbuffer + offset);
00031       for( uint8_t i = 0; i < 9; i++){
00032       int32_t * val_orientation_covariancei = (int32_t *) &(this->orientation_covariance[i]);
00033       int32_t exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255);
00034       if(exp_orientation_covariancei != 0)
00035         exp_orientation_covariancei += 1023-127;
00036       int32_t sig_orientation_covariancei = *val_orientation_covariancei;
00037       *(outbuffer + offset++) = 0;
00038       *(outbuffer + offset++) = 0;
00039       *(outbuffer + offset++) = 0;
00040       *(outbuffer + offset++) = (sig_orientation_covariancei<<5) & 0xff;
00041       *(outbuffer + offset++) = (sig_orientation_covariancei>>3) & 0xff;
00042       *(outbuffer + offset++) = (sig_orientation_covariancei>>11) & 0xff;
00043       *(outbuffer + offset++) = ((exp_orientation_covariancei<<4) & 0xF0) | ((sig_orientation_covariancei>>19)&0x0F);
00044       *(outbuffer + offset++) = (exp_orientation_covariancei>>4) & 0x7F;
00045       if(this->orientation_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
00046       }
00047       offset += this->angular_velocity.serialize(outbuffer + offset);
00048       for( uint8_t i = 0; i < 9; i++){
00049       int32_t * val_angular_velocity_covariancei = (int32_t *) &(this->angular_velocity_covariance[i]);
00050       int32_t exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255);
00051       if(exp_angular_velocity_covariancei != 0)
00052         exp_angular_velocity_covariancei += 1023-127;
00053       int32_t sig_angular_velocity_covariancei = *val_angular_velocity_covariancei;
00054       *(outbuffer + offset++) = 0;
00055       *(outbuffer + offset++) = 0;
00056       *(outbuffer + offset++) = 0;
00057       *(outbuffer + offset++) = (sig_angular_velocity_covariancei<<5) & 0xff;
00058       *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>3) & 0xff;
00059       *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>11) & 0xff;
00060       *(outbuffer + offset++) = ((exp_angular_velocity_covariancei<<4) & 0xF0) | ((sig_angular_velocity_covariancei>>19)&0x0F);
00061       *(outbuffer + offset++) = (exp_angular_velocity_covariancei>>4) & 0x7F;
00062       if(this->angular_velocity_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
00063       }
00064       offset += this->linear_acceleration.serialize(outbuffer + offset);
00065       for( uint8_t i = 0; i < 9; i++){
00066       int32_t * val_linear_acceleration_covariancei = (int32_t *) &(this->linear_acceleration_covariance[i]);
00067       int32_t exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255);
00068       if(exp_linear_acceleration_covariancei != 0)
00069         exp_linear_acceleration_covariancei += 1023-127;
00070       int32_t sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei;
00071       *(outbuffer + offset++) = 0;
00072       *(outbuffer + offset++) = 0;
00073       *(outbuffer + offset++) = 0;
00074       *(outbuffer + offset++) = (sig_linear_acceleration_covariancei<<5) & 0xff;
00075       *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>3) & 0xff;
00076       *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>11) & 0xff;
00077       *(outbuffer + offset++) = ((exp_linear_acceleration_covariancei<<4) & 0xF0) | ((sig_linear_acceleration_covariancei>>19)&0x0F);
00078       *(outbuffer + offset++) = (exp_linear_acceleration_covariancei>>4) & 0x7F;
00079       if(this->linear_acceleration_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
00080       }
00081       return offset;
00082     }
00083 
00084     virtual int deserialize(unsigned char *inbuffer)
00085     {
00086       int offset = 0;
00087       offset += this->header.deserialize(inbuffer + offset);
00088       offset += this->orientation.deserialize(inbuffer + offset);
00089       for( uint8_t i = 0; i < 9; i++){
00090       uint32_t * val_orientation_covariancei = (uint32_t*) &(this->orientation_covariance[i]);
00091       offset += 3;
00092       *val_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00093       *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00094       *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00095       *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00096       uint32_t exp_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00097       exp_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00098       if(exp_orientation_covariancei !=0)
00099         *val_orientation_covariancei |= ((exp_orientation_covariancei)-1023+127)<<23;
00100       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->orientation_covariance[i] = -this->orientation_covariance[i];
00101       }
00102       offset += this->angular_velocity.deserialize(inbuffer + offset);
00103       for( uint8_t i = 0; i < 9; i++){
00104       uint32_t * val_angular_velocity_covariancei = (uint32_t*) &(this->angular_velocity_covariance[i]);
00105       offset += 3;
00106       *val_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00107       *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00108       *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00109       *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00110       uint32_t exp_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00111       exp_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00112       if(exp_angular_velocity_covariancei !=0)
00113         *val_angular_velocity_covariancei |= ((exp_angular_velocity_covariancei)-1023+127)<<23;
00114       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->angular_velocity_covariance[i] = -this->angular_velocity_covariance[i];
00115       }
00116       offset += this->linear_acceleration.deserialize(inbuffer + offset);
00117       for( uint8_t i = 0; i < 9; i++){
00118       uint32_t * val_linear_acceleration_covariancei = (uint32_t*) &(this->linear_acceleration_covariance[i]);
00119       offset += 3;
00120       *val_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00121       *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00122       *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00123       *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00124       uint32_t exp_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00125       exp_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00126       if(exp_linear_acceleration_covariancei !=0)
00127         *val_linear_acceleration_covariancei |= ((exp_linear_acceleration_covariancei)-1023+127)<<23;
00128       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->linear_acceleration_covariance[i] = -this->linear_acceleration_covariance[i];
00129       }
00130      return offset;
00131     }
00132 
00133     const char * getType(){ return "sensor_msgs/Imu"; };
00134     const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; };
00135 
00136   };
00137 
00138 }
00139 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Fri May 20 2016 03:48:55