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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_jade

ROSSerial_mbed for Jade 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_jade

rosserial_mbed Hello World example for jade 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:
garyservin
Date:
Thu Mar 31 23:23:15 2016 +0000
Revision:
0:a906bb7c7831
ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:a906bb7c7831 1 #ifndef _ROS_gazebo_msgs_ODEJointProperties_h
garyservin 0:a906bb7c7831 2 #define _ROS_gazebo_msgs_ODEJointProperties_h
garyservin 0:a906bb7c7831 3
garyservin 0:a906bb7c7831 4 #include <stdint.h>
garyservin 0:a906bb7c7831 5 #include <string.h>
garyservin 0:a906bb7c7831 6 #include <stdlib.h>
garyservin 0:a906bb7c7831 7 #include "ros/msg.h"
garyservin 0:a906bb7c7831 8
garyservin 0:a906bb7c7831 9 namespace gazebo_msgs
garyservin 0:a906bb7c7831 10 {
garyservin 0:a906bb7c7831 11
garyservin 0:a906bb7c7831 12 class ODEJointProperties : public ros::Msg
garyservin 0:a906bb7c7831 13 {
garyservin 0:a906bb7c7831 14 public:
garyservin 0:a906bb7c7831 15 uint8_t damping_length;
garyservin 0:a906bb7c7831 16 double st_damping;
garyservin 0:a906bb7c7831 17 double * damping;
garyservin 0:a906bb7c7831 18 uint8_t hiStop_length;
garyservin 0:a906bb7c7831 19 double st_hiStop;
garyservin 0:a906bb7c7831 20 double * hiStop;
garyservin 0:a906bb7c7831 21 uint8_t loStop_length;
garyservin 0:a906bb7c7831 22 double st_loStop;
garyservin 0:a906bb7c7831 23 double * loStop;
garyservin 0:a906bb7c7831 24 uint8_t erp_length;
garyservin 0:a906bb7c7831 25 double st_erp;
garyservin 0:a906bb7c7831 26 double * erp;
garyservin 0:a906bb7c7831 27 uint8_t cfm_length;
garyservin 0:a906bb7c7831 28 double st_cfm;
garyservin 0:a906bb7c7831 29 double * cfm;
garyservin 0:a906bb7c7831 30 uint8_t stop_erp_length;
garyservin 0:a906bb7c7831 31 double st_stop_erp;
garyservin 0:a906bb7c7831 32 double * stop_erp;
garyservin 0:a906bb7c7831 33 uint8_t stop_cfm_length;
garyservin 0:a906bb7c7831 34 double st_stop_cfm;
garyservin 0:a906bb7c7831 35 double * stop_cfm;
garyservin 0:a906bb7c7831 36 uint8_t fudge_factor_length;
garyservin 0:a906bb7c7831 37 double st_fudge_factor;
garyservin 0:a906bb7c7831 38 double * fudge_factor;
garyservin 0:a906bb7c7831 39 uint8_t fmax_length;
garyservin 0:a906bb7c7831 40 double st_fmax;
garyservin 0:a906bb7c7831 41 double * fmax;
garyservin 0:a906bb7c7831 42 uint8_t vel_length;
garyservin 0:a906bb7c7831 43 double st_vel;
garyservin 0:a906bb7c7831 44 double * vel;
garyservin 0:a906bb7c7831 45
garyservin 0:a906bb7c7831 46 ODEJointProperties():
garyservin 0:a906bb7c7831 47 damping_length(0), damping(NULL),
garyservin 0:a906bb7c7831 48 hiStop_length(0), hiStop(NULL),
garyservin 0:a906bb7c7831 49 loStop_length(0), loStop(NULL),
garyservin 0:a906bb7c7831 50 erp_length(0), erp(NULL),
garyservin 0:a906bb7c7831 51 cfm_length(0), cfm(NULL),
garyservin 0:a906bb7c7831 52 stop_erp_length(0), stop_erp(NULL),
garyservin 0:a906bb7c7831 53 stop_cfm_length(0), stop_cfm(NULL),
garyservin 0:a906bb7c7831 54 fudge_factor_length(0), fudge_factor(NULL),
garyservin 0:a906bb7c7831 55 fmax_length(0), fmax(NULL),
garyservin 0:a906bb7c7831 56 vel_length(0), vel(NULL)
garyservin 0:a906bb7c7831 57 {
garyservin 0:a906bb7c7831 58 }
garyservin 0:a906bb7c7831 59
garyservin 0:a906bb7c7831 60 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 61 {
garyservin 0:a906bb7c7831 62 int offset = 0;
garyservin 0:a906bb7c7831 63 *(outbuffer + offset++) = damping_length;
garyservin 0:a906bb7c7831 64 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 65 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 66 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 67 for( uint8_t i = 0; i < damping_length; i++){
garyservin 0:a906bb7c7831 68 union {
garyservin 0:a906bb7c7831 69 double real;
garyservin 0:a906bb7c7831 70 uint64_t base;
garyservin 0:a906bb7c7831 71 } u_dampingi;
garyservin 0:a906bb7c7831 72 u_dampingi.real = this->damping[i];
garyservin 0:a906bb7c7831 73 *(outbuffer + offset + 0) = (u_dampingi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 74 *(outbuffer + offset + 1) = (u_dampingi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 75 *(outbuffer + offset + 2) = (u_dampingi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 76 *(outbuffer + offset + 3) = (u_dampingi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 77 *(outbuffer + offset + 4) = (u_dampingi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 78 *(outbuffer + offset + 5) = (u_dampingi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 79 *(outbuffer + offset + 6) = (u_dampingi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 80 *(outbuffer + offset + 7) = (u_dampingi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 81 offset += sizeof(this->damping[i]);
garyservin 0:a906bb7c7831 82 }
garyservin 0:a906bb7c7831 83 *(outbuffer + offset++) = hiStop_length;
garyservin 0:a906bb7c7831 84 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 85 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 86 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 87 for( uint8_t i = 0; i < hiStop_length; i++){
garyservin 0:a906bb7c7831 88 union {
garyservin 0:a906bb7c7831 89 double real;
garyservin 0:a906bb7c7831 90 uint64_t base;
garyservin 0:a906bb7c7831 91 } u_hiStopi;
garyservin 0:a906bb7c7831 92 u_hiStopi.real = this->hiStop[i];
garyservin 0:a906bb7c7831 93 *(outbuffer + offset + 0) = (u_hiStopi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 94 *(outbuffer + offset + 1) = (u_hiStopi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 95 *(outbuffer + offset + 2) = (u_hiStopi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 96 *(outbuffer + offset + 3) = (u_hiStopi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 97 *(outbuffer + offset + 4) = (u_hiStopi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 98 *(outbuffer + offset + 5) = (u_hiStopi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 99 *(outbuffer + offset + 6) = (u_hiStopi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 100 *(outbuffer + offset + 7) = (u_hiStopi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 101 offset += sizeof(this->hiStop[i]);
garyservin 0:a906bb7c7831 102 }
garyservin 0:a906bb7c7831 103 *(outbuffer + offset++) = loStop_length;
garyservin 0:a906bb7c7831 104 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 105 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 106 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 107 for( uint8_t i = 0; i < loStop_length; i++){
garyservin 0:a906bb7c7831 108 union {
garyservin 0:a906bb7c7831 109 double real;
garyservin 0:a906bb7c7831 110 uint64_t base;
garyservin 0:a906bb7c7831 111 } u_loStopi;
garyservin 0:a906bb7c7831 112 u_loStopi.real = this->loStop[i];
garyservin 0:a906bb7c7831 113 *(outbuffer + offset + 0) = (u_loStopi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 114 *(outbuffer + offset + 1) = (u_loStopi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 115 *(outbuffer + offset + 2) = (u_loStopi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 116 *(outbuffer + offset + 3) = (u_loStopi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 117 *(outbuffer + offset + 4) = (u_loStopi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 118 *(outbuffer + offset + 5) = (u_loStopi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 119 *(outbuffer + offset + 6) = (u_loStopi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 120 *(outbuffer + offset + 7) = (u_loStopi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 121 offset += sizeof(this->loStop[i]);
garyservin 0:a906bb7c7831 122 }
garyservin 0:a906bb7c7831 123 *(outbuffer + offset++) = erp_length;
garyservin 0:a906bb7c7831 124 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 125 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 126 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 127 for( uint8_t i = 0; i < erp_length; i++){
garyservin 0:a906bb7c7831 128 union {
garyservin 0:a906bb7c7831 129 double real;
garyservin 0:a906bb7c7831 130 uint64_t base;
garyservin 0:a906bb7c7831 131 } u_erpi;
garyservin 0:a906bb7c7831 132 u_erpi.real = this->erp[i];
garyservin 0:a906bb7c7831 133 *(outbuffer + offset + 0) = (u_erpi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 134 *(outbuffer + offset + 1) = (u_erpi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 135 *(outbuffer + offset + 2) = (u_erpi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 136 *(outbuffer + offset + 3) = (u_erpi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 137 *(outbuffer + offset + 4) = (u_erpi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 138 *(outbuffer + offset + 5) = (u_erpi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 139 *(outbuffer + offset + 6) = (u_erpi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 140 *(outbuffer + offset + 7) = (u_erpi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 141 offset += sizeof(this->erp[i]);
garyservin 0:a906bb7c7831 142 }
garyservin 0:a906bb7c7831 143 *(outbuffer + offset++) = cfm_length;
garyservin 0:a906bb7c7831 144 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 145 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 146 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 147 for( uint8_t i = 0; i < cfm_length; i++){
garyservin 0:a906bb7c7831 148 union {
garyservin 0:a906bb7c7831 149 double real;
garyservin 0:a906bb7c7831 150 uint64_t base;
garyservin 0:a906bb7c7831 151 } u_cfmi;
garyservin 0:a906bb7c7831 152 u_cfmi.real = this->cfm[i];
garyservin 0:a906bb7c7831 153 *(outbuffer + offset + 0) = (u_cfmi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 154 *(outbuffer + offset + 1) = (u_cfmi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 155 *(outbuffer + offset + 2) = (u_cfmi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 156 *(outbuffer + offset + 3) = (u_cfmi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 157 *(outbuffer + offset + 4) = (u_cfmi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 158 *(outbuffer + offset + 5) = (u_cfmi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 159 *(outbuffer + offset + 6) = (u_cfmi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 160 *(outbuffer + offset + 7) = (u_cfmi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 161 offset += sizeof(this->cfm[i]);
garyservin 0:a906bb7c7831 162 }
garyservin 0:a906bb7c7831 163 *(outbuffer + offset++) = stop_erp_length;
garyservin 0:a906bb7c7831 164 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 165 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 166 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 167 for( uint8_t i = 0; i < stop_erp_length; i++){
garyservin 0:a906bb7c7831 168 union {
garyservin 0:a906bb7c7831 169 double real;
garyservin 0:a906bb7c7831 170 uint64_t base;
garyservin 0:a906bb7c7831 171 } u_stop_erpi;
garyservin 0:a906bb7c7831 172 u_stop_erpi.real = this->stop_erp[i];
garyservin 0:a906bb7c7831 173 *(outbuffer + offset + 0) = (u_stop_erpi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 174 *(outbuffer + offset + 1) = (u_stop_erpi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 175 *(outbuffer + offset + 2) = (u_stop_erpi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 176 *(outbuffer + offset + 3) = (u_stop_erpi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 177 *(outbuffer + offset + 4) = (u_stop_erpi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 178 *(outbuffer + offset + 5) = (u_stop_erpi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 179 *(outbuffer + offset + 6) = (u_stop_erpi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 180 *(outbuffer + offset + 7) = (u_stop_erpi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 181 offset += sizeof(this->stop_erp[i]);
garyservin 0:a906bb7c7831 182 }
garyservin 0:a906bb7c7831 183 *(outbuffer + offset++) = stop_cfm_length;
garyservin 0:a906bb7c7831 184 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 185 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 186 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 187 for( uint8_t i = 0; i < stop_cfm_length; i++){
garyservin 0:a906bb7c7831 188 union {
garyservin 0:a906bb7c7831 189 double real;
garyservin 0:a906bb7c7831 190 uint64_t base;
garyservin 0:a906bb7c7831 191 } u_stop_cfmi;
garyservin 0:a906bb7c7831 192 u_stop_cfmi.real = this->stop_cfm[i];
garyservin 0:a906bb7c7831 193 *(outbuffer + offset + 0) = (u_stop_cfmi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 194 *(outbuffer + offset + 1) = (u_stop_cfmi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 195 *(outbuffer + offset + 2) = (u_stop_cfmi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 196 *(outbuffer + offset + 3) = (u_stop_cfmi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 197 *(outbuffer + offset + 4) = (u_stop_cfmi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 198 *(outbuffer + offset + 5) = (u_stop_cfmi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 199 *(outbuffer + offset + 6) = (u_stop_cfmi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 200 *(outbuffer + offset + 7) = (u_stop_cfmi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 201 offset += sizeof(this->stop_cfm[i]);
garyservin 0:a906bb7c7831 202 }
garyservin 0:a906bb7c7831 203 *(outbuffer + offset++) = fudge_factor_length;
garyservin 0:a906bb7c7831 204 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 205 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 206 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 207 for( uint8_t i = 0; i < fudge_factor_length; i++){
garyservin 0:a906bb7c7831 208 union {
garyservin 0:a906bb7c7831 209 double real;
garyservin 0:a906bb7c7831 210 uint64_t base;
garyservin 0:a906bb7c7831 211 } u_fudge_factori;
garyservin 0:a906bb7c7831 212 u_fudge_factori.real = this->fudge_factor[i];
garyservin 0:a906bb7c7831 213 *(outbuffer + offset + 0) = (u_fudge_factori.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 214 *(outbuffer + offset + 1) = (u_fudge_factori.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 215 *(outbuffer + offset + 2) = (u_fudge_factori.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 216 *(outbuffer + offset + 3) = (u_fudge_factori.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 217 *(outbuffer + offset + 4) = (u_fudge_factori.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 218 *(outbuffer + offset + 5) = (u_fudge_factori.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 219 *(outbuffer + offset + 6) = (u_fudge_factori.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 220 *(outbuffer + offset + 7) = (u_fudge_factori.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 221 offset += sizeof(this->fudge_factor[i]);
garyservin 0:a906bb7c7831 222 }
garyservin 0:a906bb7c7831 223 *(outbuffer + offset++) = fmax_length;
garyservin 0:a906bb7c7831 224 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 225 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 226 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 227 for( uint8_t i = 0; i < fmax_length; i++){
garyservin 0:a906bb7c7831 228 union {
garyservin 0:a906bb7c7831 229 double real;
garyservin 0:a906bb7c7831 230 uint64_t base;
garyservin 0:a906bb7c7831 231 } u_fmaxi;
garyservin 0:a906bb7c7831 232 u_fmaxi.real = this->fmax[i];
garyservin 0:a906bb7c7831 233 *(outbuffer + offset + 0) = (u_fmaxi.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 234 *(outbuffer + offset + 1) = (u_fmaxi.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 235 *(outbuffer + offset + 2) = (u_fmaxi.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 236 *(outbuffer + offset + 3) = (u_fmaxi.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 237 *(outbuffer + offset + 4) = (u_fmaxi.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 238 *(outbuffer + offset + 5) = (u_fmaxi.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 239 *(outbuffer + offset + 6) = (u_fmaxi.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 240 *(outbuffer + offset + 7) = (u_fmaxi.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 241 offset += sizeof(this->fmax[i]);
garyservin 0:a906bb7c7831 242 }
garyservin 0:a906bb7c7831 243 *(outbuffer + offset++) = vel_length;
garyservin 0:a906bb7c7831 244 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 245 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 246 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 247 for( uint8_t i = 0; i < vel_length; i++){
garyservin 0:a906bb7c7831 248 union {
garyservin 0:a906bb7c7831 249 double real;
garyservin 0:a906bb7c7831 250 uint64_t base;
garyservin 0:a906bb7c7831 251 } u_veli;
garyservin 0:a906bb7c7831 252 u_veli.real = this->vel[i];
garyservin 0:a906bb7c7831 253 *(outbuffer + offset + 0) = (u_veli.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 254 *(outbuffer + offset + 1) = (u_veli.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 255 *(outbuffer + offset + 2) = (u_veli.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 256 *(outbuffer + offset + 3) = (u_veli.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 257 *(outbuffer + offset + 4) = (u_veli.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 258 *(outbuffer + offset + 5) = (u_veli.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 259 *(outbuffer + offset + 6) = (u_veli.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 260 *(outbuffer + offset + 7) = (u_veli.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 261 offset += sizeof(this->vel[i]);
garyservin 0:a906bb7c7831 262 }
garyservin 0:a906bb7c7831 263 return offset;
garyservin 0:a906bb7c7831 264 }
garyservin 0:a906bb7c7831 265
garyservin 0:a906bb7c7831 266 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 267 {
garyservin 0:a906bb7c7831 268 int offset = 0;
garyservin 0:a906bb7c7831 269 uint8_t damping_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 270 if(damping_lengthT > damping_length)
garyservin 0:a906bb7c7831 271 this->damping = (double*)realloc(this->damping, damping_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 272 offset += 3;
garyservin 0:a906bb7c7831 273 damping_length = damping_lengthT;
garyservin 0:a906bb7c7831 274 for( uint8_t i = 0; i < damping_length; i++){
garyservin 0:a906bb7c7831 275 union {
garyservin 0:a906bb7c7831 276 double real;
garyservin 0:a906bb7c7831 277 uint64_t base;
garyservin 0:a906bb7c7831 278 } u_st_damping;
garyservin 0:a906bb7c7831 279 u_st_damping.base = 0;
garyservin 0:a906bb7c7831 280 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 281 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 282 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 283 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 284 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 285 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 286 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 287 u_st_damping.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 288 this->st_damping = u_st_damping.real;
garyservin 0:a906bb7c7831 289 offset += sizeof(this->st_damping);
garyservin 0:a906bb7c7831 290 memcpy( &(this->damping[i]), &(this->st_damping), sizeof(double));
garyservin 0:a906bb7c7831 291 }
garyservin 0:a906bb7c7831 292 uint8_t hiStop_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 293 if(hiStop_lengthT > hiStop_length)
garyservin 0:a906bb7c7831 294 this->hiStop = (double*)realloc(this->hiStop, hiStop_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 295 offset += 3;
garyservin 0:a906bb7c7831 296 hiStop_length = hiStop_lengthT;
garyservin 0:a906bb7c7831 297 for( uint8_t i = 0; i < hiStop_length; i++){
garyservin 0:a906bb7c7831 298 union {
garyservin 0:a906bb7c7831 299 double real;
garyservin 0:a906bb7c7831 300 uint64_t base;
garyservin 0:a906bb7c7831 301 } u_st_hiStop;
garyservin 0:a906bb7c7831 302 u_st_hiStop.base = 0;
garyservin 0:a906bb7c7831 303 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 304 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 305 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 306 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 307 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 308 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 309 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 310 u_st_hiStop.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 311 this->st_hiStop = u_st_hiStop.real;
garyservin 0:a906bb7c7831 312 offset += sizeof(this->st_hiStop);
garyservin 0:a906bb7c7831 313 memcpy( &(this->hiStop[i]), &(this->st_hiStop), sizeof(double));
garyservin 0:a906bb7c7831 314 }
garyservin 0:a906bb7c7831 315 uint8_t loStop_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 316 if(loStop_lengthT > loStop_length)
garyservin 0:a906bb7c7831 317 this->loStop = (double*)realloc(this->loStop, loStop_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 318 offset += 3;
garyservin 0:a906bb7c7831 319 loStop_length = loStop_lengthT;
garyservin 0:a906bb7c7831 320 for( uint8_t i = 0; i < loStop_length; i++){
garyservin 0:a906bb7c7831 321 union {
garyservin 0:a906bb7c7831 322 double real;
garyservin 0:a906bb7c7831 323 uint64_t base;
garyservin 0:a906bb7c7831 324 } u_st_loStop;
garyservin 0:a906bb7c7831 325 u_st_loStop.base = 0;
garyservin 0:a906bb7c7831 326 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 327 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 328 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 329 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 330 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 331 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 332 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 333 u_st_loStop.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 334 this->st_loStop = u_st_loStop.real;
garyservin 0:a906bb7c7831 335 offset += sizeof(this->st_loStop);
garyservin 0:a906bb7c7831 336 memcpy( &(this->loStop[i]), &(this->st_loStop), sizeof(double));
garyservin 0:a906bb7c7831 337 }
garyservin 0:a906bb7c7831 338 uint8_t erp_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 339 if(erp_lengthT > erp_length)
garyservin 0:a906bb7c7831 340 this->erp = (double*)realloc(this->erp, erp_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 341 offset += 3;
garyservin 0:a906bb7c7831 342 erp_length = erp_lengthT;
garyservin 0:a906bb7c7831 343 for( uint8_t i = 0; i < erp_length; i++){
garyservin 0:a906bb7c7831 344 union {
garyservin 0:a906bb7c7831 345 double real;
garyservin 0:a906bb7c7831 346 uint64_t base;
garyservin 0:a906bb7c7831 347 } u_st_erp;
garyservin 0:a906bb7c7831 348 u_st_erp.base = 0;
garyservin 0:a906bb7c7831 349 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 350 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 351 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 352 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 353 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 354 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 355 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 356 u_st_erp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 357 this->st_erp = u_st_erp.real;
garyservin 0:a906bb7c7831 358 offset += sizeof(this->st_erp);
garyservin 0:a906bb7c7831 359 memcpy( &(this->erp[i]), &(this->st_erp), sizeof(double));
garyservin 0:a906bb7c7831 360 }
garyservin 0:a906bb7c7831 361 uint8_t cfm_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 362 if(cfm_lengthT > cfm_length)
garyservin 0:a906bb7c7831 363 this->cfm = (double*)realloc(this->cfm, cfm_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 364 offset += 3;
garyservin 0:a906bb7c7831 365 cfm_length = cfm_lengthT;
garyservin 0:a906bb7c7831 366 for( uint8_t i = 0; i < cfm_length; i++){
garyservin 0:a906bb7c7831 367 union {
garyservin 0:a906bb7c7831 368 double real;
garyservin 0:a906bb7c7831 369 uint64_t base;
garyservin 0:a906bb7c7831 370 } u_st_cfm;
garyservin 0:a906bb7c7831 371 u_st_cfm.base = 0;
garyservin 0:a906bb7c7831 372 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 373 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 374 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 375 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 376 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 377 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 378 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 379 u_st_cfm.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 380 this->st_cfm = u_st_cfm.real;
garyservin 0:a906bb7c7831 381 offset += sizeof(this->st_cfm);
garyservin 0:a906bb7c7831 382 memcpy( &(this->cfm[i]), &(this->st_cfm), sizeof(double));
garyservin 0:a906bb7c7831 383 }
garyservin 0:a906bb7c7831 384 uint8_t stop_erp_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 385 if(stop_erp_lengthT > stop_erp_length)
garyservin 0:a906bb7c7831 386 this->stop_erp = (double*)realloc(this->stop_erp, stop_erp_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 387 offset += 3;
garyservin 0:a906bb7c7831 388 stop_erp_length = stop_erp_lengthT;
garyservin 0:a906bb7c7831 389 for( uint8_t i = 0; i < stop_erp_length; i++){
garyservin 0:a906bb7c7831 390 union {
garyservin 0:a906bb7c7831 391 double real;
garyservin 0:a906bb7c7831 392 uint64_t base;
garyservin 0:a906bb7c7831 393 } u_st_stop_erp;
garyservin 0:a906bb7c7831 394 u_st_stop_erp.base = 0;
garyservin 0:a906bb7c7831 395 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 396 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 397 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 398 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 399 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 400 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 401 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 402 u_st_stop_erp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 403 this->st_stop_erp = u_st_stop_erp.real;
garyservin 0:a906bb7c7831 404 offset += sizeof(this->st_stop_erp);
garyservin 0:a906bb7c7831 405 memcpy( &(this->stop_erp[i]), &(this->st_stop_erp), sizeof(double));
garyservin 0:a906bb7c7831 406 }
garyservin 0:a906bb7c7831 407 uint8_t stop_cfm_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 408 if(stop_cfm_lengthT > stop_cfm_length)
garyservin 0:a906bb7c7831 409 this->stop_cfm = (double*)realloc(this->stop_cfm, stop_cfm_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 410 offset += 3;
garyservin 0:a906bb7c7831 411 stop_cfm_length = stop_cfm_lengthT;
garyservin 0:a906bb7c7831 412 for( uint8_t i = 0; i < stop_cfm_length; i++){
garyservin 0:a906bb7c7831 413 union {
garyservin 0:a906bb7c7831 414 double real;
garyservin 0:a906bb7c7831 415 uint64_t base;
garyservin 0:a906bb7c7831 416 } u_st_stop_cfm;
garyservin 0:a906bb7c7831 417 u_st_stop_cfm.base = 0;
garyservin 0:a906bb7c7831 418 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 419 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 420 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 421 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 422 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 423 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 424 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 425 u_st_stop_cfm.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 426 this->st_stop_cfm = u_st_stop_cfm.real;
garyservin 0:a906bb7c7831 427 offset += sizeof(this->st_stop_cfm);
garyservin 0:a906bb7c7831 428 memcpy( &(this->stop_cfm[i]), &(this->st_stop_cfm), sizeof(double));
garyservin 0:a906bb7c7831 429 }
garyservin 0:a906bb7c7831 430 uint8_t fudge_factor_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 431 if(fudge_factor_lengthT > fudge_factor_length)
garyservin 0:a906bb7c7831 432 this->fudge_factor = (double*)realloc(this->fudge_factor, fudge_factor_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 433 offset += 3;
garyservin 0:a906bb7c7831 434 fudge_factor_length = fudge_factor_lengthT;
garyservin 0:a906bb7c7831 435 for( uint8_t i = 0; i < fudge_factor_length; i++){
garyservin 0:a906bb7c7831 436 union {
garyservin 0:a906bb7c7831 437 double real;
garyservin 0:a906bb7c7831 438 uint64_t base;
garyservin 0:a906bb7c7831 439 } u_st_fudge_factor;
garyservin 0:a906bb7c7831 440 u_st_fudge_factor.base = 0;
garyservin 0:a906bb7c7831 441 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 442 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 443 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 444 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 445 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 446 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 447 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 448 u_st_fudge_factor.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 449 this->st_fudge_factor = u_st_fudge_factor.real;
garyservin 0:a906bb7c7831 450 offset += sizeof(this->st_fudge_factor);
garyservin 0:a906bb7c7831 451 memcpy( &(this->fudge_factor[i]), &(this->st_fudge_factor), sizeof(double));
garyservin 0:a906bb7c7831 452 }
garyservin 0:a906bb7c7831 453 uint8_t fmax_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 454 if(fmax_lengthT > fmax_length)
garyservin 0:a906bb7c7831 455 this->fmax = (double*)realloc(this->fmax, fmax_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 456 offset += 3;
garyservin 0:a906bb7c7831 457 fmax_length = fmax_lengthT;
garyservin 0:a906bb7c7831 458 for( uint8_t i = 0; i < fmax_length; i++){
garyservin 0:a906bb7c7831 459 union {
garyservin 0:a906bb7c7831 460 double real;
garyservin 0:a906bb7c7831 461 uint64_t base;
garyservin 0:a906bb7c7831 462 } u_st_fmax;
garyservin 0:a906bb7c7831 463 u_st_fmax.base = 0;
garyservin 0:a906bb7c7831 464 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 465 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 466 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 467 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 468 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 469 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 470 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 471 u_st_fmax.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 472 this->st_fmax = u_st_fmax.real;
garyservin 0:a906bb7c7831 473 offset += sizeof(this->st_fmax);
garyservin 0:a906bb7c7831 474 memcpy( &(this->fmax[i]), &(this->st_fmax), sizeof(double));
garyservin 0:a906bb7c7831 475 }
garyservin 0:a906bb7c7831 476 uint8_t vel_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 477 if(vel_lengthT > vel_length)
garyservin 0:a906bb7c7831 478 this->vel = (double*)realloc(this->vel, vel_lengthT * sizeof(double));
garyservin 0:a906bb7c7831 479 offset += 3;
garyservin 0:a906bb7c7831 480 vel_length = vel_lengthT;
garyservin 0:a906bb7c7831 481 for( uint8_t i = 0; i < vel_length; i++){
garyservin 0:a906bb7c7831 482 union {
garyservin 0:a906bb7c7831 483 double real;
garyservin 0:a906bb7c7831 484 uint64_t base;
garyservin 0:a906bb7c7831 485 } u_st_vel;
garyservin 0:a906bb7c7831 486 u_st_vel.base = 0;
garyservin 0:a906bb7c7831 487 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 488 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 489 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 490 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 491 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 492 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 493 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 494 u_st_vel.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 495 this->st_vel = u_st_vel.real;
garyservin 0:a906bb7c7831 496 offset += sizeof(this->st_vel);
garyservin 0:a906bb7c7831 497 memcpy( &(this->vel[i]), &(this->st_vel), sizeof(double));
garyservin 0:a906bb7c7831 498 }
garyservin 0:a906bb7c7831 499 return offset;
garyservin 0:a906bb7c7831 500 }
garyservin 0:a906bb7c7831 501
garyservin 0:a906bb7c7831 502 const char * getType(){ return "gazebo_msgs/ODEJointProperties"; };
garyservin 0:a906bb7c7831 503 const char * getMD5(){ return "1b744c32a920af979f53afe2f9c3511f"; };
garyservin 0:a906bb7c7831 504
garyservin 0:a906bb7c7831 505 };
garyservin 0:a906bb7c7831 506
garyservin 0:a906bb7c7831 507 }
garyservin 0:a906bb7c7831 508 #endif