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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more

ROSSerial_mbed for Melodic Distribution

The Robot Operating System (ROS) is a flexible framework for writing robot software. It is a collection of tools, libraries, and conventions that aim to simplify the task of creating complex and robust robot behavior across a wide variety of robotic platforms.

The rosserial_mbed package allows to write ROS nodes on any mbed enabled devices and have them connected to a running ROS system on your computer using the serial port.

Hello World (example publisher)

Import programrosserial_mbed_hello_world_publisher_melodic

rosserial_mbed Hello World example for Melodic Morenia distribution

Running the Code

Now, launch the roscore in a new terminal window:

Quote:

$ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

Quote:

$ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

Quote:

$ rostopic echo chatter

See Also

More examples

Blink

/*
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle nh;
DigitalOut myled(LED1);

void messageCb(const std_msgs::Empty& toggle_msg){
    myled = !myled;   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);

    while (1) {
        nh.spinOnce();
        wait_ms(1);
    }
}

Push

/*
 * Button Example for Rosserial
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Bool.h>

PinName button = p20;

ros::NodeHandle nh;

std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);

DigitalIn button_pin(button);
DigitalOut led_pin(LED1);

bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;

Timer t;
int main() {
    t.start();
    nh.initNode();
    nh.advertise(pub_button);

    //Enable the pullup resistor on the button
    button_pin.mode(PullUp);

    //The button is a normally button
    last_reading = ! button_pin;

    while (1) {
        bool reading = ! button_pin;

        if (last_reading!= reading) {
            last_debounce_time = t.read_ms();
            published = false;
        }

        //if the button value has not changed for the debounce delay, we know its stable
        if ( !published && (t.read_ms() - last_debounce_time)  > debounce_delay) {
            led_pin = reading;
            pushed_msg.data = reading;
            pub_button.publish(&pushed_msg);
            published = true;
        }

        last_reading = reading;

        nh.spinOnce();
    }
}
Committer:
Gary Servin
Date:
Fri Nov 08 14:55:04 2019 -0300
Revision:
1:da82487f547e
Parent:
0:04ac6be8229a
Add missing round() method

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_geometry_msgs_Inertia_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_geometry_msgs_Inertia_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "geometry_msgs/Vector3.h"
Gary Servin 0:04ac6be8229a 9
Gary Servin 0:04ac6be8229a 10 namespace geometry_msgs
Gary Servin 0:04ac6be8229a 11 {
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 class Inertia : public ros::Msg
Gary Servin 0:04ac6be8229a 14 {
Gary Servin 0:04ac6be8229a 15 public:
Gary Servin 0:04ac6be8229a 16 typedef double _m_type;
Gary Servin 0:04ac6be8229a 17 _m_type m;
Gary Servin 0:04ac6be8229a 18 typedef geometry_msgs::Vector3 _com_type;
Gary Servin 0:04ac6be8229a 19 _com_type com;
Gary Servin 0:04ac6be8229a 20 typedef double _ixx_type;
Gary Servin 0:04ac6be8229a 21 _ixx_type ixx;
Gary Servin 0:04ac6be8229a 22 typedef double _ixy_type;
Gary Servin 0:04ac6be8229a 23 _ixy_type ixy;
Gary Servin 0:04ac6be8229a 24 typedef double _ixz_type;
Gary Servin 0:04ac6be8229a 25 _ixz_type ixz;
Gary Servin 0:04ac6be8229a 26 typedef double _iyy_type;
Gary Servin 0:04ac6be8229a 27 _iyy_type iyy;
Gary Servin 0:04ac6be8229a 28 typedef double _iyz_type;
Gary Servin 0:04ac6be8229a 29 _iyz_type iyz;
Gary Servin 0:04ac6be8229a 30 typedef double _izz_type;
Gary Servin 0:04ac6be8229a 31 _izz_type izz;
Gary Servin 0:04ac6be8229a 32
Gary Servin 0:04ac6be8229a 33 Inertia():
Gary Servin 0:04ac6be8229a 34 m(0),
Gary Servin 0:04ac6be8229a 35 com(),
Gary Servin 0:04ac6be8229a 36 ixx(0),
Gary Servin 0:04ac6be8229a 37 ixy(0),
Gary Servin 0:04ac6be8229a 38 ixz(0),
Gary Servin 0:04ac6be8229a 39 iyy(0),
Gary Servin 0:04ac6be8229a 40 iyz(0),
Gary Servin 0:04ac6be8229a 41 izz(0)
Gary Servin 0:04ac6be8229a 42 {
Gary Servin 0:04ac6be8229a 43 }
Gary Servin 0:04ac6be8229a 44
Gary Servin 0:04ac6be8229a 45 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 46 {
Gary Servin 0:04ac6be8229a 47 int offset = 0;
Gary Servin 0:04ac6be8229a 48 union {
Gary Servin 0:04ac6be8229a 49 double real;
Gary Servin 0:04ac6be8229a 50 uint64_t base;
Gary Servin 0:04ac6be8229a 51 } u_m;
Gary Servin 0:04ac6be8229a 52 u_m.real = this->m;
Gary Servin 0:04ac6be8229a 53 *(outbuffer + offset + 0) = (u_m.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 54 *(outbuffer + offset + 1) = (u_m.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 55 *(outbuffer + offset + 2) = (u_m.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 56 *(outbuffer + offset + 3) = (u_m.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 57 *(outbuffer + offset + 4) = (u_m.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 58 *(outbuffer + offset + 5) = (u_m.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 59 *(outbuffer + offset + 6) = (u_m.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 60 *(outbuffer + offset + 7) = (u_m.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 61 offset += sizeof(this->m);
Gary Servin 0:04ac6be8229a 62 offset += this->com.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 63 union {
Gary Servin 0:04ac6be8229a 64 double real;
Gary Servin 0:04ac6be8229a 65 uint64_t base;
Gary Servin 0:04ac6be8229a 66 } u_ixx;
Gary Servin 0:04ac6be8229a 67 u_ixx.real = this->ixx;
Gary Servin 0:04ac6be8229a 68 *(outbuffer + offset + 0) = (u_ixx.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 69 *(outbuffer + offset + 1) = (u_ixx.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 70 *(outbuffer + offset + 2) = (u_ixx.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 71 *(outbuffer + offset + 3) = (u_ixx.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 72 *(outbuffer + offset + 4) = (u_ixx.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 73 *(outbuffer + offset + 5) = (u_ixx.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 74 *(outbuffer + offset + 6) = (u_ixx.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 75 *(outbuffer + offset + 7) = (u_ixx.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 76 offset += sizeof(this->ixx);
Gary Servin 0:04ac6be8229a 77 union {
Gary Servin 0:04ac6be8229a 78 double real;
Gary Servin 0:04ac6be8229a 79 uint64_t base;
Gary Servin 0:04ac6be8229a 80 } u_ixy;
Gary Servin 0:04ac6be8229a 81 u_ixy.real = this->ixy;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 0) = (u_ixy.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 *(outbuffer + offset + 1) = (u_ixy.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 84 *(outbuffer + offset + 2) = (u_ixy.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 85 *(outbuffer + offset + 3) = (u_ixy.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 86 *(outbuffer + offset + 4) = (u_ixy.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 87 *(outbuffer + offset + 5) = (u_ixy.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 88 *(outbuffer + offset + 6) = (u_ixy.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 89 *(outbuffer + offset + 7) = (u_ixy.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 90 offset += sizeof(this->ixy);
Gary Servin 0:04ac6be8229a 91 union {
Gary Servin 0:04ac6be8229a 92 double real;
Gary Servin 0:04ac6be8229a 93 uint64_t base;
Gary Servin 0:04ac6be8229a 94 } u_ixz;
Gary Servin 0:04ac6be8229a 95 u_ixz.real = this->ixz;
Gary Servin 0:04ac6be8229a 96 *(outbuffer + offset + 0) = (u_ixz.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 97 *(outbuffer + offset + 1) = (u_ixz.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 98 *(outbuffer + offset + 2) = (u_ixz.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 99 *(outbuffer + offset + 3) = (u_ixz.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 100 *(outbuffer + offset + 4) = (u_ixz.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 101 *(outbuffer + offset + 5) = (u_ixz.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 102 *(outbuffer + offset + 6) = (u_ixz.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 103 *(outbuffer + offset + 7) = (u_ixz.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 104 offset += sizeof(this->ixz);
Gary Servin 0:04ac6be8229a 105 union {
Gary Servin 0:04ac6be8229a 106 double real;
Gary Servin 0:04ac6be8229a 107 uint64_t base;
Gary Servin 0:04ac6be8229a 108 } u_iyy;
Gary Servin 0:04ac6be8229a 109 u_iyy.real = this->iyy;
Gary Servin 0:04ac6be8229a 110 *(outbuffer + offset + 0) = (u_iyy.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 111 *(outbuffer + offset + 1) = (u_iyy.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 112 *(outbuffer + offset + 2) = (u_iyy.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 113 *(outbuffer + offset + 3) = (u_iyy.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 114 *(outbuffer + offset + 4) = (u_iyy.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 115 *(outbuffer + offset + 5) = (u_iyy.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 116 *(outbuffer + offset + 6) = (u_iyy.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 117 *(outbuffer + offset + 7) = (u_iyy.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 118 offset += sizeof(this->iyy);
Gary Servin 0:04ac6be8229a 119 union {
Gary Servin 0:04ac6be8229a 120 double real;
Gary Servin 0:04ac6be8229a 121 uint64_t base;
Gary Servin 0:04ac6be8229a 122 } u_iyz;
Gary Servin 0:04ac6be8229a 123 u_iyz.real = this->iyz;
Gary Servin 0:04ac6be8229a 124 *(outbuffer + offset + 0) = (u_iyz.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 125 *(outbuffer + offset + 1) = (u_iyz.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 126 *(outbuffer + offset + 2) = (u_iyz.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 127 *(outbuffer + offset + 3) = (u_iyz.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 128 *(outbuffer + offset + 4) = (u_iyz.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 129 *(outbuffer + offset + 5) = (u_iyz.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 130 *(outbuffer + offset + 6) = (u_iyz.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 131 *(outbuffer + offset + 7) = (u_iyz.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 132 offset += sizeof(this->iyz);
Gary Servin 0:04ac6be8229a 133 union {
Gary Servin 0:04ac6be8229a 134 double real;
Gary Servin 0:04ac6be8229a 135 uint64_t base;
Gary Servin 0:04ac6be8229a 136 } u_izz;
Gary Servin 0:04ac6be8229a 137 u_izz.real = this->izz;
Gary Servin 0:04ac6be8229a 138 *(outbuffer + offset + 0) = (u_izz.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 139 *(outbuffer + offset + 1) = (u_izz.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 140 *(outbuffer + offset + 2) = (u_izz.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 141 *(outbuffer + offset + 3) = (u_izz.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 142 *(outbuffer + offset + 4) = (u_izz.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 143 *(outbuffer + offset + 5) = (u_izz.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 144 *(outbuffer + offset + 6) = (u_izz.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 145 *(outbuffer + offset + 7) = (u_izz.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 146 offset += sizeof(this->izz);
Gary Servin 0:04ac6be8229a 147 return offset;
Gary Servin 0:04ac6be8229a 148 }
Gary Servin 0:04ac6be8229a 149
Gary Servin 0:04ac6be8229a 150 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 151 {
Gary Servin 0:04ac6be8229a 152 int offset = 0;
Gary Servin 0:04ac6be8229a 153 union {
Gary Servin 0:04ac6be8229a 154 double real;
Gary Servin 0:04ac6be8229a 155 uint64_t base;
Gary Servin 0:04ac6be8229a 156 } u_m;
Gary Servin 0:04ac6be8229a 157 u_m.base = 0;
Gary Servin 0:04ac6be8229a 158 u_m.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 159 u_m.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 160 u_m.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 161 u_m.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 162 u_m.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 163 u_m.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 164 u_m.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 165 u_m.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 166 this->m = u_m.real;
Gary Servin 0:04ac6be8229a 167 offset += sizeof(this->m);
Gary Servin 0:04ac6be8229a 168 offset += this->com.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 169 union {
Gary Servin 0:04ac6be8229a 170 double real;
Gary Servin 0:04ac6be8229a 171 uint64_t base;
Gary Servin 0:04ac6be8229a 172 } u_ixx;
Gary Servin 0:04ac6be8229a 173 u_ixx.base = 0;
Gary Servin 0:04ac6be8229a 174 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 175 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 176 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 177 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 178 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 179 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 180 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 181 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 182 this->ixx = u_ixx.real;
Gary Servin 0:04ac6be8229a 183 offset += sizeof(this->ixx);
Gary Servin 0:04ac6be8229a 184 union {
Gary Servin 0:04ac6be8229a 185 double real;
Gary Servin 0:04ac6be8229a 186 uint64_t base;
Gary Servin 0:04ac6be8229a 187 } u_ixy;
Gary Servin 0:04ac6be8229a 188 u_ixy.base = 0;
Gary Servin 0:04ac6be8229a 189 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 190 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 191 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 192 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 193 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 194 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 195 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 196 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 197 this->ixy = u_ixy.real;
Gary Servin 0:04ac6be8229a 198 offset += sizeof(this->ixy);
Gary Servin 0:04ac6be8229a 199 union {
Gary Servin 0:04ac6be8229a 200 double real;
Gary Servin 0:04ac6be8229a 201 uint64_t base;
Gary Servin 0:04ac6be8229a 202 } u_ixz;
Gary Servin 0:04ac6be8229a 203 u_ixz.base = 0;
Gary Servin 0:04ac6be8229a 204 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 205 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 206 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 207 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 208 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 209 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 210 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 211 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 212 this->ixz = u_ixz.real;
Gary Servin 0:04ac6be8229a 213 offset += sizeof(this->ixz);
Gary Servin 0:04ac6be8229a 214 union {
Gary Servin 0:04ac6be8229a 215 double real;
Gary Servin 0:04ac6be8229a 216 uint64_t base;
Gary Servin 0:04ac6be8229a 217 } u_iyy;
Gary Servin 0:04ac6be8229a 218 u_iyy.base = 0;
Gary Servin 0:04ac6be8229a 219 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 220 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 221 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 222 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 223 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 224 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 225 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 226 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 227 this->iyy = u_iyy.real;
Gary Servin 0:04ac6be8229a 228 offset += sizeof(this->iyy);
Gary Servin 0:04ac6be8229a 229 union {
Gary Servin 0:04ac6be8229a 230 double real;
Gary Servin 0:04ac6be8229a 231 uint64_t base;
Gary Servin 0:04ac6be8229a 232 } u_iyz;
Gary Servin 0:04ac6be8229a 233 u_iyz.base = 0;
Gary Servin 0:04ac6be8229a 234 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 235 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 236 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 237 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 238 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 239 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 240 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 241 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 242 this->iyz = u_iyz.real;
Gary Servin 0:04ac6be8229a 243 offset += sizeof(this->iyz);
Gary Servin 0:04ac6be8229a 244 union {
Gary Servin 0:04ac6be8229a 245 double real;
Gary Servin 0:04ac6be8229a 246 uint64_t base;
Gary Servin 0:04ac6be8229a 247 } u_izz;
Gary Servin 0:04ac6be8229a 248 u_izz.base = 0;
Gary Servin 0:04ac6be8229a 249 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 250 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 251 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 252 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 253 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 254 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 255 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 256 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 257 this->izz = u_izz.real;
Gary Servin 0:04ac6be8229a 258 offset += sizeof(this->izz);
Gary Servin 0:04ac6be8229a 259 return offset;
Gary Servin 0:04ac6be8229a 260 }
Gary Servin 0:04ac6be8229a 261
Gary Servin 0:04ac6be8229a 262 const char * getType(){ return "geometry_msgs/Inertia"; };
Gary Servin 0:04ac6be8229a 263 const char * getMD5(){ return "1d26e4bb6c83ff141c5cf0d883c2b0fe"; };
Gary Servin 0:04ac6be8229a 264
Gary Servin 0:04ac6be8229a 265 };
Gary Servin 0:04ac6be8229a 266
Gary Servin 0:04ac6be8229a 267 }
Gary Servin 0:04ac6be8229a 268 #endif