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_control_msgs_JointControllerState_h
garyservin 0:a906bb7c7831 2 #define _ROS_control_msgs_JointControllerState_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 #include "std_msgs/Header.h"
garyservin 0:a906bb7c7831 9
garyservin 0:a906bb7c7831 10 namespace control_msgs
garyservin 0:a906bb7c7831 11 {
garyservin 0:a906bb7c7831 12
garyservin 0:a906bb7c7831 13 class JointControllerState : public ros::Msg
garyservin 0:a906bb7c7831 14 {
garyservin 0:a906bb7c7831 15 public:
garyservin 0:a906bb7c7831 16 std_msgs::Header header;
garyservin 0:a906bb7c7831 17 double set_point;
garyservin 0:a906bb7c7831 18 double process_value;
garyservin 0:a906bb7c7831 19 double process_value_dot;
garyservin 0:a906bb7c7831 20 double error;
garyservin 0:a906bb7c7831 21 double time_step;
garyservin 0:a906bb7c7831 22 double command;
garyservin 0:a906bb7c7831 23 double p;
garyservin 0:a906bb7c7831 24 double i;
garyservin 0:a906bb7c7831 25 double d;
garyservin 0:a906bb7c7831 26 double i_clamp;
garyservin 0:a906bb7c7831 27
garyservin 0:a906bb7c7831 28 JointControllerState():
garyservin 0:a906bb7c7831 29 header(),
garyservin 0:a906bb7c7831 30 set_point(0),
garyservin 0:a906bb7c7831 31 process_value(0),
garyservin 0:a906bb7c7831 32 process_value_dot(0),
garyservin 0:a906bb7c7831 33 error(0),
garyservin 0:a906bb7c7831 34 time_step(0),
garyservin 0:a906bb7c7831 35 command(0),
garyservin 0:a906bb7c7831 36 p(0),
garyservin 0:a906bb7c7831 37 i(0),
garyservin 0:a906bb7c7831 38 d(0),
garyservin 0:a906bb7c7831 39 i_clamp(0)
garyservin 0:a906bb7c7831 40 {
garyservin 0:a906bb7c7831 41 }
garyservin 0:a906bb7c7831 42
garyservin 0:a906bb7c7831 43 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 44 {
garyservin 0:a906bb7c7831 45 int offset = 0;
garyservin 0:a906bb7c7831 46 offset += this->header.serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 47 union {
garyservin 0:a906bb7c7831 48 double real;
garyservin 0:a906bb7c7831 49 uint64_t base;
garyservin 0:a906bb7c7831 50 } u_set_point;
garyservin 0:a906bb7c7831 51 u_set_point.real = this->set_point;
garyservin 0:a906bb7c7831 52 *(outbuffer + offset + 0) = (u_set_point.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 53 *(outbuffer + offset + 1) = (u_set_point.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 54 *(outbuffer + offset + 2) = (u_set_point.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 55 *(outbuffer + offset + 3) = (u_set_point.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 56 *(outbuffer + offset + 4) = (u_set_point.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 57 *(outbuffer + offset + 5) = (u_set_point.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 58 *(outbuffer + offset + 6) = (u_set_point.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 59 *(outbuffer + offset + 7) = (u_set_point.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 60 offset += sizeof(this->set_point);
garyservin 0:a906bb7c7831 61 union {
garyservin 0:a906bb7c7831 62 double real;
garyservin 0:a906bb7c7831 63 uint64_t base;
garyservin 0:a906bb7c7831 64 } u_process_value;
garyservin 0:a906bb7c7831 65 u_process_value.real = this->process_value;
garyservin 0:a906bb7c7831 66 *(outbuffer + offset + 0) = (u_process_value.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 67 *(outbuffer + offset + 1) = (u_process_value.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 68 *(outbuffer + offset + 2) = (u_process_value.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 69 *(outbuffer + offset + 3) = (u_process_value.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 70 *(outbuffer + offset + 4) = (u_process_value.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 71 *(outbuffer + offset + 5) = (u_process_value.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 72 *(outbuffer + offset + 6) = (u_process_value.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 73 *(outbuffer + offset + 7) = (u_process_value.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 74 offset += sizeof(this->process_value);
garyservin 0:a906bb7c7831 75 union {
garyservin 0:a906bb7c7831 76 double real;
garyservin 0:a906bb7c7831 77 uint64_t base;
garyservin 0:a906bb7c7831 78 } u_process_value_dot;
garyservin 0:a906bb7c7831 79 u_process_value_dot.real = this->process_value_dot;
garyservin 0:a906bb7c7831 80 *(outbuffer + offset + 0) = (u_process_value_dot.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 81 *(outbuffer + offset + 1) = (u_process_value_dot.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 82 *(outbuffer + offset + 2) = (u_process_value_dot.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 83 *(outbuffer + offset + 3) = (u_process_value_dot.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 84 *(outbuffer + offset + 4) = (u_process_value_dot.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 85 *(outbuffer + offset + 5) = (u_process_value_dot.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 86 *(outbuffer + offset + 6) = (u_process_value_dot.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 87 *(outbuffer + offset + 7) = (u_process_value_dot.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 88 offset += sizeof(this->process_value_dot);
garyservin 0:a906bb7c7831 89 union {
garyservin 0:a906bb7c7831 90 double real;
garyservin 0:a906bb7c7831 91 uint64_t base;
garyservin 0:a906bb7c7831 92 } u_error;
garyservin 0:a906bb7c7831 93 u_error.real = this->error;
garyservin 0:a906bb7c7831 94 *(outbuffer + offset + 0) = (u_error.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 95 *(outbuffer + offset + 1) = (u_error.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 96 *(outbuffer + offset + 2) = (u_error.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 97 *(outbuffer + offset + 3) = (u_error.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 98 *(outbuffer + offset + 4) = (u_error.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 99 *(outbuffer + offset + 5) = (u_error.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 100 *(outbuffer + offset + 6) = (u_error.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 101 *(outbuffer + offset + 7) = (u_error.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 102 offset += sizeof(this->error);
garyservin 0:a906bb7c7831 103 union {
garyservin 0:a906bb7c7831 104 double real;
garyservin 0:a906bb7c7831 105 uint64_t base;
garyservin 0:a906bb7c7831 106 } u_time_step;
garyservin 0:a906bb7c7831 107 u_time_step.real = this->time_step;
garyservin 0:a906bb7c7831 108 *(outbuffer + offset + 0) = (u_time_step.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 109 *(outbuffer + offset + 1) = (u_time_step.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 110 *(outbuffer + offset + 2) = (u_time_step.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 111 *(outbuffer + offset + 3) = (u_time_step.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 112 *(outbuffer + offset + 4) = (u_time_step.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 113 *(outbuffer + offset + 5) = (u_time_step.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 114 *(outbuffer + offset + 6) = (u_time_step.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 115 *(outbuffer + offset + 7) = (u_time_step.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 116 offset += sizeof(this->time_step);
garyservin 0:a906bb7c7831 117 union {
garyservin 0:a906bb7c7831 118 double real;
garyservin 0:a906bb7c7831 119 uint64_t base;
garyservin 0:a906bb7c7831 120 } u_command;
garyservin 0:a906bb7c7831 121 u_command.real = this->command;
garyservin 0:a906bb7c7831 122 *(outbuffer + offset + 0) = (u_command.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 123 *(outbuffer + offset + 1) = (u_command.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 124 *(outbuffer + offset + 2) = (u_command.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 125 *(outbuffer + offset + 3) = (u_command.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 126 *(outbuffer + offset + 4) = (u_command.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 127 *(outbuffer + offset + 5) = (u_command.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 128 *(outbuffer + offset + 6) = (u_command.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 129 *(outbuffer + offset + 7) = (u_command.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 130 offset += sizeof(this->command);
garyservin 0:a906bb7c7831 131 union {
garyservin 0:a906bb7c7831 132 double real;
garyservin 0:a906bb7c7831 133 uint64_t base;
garyservin 0:a906bb7c7831 134 } u_p;
garyservin 0:a906bb7c7831 135 u_p.real = this->p;
garyservin 0:a906bb7c7831 136 *(outbuffer + offset + 0) = (u_p.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 137 *(outbuffer + offset + 1) = (u_p.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 138 *(outbuffer + offset + 2) = (u_p.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 139 *(outbuffer + offset + 3) = (u_p.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 140 *(outbuffer + offset + 4) = (u_p.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 141 *(outbuffer + offset + 5) = (u_p.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 142 *(outbuffer + offset + 6) = (u_p.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 143 *(outbuffer + offset + 7) = (u_p.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 144 offset += sizeof(this->p);
garyservin 0:a906bb7c7831 145 union {
garyservin 0:a906bb7c7831 146 double real;
garyservin 0:a906bb7c7831 147 uint64_t base;
garyservin 0:a906bb7c7831 148 } u_i;
garyservin 0:a906bb7c7831 149 u_i.real = this->i;
garyservin 0:a906bb7c7831 150 *(outbuffer + offset + 0) = (u_i.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 151 *(outbuffer + offset + 1) = (u_i.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 152 *(outbuffer + offset + 2) = (u_i.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 153 *(outbuffer + offset + 3) = (u_i.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 154 *(outbuffer + offset + 4) = (u_i.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 155 *(outbuffer + offset + 5) = (u_i.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 156 *(outbuffer + offset + 6) = (u_i.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 157 *(outbuffer + offset + 7) = (u_i.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 158 offset += sizeof(this->i);
garyservin 0:a906bb7c7831 159 union {
garyservin 0:a906bb7c7831 160 double real;
garyservin 0:a906bb7c7831 161 uint64_t base;
garyservin 0:a906bb7c7831 162 } u_d;
garyservin 0:a906bb7c7831 163 u_d.real = this->d;
garyservin 0:a906bb7c7831 164 *(outbuffer + offset + 0) = (u_d.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 165 *(outbuffer + offset + 1) = (u_d.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 166 *(outbuffer + offset + 2) = (u_d.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 167 *(outbuffer + offset + 3) = (u_d.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 168 *(outbuffer + offset + 4) = (u_d.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 169 *(outbuffer + offset + 5) = (u_d.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 170 *(outbuffer + offset + 6) = (u_d.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 171 *(outbuffer + offset + 7) = (u_d.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 172 offset += sizeof(this->d);
garyservin 0:a906bb7c7831 173 union {
garyservin 0:a906bb7c7831 174 double real;
garyservin 0:a906bb7c7831 175 uint64_t base;
garyservin 0:a906bb7c7831 176 } u_i_clamp;
garyservin 0:a906bb7c7831 177 u_i_clamp.real = this->i_clamp;
garyservin 0:a906bb7c7831 178 *(outbuffer + offset + 0) = (u_i_clamp.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 179 *(outbuffer + offset + 1) = (u_i_clamp.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 180 *(outbuffer + offset + 2) = (u_i_clamp.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 181 *(outbuffer + offset + 3) = (u_i_clamp.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 182 *(outbuffer + offset + 4) = (u_i_clamp.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 183 *(outbuffer + offset + 5) = (u_i_clamp.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 184 *(outbuffer + offset + 6) = (u_i_clamp.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 185 *(outbuffer + offset + 7) = (u_i_clamp.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 186 offset += sizeof(this->i_clamp);
garyservin 0:a906bb7c7831 187 return offset;
garyservin 0:a906bb7c7831 188 }
garyservin 0:a906bb7c7831 189
garyservin 0:a906bb7c7831 190 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 191 {
garyservin 0:a906bb7c7831 192 int offset = 0;
garyservin 0:a906bb7c7831 193 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 194 union {
garyservin 0:a906bb7c7831 195 double real;
garyservin 0:a906bb7c7831 196 uint64_t base;
garyservin 0:a906bb7c7831 197 } u_set_point;
garyservin 0:a906bb7c7831 198 u_set_point.base = 0;
garyservin 0:a906bb7c7831 199 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 200 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 201 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 202 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 203 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 204 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 205 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 206 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 207 this->set_point = u_set_point.real;
garyservin 0:a906bb7c7831 208 offset += sizeof(this->set_point);
garyservin 0:a906bb7c7831 209 union {
garyservin 0:a906bb7c7831 210 double real;
garyservin 0:a906bb7c7831 211 uint64_t base;
garyservin 0:a906bb7c7831 212 } u_process_value;
garyservin 0:a906bb7c7831 213 u_process_value.base = 0;
garyservin 0:a906bb7c7831 214 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 215 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 216 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 217 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 218 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 219 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 220 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 221 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 222 this->process_value = u_process_value.real;
garyservin 0:a906bb7c7831 223 offset += sizeof(this->process_value);
garyservin 0:a906bb7c7831 224 union {
garyservin 0:a906bb7c7831 225 double real;
garyservin 0:a906bb7c7831 226 uint64_t base;
garyservin 0:a906bb7c7831 227 } u_process_value_dot;
garyservin 0:a906bb7c7831 228 u_process_value_dot.base = 0;
garyservin 0:a906bb7c7831 229 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 230 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 231 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 232 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 233 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 234 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 235 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 236 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 237 this->process_value_dot = u_process_value_dot.real;
garyservin 0:a906bb7c7831 238 offset += sizeof(this->process_value_dot);
garyservin 0:a906bb7c7831 239 union {
garyservin 0:a906bb7c7831 240 double real;
garyservin 0:a906bb7c7831 241 uint64_t base;
garyservin 0:a906bb7c7831 242 } u_error;
garyservin 0:a906bb7c7831 243 u_error.base = 0;
garyservin 0:a906bb7c7831 244 u_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 245 u_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 246 u_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 247 u_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 248 u_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 249 u_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 250 u_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 251 u_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 252 this->error = u_error.real;
garyservin 0:a906bb7c7831 253 offset += sizeof(this->error);
garyservin 0:a906bb7c7831 254 union {
garyservin 0:a906bb7c7831 255 double real;
garyservin 0:a906bb7c7831 256 uint64_t base;
garyservin 0:a906bb7c7831 257 } u_time_step;
garyservin 0:a906bb7c7831 258 u_time_step.base = 0;
garyservin 0:a906bb7c7831 259 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 260 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 261 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 262 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 263 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 264 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 265 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 266 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 267 this->time_step = u_time_step.real;
garyservin 0:a906bb7c7831 268 offset += sizeof(this->time_step);
garyservin 0:a906bb7c7831 269 union {
garyservin 0:a906bb7c7831 270 double real;
garyservin 0:a906bb7c7831 271 uint64_t base;
garyservin 0:a906bb7c7831 272 } u_command;
garyservin 0:a906bb7c7831 273 u_command.base = 0;
garyservin 0:a906bb7c7831 274 u_command.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 275 u_command.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 276 u_command.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 277 u_command.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 278 u_command.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 279 u_command.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 280 u_command.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 281 u_command.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 282 this->command = u_command.real;
garyservin 0:a906bb7c7831 283 offset += sizeof(this->command);
garyservin 0:a906bb7c7831 284 union {
garyservin 0:a906bb7c7831 285 double real;
garyservin 0:a906bb7c7831 286 uint64_t base;
garyservin 0:a906bb7c7831 287 } u_p;
garyservin 0:a906bb7c7831 288 u_p.base = 0;
garyservin 0:a906bb7c7831 289 u_p.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 290 u_p.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 291 u_p.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 292 u_p.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 293 u_p.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 294 u_p.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 295 u_p.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 296 u_p.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 297 this->p = u_p.real;
garyservin 0:a906bb7c7831 298 offset += sizeof(this->p);
garyservin 0:a906bb7c7831 299 union {
garyservin 0:a906bb7c7831 300 double real;
garyservin 0:a906bb7c7831 301 uint64_t base;
garyservin 0:a906bb7c7831 302 } u_i;
garyservin 0:a906bb7c7831 303 u_i.base = 0;
garyservin 0:a906bb7c7831 304 u_i.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 305 u_i.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 306 u_i.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 307 u_i.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 308 u_i.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 309 u_i.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 310 u_i.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 311 u_i.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 312 this->i = u_i.real;
garyservin 0:a906bb7c7831 313 offset += sizeof(this->i);
garyservin 0:a906bb7c7831 314 union {
garyservin 0:a906bb7c7831 315 double real;
garyservin 0:a906bb7c7831 316 uint64_t base;
garyservin 0:a906bb7c7831 317 } u_d;
garyservin 0:a906bb7c7831 318 u_d.base = 0;
garyservin 0:a906bb7c7831 319 u_d.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 320 u_d.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 321 u_d.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 322 u_d.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 323 u_d.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 324 u_d.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 325 u_d.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 326 u_d.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 327 this->d = u_d.real;
garyservin 0:a906bb7c7831 328 offset += sizeof(this->d);
garyservin 0:a906bb7c7831 329 union {
garyservin 0:a906bb7c7831 330 double real;
garyservin 0:a906bb7c7831 331 uint64_t base;
garyservin 0:a906bb7c7831 332 } u_i_clamp;
garyservin 0:a906bb7c7831 333 u_i_clamp.base = 0;
garyservin 0:a906bb7c7831 334 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 335 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 336 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 337 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 338 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 339 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 340 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 341 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 342 this->i_clamp = u_i_clamp.real;
garyservin 0:a906bb7c7831 343 offset += sizeof(this->i_clamp);
garyservin 0:a906bb7c7831 344 return offset;
garyservin 0:a906bb7c7831 345 }
garyservin 0:a906bb7c7831 346
garyservin 0:a906bb7c7831 347 const char * getType(){ return "control_msgs/JointControllerState"; };
garyservin 0:a906bb7c7831 348 const char * getMD5(){ return "c0d034a7bf20aeb1c37f3eccb7992b69"; };
garyservin 0:a906bb7c7831 349
garyservin 0:a906bb7c7831 350 };
garyservin 0:a906bb7c7831 351
garyservin 0:a906bb7c7831 352 }
garyservin 0:a906bb7c7831 353 #endif