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 Inertia.h Source File

Inertia.h

00001 #ifndef _ROS_geometry_msgs_Inertia_h
00002 #define _ROS_geometry_msgs_Inertia_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "geometry_msgs/Vector3.h"
00009 
00010 namespace geometry_msgs
00011 {
00012 
00013   class Inertia : public ros::Msg
00014   {
00015     public:
00016       double m;
00017       geometry_msgs::Vector3 com;
00018       double ixx;
00019       double ixy;
00020       double ixz;
00021       double iyy;
00022       double iyz;
00023       double izz;
00024 
00025     Inertia():
00026       m(0),
00027       com(),
00028       ixx(0),
00029       ixy(0),
00030       ixz(0),
00031       iyy(0),
00032       iyz(0),
00033       izz(0)
00034     {
00035     }
00036 
00037     virtual int serialize(unsigned char *outbuffer) const
00038     {
00039       int offset = 0;
00040       union {
00041         double real;
00042         uint64_t base;
00043       } u_m;
00044       u_m.real = this->m;
00045       *(outbuffer + offset + 0) = (u_m.base >> (8 * 0)) & 0xFF;
00046       *(outbuffer + offset + 1) = (u_m.base >> (8 * 1)) & 0xFF;
00047       *(outbuffer + offset + 2) = (u_m.base >> (8 * 2)) & 0xFF;
00048       *(outbuffer + offset + 3) = (u_m.base >> (8 * 3)) & 0xFF;
00049       *(outbuffer + offset + 4) = (u_m.base >> (8 * 4)) & 0xFF;
00050       *(outbuffer + offset + 5) = (u_m.base >> (8 * 5)) & 0xFF;
00051       *(outbuffer + offset + 6) = (u_m.base >> (8 * 6)) & 0xFF;
00052       *(outbuffer + offset + 7) = (u_m.base >> (8 * 7)) & 0xFF;
00053       offset += sizeof(this->m);
00054       offset += this->com.serialize(outbuffer + offset);
00055       union {
00056         double real;
00057         uint64_t base;
00058       } u_ixx;
00059       u_ixx.real = this->ixx;
00060       *(outbuffer + offset + 0) = (u_ixx.base >> (8 * 0)) & 0xFF;
00061       *(outbuffer + offset + 1) = (u_ixx.base >> (8 * 1)) & 0xFF;
00062       *(outbuffer + offset + 2) = (u_ixx.base >> (8 * 2)) & 0xFF;
00063       *(outbuffer + offset + 3) = (u_ixx.base >> (8 * 3)) & 0xFF;
00064       *(outbuffer + offset + 4) = (u_ixx.base >> (8 * 4)) & 0xFF;
00065       *(outbuffer + offset + 5) = (u_ixx.base >> (8 * 5)) & 0xFF;
00066       *(outbuffer + offset + 6) = (u_ixx.base >> (8 * 6)) & 0xFF;
00067       *(outbuffer + offset + 7) = (u_ixx.base >> (8 * 7)) & 0xFF;
00068       offset += sizeof(this->ixx);
00069       union {
00070         double real;
00071         uint64_t base;
00072       } u_ixy;
00073       u_ixy.real = this->ixy;
00074       *(outbuffer + offset + 0) = (u_ixy.base >> (8 * 0)) & 0xFF;
00075       *(outbuffer + offset + 1) = (u_ixy.base >> (8 * 1)) & 0xFF;
00076       *(outbuffer + offset + 2) = (u_ixy.base >> (8 * 2)) & 0xFF;
00077       *(outbuffer + offset + 3) = (u_ixy.base >> (8 * 3)) & 0xFF;
00078       *(outbuffer + offset + 4) = (u_ixy.base >> (8 * 4)) & 0xFF;
00079       *(outbuffer + offset + 5) = (u_ixy.base >> (8 * 5)) & 0xFF;
00080       *(outbuffer + offset + 6) = (u_ixy.base >> (8 * 6)) & 0xFF;
00081       *(outbuffer + offset + 7) = (u_ixy.base >> (8 * 7)) & 0xFF;
00082       offset += sizeof(this->ixy);
00083       union {
00084         double real;
00085         uint64_t base;
00086       } u_ixz;
00087       u_ixz.real = this->ixz;
00088       *(outbuffer + offset + 0) = (u_ixz.base >> (8 * 0)) & 0xFF;
00089       *(outbuffer + offset + 1) = (u_ixz.base >> (8 * 1)) & 0xFF;
00090       *(outbuffer + offset + 2) = (u_ixz.base >> (8 * 2)) & 0xFF;
00091       *(outbuffer + offset + 3) = (u_ixz.base >> (8 * 3)) & 0xFF;
00092       *(outbuffer + offset + 4) = (u_ixz.base >> (8 * 4)) & 0xFF;
00093       *(outbuffer + offset + 5) = (u_ixz.base >> (8 * 5)) & 0xFF;
00094       *(outbuffer + offset + 6) = (u_ixz.base >> (8 * 6)) & 0xFF;
00095       *(outbuffer + offset + 7) = (u_ixz.base >> (8 * 7)) & 0xFF;
00096       offset += sizeof(this->ixz);
00097       union {
00098         double real;
00099         uint64_t base;
00100       } u_iyy;
00101       u_iyy.real = this->iyy;
00102       *(outbuffer + offset + 0) = (u_iyy.base >> (8 * 0)) & 0xFF;
00103       *(outbuffer + offset + 1) = (u_iyy.base >> (8 * 1)) & 0xFF;
00104       *(outbuffer + offset + 2) = (u_iyy.base >> (8 * 2)) & 0xFF;
00105       *(outbuffer + offset + 3) = (u_iyy.base >> (8 * 3)) & 0xFF;
00106       *(outbuffer + offset + 4) = (u_iyy.base >> (8 * 4)) & 0xFF;
00107       *(outbuffer + offset + 5) = (u_iyy.base >> (8 * 5)) & 0xFF;
00108       *(outbuffer + offset + 6) = (u_iyy.base >> (8 * 6)) & 0xFF;
00109       *(outbuffer + offset + 7) = (u_iyy.base >> (8 * 7)) & 0xFF;
00110       offset += sizeof(this->iyy);
00111       union {
00112         double real;
00113         uint64_t base;
00114       } u_iyz;
00115       u_iyz.real = this->iyz;
00116       *(outbuffer + offset + 0) = (u_iyz.base >> (8 * 0)) & 0xFF;
00117       *(outbuffer + offset + 1) = (u_iyz.base >> (8 * 1)) & 0xFF;
00118       *(outbuffer + offset + 2) = (u_iyz.base >> (8 * 2)) & 0xFF;
00119       *(outbuffer + offset + 3) = (u_iyz.base >> (8 * 3)) & 0xFF;
00120       *(outbuffer + offset + 4) = (u_iyz.base >> (8 * 4)) & 0xFF;
00121       *(outbuffer + offset + 5) = (u_iyz.base >> (8 * 5)) & 0xFF;
00122       *(outbuffer + offset + 6) = (u_iyz.base >> (8 * 6)) & 0xFF;
00123       *(outbuffer + offset + 7) = (u_iyz.base >> (8 * 7)) & 0xFF;
00124       offset += sizeof(this->iyz);
00125       union {
00126         double real;
00127         uint64_t base;
00128       } u_izz;
00129       u_izz.real = this->izz;
00130       *(outbuffer + offset + 0) = (u_izz.base >> (8 * 0)) & 0xFF;
00131       *(outbuffer + offset + 1) = (u_izz.base >> (8 * 1)) & 0xFF;
00132       *(outbuffer + offset + 2) = (u_izz.base >> (8 * 2)) & 0xFF;
00133       *(outbuffer + offset + 3) = (u_izz.base >> (8 * 3)) & 0xFF;
00134       *(outbuffer + offset + 4) = (u_izz.base >> (8 * 4)) & 0xFF;
00135       *(outbuffer + offset + 5) = (u_izz.base >> (8 * 5)) & 0xFF;
00136       *(outbuffer + offset + 6) = (u_izz.base >> (8 * 6)) & 0xFF;
00137       *(outbuffer + offset + 7) = (u_izz.base >> (8 * 7)) & 0xFF;
00138       offset += sizeof(this->izz);
00139       return offset;
00140     }
00141 
00142     virtual int deserialize(unsigned char *inbuffer)
00143     {
00144       int offset = 0;
00145       union {
00146         double real;
00147         uint64_t base;
00148       } u_m;
00149       u_m.base = 0;
00150       u_m.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00151       u_m.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00152       u_m.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00153       u_m.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00154       u_m.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00155       u_m.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00156       u_m.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00157       u_m.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00158       this->m = u_m.real;
00159       offset += sizeof(this->m);
00160       offset += this->com.deserialize(inbuffer + offset);
00161       union {
00162         double real;
00163         uint64_t base;
00164       } u_ixx;
00165       u_ixx.base = 0;
00166       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00167       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00168       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00169       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00170       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00171       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00172       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00173       u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00174       this->ixx = u_ixx.real;
00175       offset += sizeof(this->ixx);
00176       union {
00177         double real;
00178         uint64_t base;
00179       } u_ixy;
00180       u_ixy.base = 0;
00181       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00182       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00183       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00184       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00185       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00186       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00187       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00188       u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00189       this->ixy = u_ixy.real;
00190       offset += sizeof(this->ixy);
00191       union {
00192         double real;
00193         uint64_t base;
00194       } u_ixz;
00195       u_ixz.base = 0;
00196       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00197       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00198       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00199       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00200       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00201       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00202       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00203       u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00204       this->ixz = u_ixz.real;
00205       offset += sizeof(this->ixz);
00206       union {
00207         double real;
00208         uint64_t base;
00209       } u_iyy;
00210       u_iyy.base = 0;
00211       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00212       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00213       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00214       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00215       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00216       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00217       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00218       u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00219       this->iyy = u_iyy.real;
00220       offset += sizeof(this->iyy);
00221       union {
00222         double real;
00223         uint64_t base;
00224       } u_iyz;
00225       u_iyz.base = 0;
00226       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00227       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00228       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00229       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00230       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00231       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00232       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00233       u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00234       this->iyz = u_iyz.real;
00235       offset += sizeof(this->iyz);
00236       union {
00237         double real;
00238         uint64_t base;
00239       } u_izz;
00240       u_izz.base = 0;
00241       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00242       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00243       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00244       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00245       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00246       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00247       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00248       u_izz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00249       this->izz = u_izz.real;
00250       offset += sizeof(this->izz);
00251      return offset;
00252     }
00253 
00254     const char * getType(){ return "geometry_msgs/Inertia"; };
00255     const char * getMD5(){ return "1d26e4bb6c83ff141c5cf0d883c2b0fe"; };
00256 
00257   };
00258 
00259 }
00260 #endif