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