ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

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