Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h

Dependencies:   BufferedSerial

Dependents:   WRS2020_mecanum_node

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers Imu.h Source File

Imu.h

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       typedef std_msgs::Header _header_type;
00019       _header_type header;
00020       typedef geometry_msgs::Quaternion _orientation_type;
00021       _orientation_type orientation;
00022       double orientation_covariance[9];
00023       typedef geometry_msgs::Vector3 _angular_velocity_type;
00024       _angular_velocity_type angular_velocity;
00025       double angular_velocity_covariance[9];
00026       typedef geometry_msgs::Vector3 _linear_acceleration_type;
00027       _linear_acceleration_type linear_acceleration;
00028       double linear_acceleration_covariance[9];
00029 
00030     Imu():
00031       header(),
00032       orientation(),
00033       orientation_covariance(),
00034       angular_velocity(),
00035       angular_velocity_covariance(),
00036       linear_acceleration(),
00037       linear_acceleration_covariance()
00038     {
00039     }
00040 
00041     virtual int serialize(unsigned char *outbuffer) const
00042     {
00043       int offset = 0;
00044       offset += this->header.serialize(outbuffer + offset);
00045       offset += this->orientation.serialize(outbuffer + offset);
00046       for( uint32_t i = 0; i < 9; i++){
00047       union {
00048         double real;
00049         uint64_t base;
00050       } u_orientation_covariancei;
00051       u_orientation_covariancei.real = this->orientation_covariance[i];
00052       *(outbuffer + offset + 0) = (u_orientation_covariancei.base >> (8 * 0)) & 0xFF;
00053       *(outbuffer + offset + 1) = (u_orientation_covariancei.base >> (8 * 1)) & 0xFF;
00054       *(outbuffer + offset + 2) = (u_orientation_covariancei.base >> (8 * 2)) & 0xFF;
00055       *(outbuffer + offset + 3) = (u_orientation_covariancei.base >> (8 * 3)) & 0xFF;
00056       *(outbuffer + offset + 4) = (u_orientation_covariancei.base >> (8 * 4)) & 0xFF;
00057       *(outbuffer + offset + 5) = (u_orientation_covariancei.base >> (8 * 5)) & 0xFF;
00058       *(outbuffer + offset + 6) = (u_orientation_covariancei.base >> (8 * 6)) & 0xFF;
00059       *(outbuffer + offset + 7) = (u_orientation_covariancei.base >> (8 * 7)) & 0xFF;
00060       offset += sizeof(this->orientation_covariance[i]);
00061       }
00062       offset += this->angular_velocity.serialize(outbuffer + offset);
00063       for( uint32_t i = 0; i < 9; i++){
00064       union {
00065         double real;
00066         uint64_t base;
00067       } u_angular_velocity_covariancei;
00068       u_angular_velocity_covariancei.real = this->angular_velocity_covariance[i];
00069       *(outbuffer + offset + 0) = (u_angular_velocity_covariancei.base >> (8 * 0)) & 0xFF;
00070       *(outbuffer + offset + 1) = (u_angular_velocity_covariancei.base >> (8 * 1)) & 0xFF;
00071       *(outbuffer + offset + 2) = (u_angular_velocity_covariancei.base >> (8 * 2)) & 0xFF;
00072       *(outbuffer + offset + 3) = (u_angular_velocity_covariancei.base >> (8 * 3)) & 0xFF;
00073       *(outbuffer + offset + 4) = (u_angular_velocity_covariancei.base >> (8 * 4)) & 0xFF;
00074       *(outbuffer + offset + 5) = (u_angular_velocity_covariancei.base >> (8 * 5)) & 0xFF;
00075       *(outbuffer + offset + 6) = (u_angular_velocity_covariancei.base >> (8 * 6)) & 0xFF;
00076       *(outbuffer + offset + 7) = (u_angular_velocity_covariancei.base >> (8 * 7)) & 0xFF;
00077       offset += sizeof(this->angular_velocity_covariance[i]);
00078       }
00079       offset += this->linear_acceleration.serialize(outbuffer + offset);
00080       for( uint32_t i = 0; i < 9; i++){
00081       union {
00082         double real;
00083         uint64_t base;
00084       } u_linear_acceleration_covariancei;
00085       u_linear_acceleration_covariancei.real = this->linear_acceleration_covariance[i];
00086       *(outbuffer + offset + 0) = (u_linear_acceleration_covariancei.base >> (8 * 0)) & 0xFF;
00087       *(outbuffer + offset + 1) = (u_linear_acceleration_covariancei.base >> (8 * 1)) & 0xFF;
00088       *(outbuffer + offset + 2) = (u_linear_acceleration_covariancei.base >> (8 * 2)) & 0xFF;
00089       *(outbuffer + offset + 3) = (u_linear_acceleration_covariancei.base >> (8 * 3)) & 0xFF;
00090       *(outbuffer + offset + 4) = (u_linear_acceleration_covariancei.base >> (8 * 4)) & 0xFF;
00091       *(outbuffer + offset + 5) = (u_linear_acceleration_covariancei.base >> (8 * 5)) & 0xFF;
00092       *(outbuffer + offset + 6) = (u_linear_acceleration_covariancei.base >> (8 * 6)) & 0xFF;
00093       *(outbuffer + offset + 7) = (u_linear_acceleration_covariancei.base >> (8 * 7)) & 0xFF;
00094       offset += sizeof(this->linear_acceleration_covariance[i]);
00095       }
00096       return offset;
00097     }
00098 
00099     virtual int deserialize(unsigned char *inbuffer)
00100     {
00101       int offset = 0;
00102       offset += this->header.deserialize(inbuffer + offset);
00103       offset += this->orientation.deserialize(inbuffer + offset);
00104       for( uint32_t i = 0; i < 9; i++){
00105       union {
00106         double real;
00107         uint64_t base;
00108       } u_orientation_covariancei;
00109       u_orientation_covariancei.base = 0;
00110       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00111       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00112       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00113       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00114       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00115       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00116       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00117       u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00118       this->orientation_covariance[i] = u_orientation_covariancei.real;
00119       offset += sizeof(this->orientation_covariance[i]);
00120       }
00121       offset += this->angular_velocity.deserialize(inbuffer + offset);
00122       for( uint32_t i = 0; i < 9; i++){
00123       union {
00124         double real;
00125         uint64_t base;
00126       } u_angular_velocity_covariancei;
00127       u_angular_velocity_covariancei.base = 0;
00128       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00129       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00130       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00131       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00132       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00133       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00134       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00135       u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00136       this->angular_velocity_covariance[i] = u_angular_velocity_covariancei.real;
00137       offset += sizeof(this->angular_velocity_covariance[i]);
00138       }
00139       offset += this->linear_acceleration.deserialize(inbuffer + offset);
00140       for( uint32_t i = 0; i < 9; i++){
00141       union {
00142         double real;
00143         uint64_t base;
00144       } u_linear_acceleration_covariancei;
00145       u_linear_acceleration_covariancei.base = 0;
00146       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00147       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00148       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00149       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00150       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00151       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00152       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00153       u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00154       this->linear_acceleration_covariance[i] = u_linear_acceleration_covariancei.real;
00155       offset += sizeof(this->linear_acceleration_covariance[i]);
00156       }
00157      return offset;
00158     }
00159 
00160     const char * getType(){ return "sensor_msgs/Imu"; };
00161     const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; };
00162 
00163   };
00164 
00165 }
00166 #endif