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_controller_manager_msgs_ControllerStatistics_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_controller_manager_msgs_ControllerStatistics_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 "ros/time.h"
Gary Servin 0:04ac6be8229a 9 #include "ros/duration.h"
Gary Servin 0:04ac6be8229a 10
Gary Servin 0:04ac6be8229a 11 namespace controller_manager_msgs
Gary Servin 0:04ac6be8229a 12 {
Gary Servin 0:04ac6be8229a 13
Gary Servin 0:04ac6be8229a 14 class ControllerStatistics : public ros::Msg
Gary Servin 0:04ac6be8229a 15 {
Gary Servin 0:04ac6be8229a 16 public:
Gary Servin 0:04ac6be8229a 17 typedef const char* _name_type;
Gary Servin 0:04ac6be8229a 18 _name_type name;
Gary Servin 0:04ac6be8229a 19 typedef const char* _type_type;
Gary Servin 0:04ac6be8229a 20 _type_type type;
Gary Servin 0:04ac6be8229a 21 typedef ros::Time _timestamp_type;
Gary Servin 0:04ac6be8229a 22 _timestamp_type timestamp;
Gary Servin 0:04ac6be8229a 23 typedef bool _running_type;
Gary Servin 0:04ac6be8229a 24 _running_type running;
Gary Servin 0:04ac6be8229a 25 typedef ros::Duration _max_time_type;
Gary Servin 0:04ac6be8229a 26 _max_time_type max_time;
Gary Servin 0:04ac6be8229a 27 typedef ros::Duration _mean_time_type;
Gary Servin 0:04ac6be8229a 28 _mean_time_type mean_time;
Gary Servin 0:04ac6be8229a 29 typedef ros::Duration _variance_time_type;
Gary Servin 0:04ac6be8229a 30 _variance_time_type variance_time;
Gary Servin 0:04ac6be8229a 31 typedef int32_t _num_control_loop_overruns_type;
Gary Servin 0:04ac6be8229a 32 _num_control_loop_overruns_type num_control_loop_overruns;
Gary Servin 0:04ac6be8229a 33 typedef ros::Time _time_last_control_loop_overrun_type;
Gary Servin 0:04ac6be8229a 34 _time_last_control_loop_overrun_type time_last_control_loop_overrun;
Gary Servin 0:04ac6be8229a 35
Gary Servin 0:04ac6be8229a 36 ControllerStatistics():
Gary Servin 0:04ac6be8229a 37 name(""),
Gary Servin 0:04ac6be8229a 38 type(""),
Gary Servin 0:04ac6be8229a 39 timestamp(),
Gary Servin 0:04ac6be8229a 40 running(0),
Gary Servin 0:04ac6be8229a 41 max_time(),
Gary Servin 0:04ac6be8229a 42 mean_time(),
Gary Servin 0:04ac6be8229a 43 variance_time(),
Gary Servin 0:04ac6be8229a 44 num_control_loop_overruns(0),
Gary Servin 0:04ac6be8229a 45 time_last_control_loop_overrun()
Gary Servin 0:04ac6be8229a 46 {
Gary Servin 0:04ac6be8229a 47 }
Gary Servin 0:04ac6be8229a 48
Gary Servin 0:04ac6be8229a 49 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 50 {
Gary Servin 0:04ac6be8229a 51 int offset = 0;
Gary Servin 0:04ac6be8229a 52 uint32_t length_name = strlen(this->name);
Gary Servin 0:04ac6be8229a 53 varToArr(outbuffer + offset, length_name);
Gary Servin 0:04ac6be8229a 54 offset += 4;
Gary Servin 0:04ac6be8229a 55 memcpy(outbuffer + offset, this->name, length_name);
Gary Servin 0:04ac6be8229a 56 offset += length_name;
Gary Servin 0:04ac6be8229a 57 uint32_t length_type = strlen(this->type);
Gary Servin 0:04ac6be8229a 58 varToArr(outbuffer + offset, length_type);
Gary Servin 0:04ac6be8229a 59 offset += 4;
Gary Servin 0:04ac6be8229a 60 memcpy(outbuffer + offset, this->type, length_type);
Gary Servin 0:04ac6be8229a 61 offset += length_type;
Gary Servin 0:04ac6be8229a 62 *(outbuffer + offset + 0) = (this->timestamp.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 63 *(outbuffer + offset + 1) = (this->timestamp.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 64 *(outbuffer + offset + 2) = (this->timestamp.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 65 *(outbuffer + offset + 3) = (this->timestamp.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 66 offset += sizeof(this->timestamp.sec);
Gary Servin 0:04ac6be8229a 67 *(outbuffer + offset + 0) = (this->timestamp.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 68 *(outbuffer + offset + 1) = (this->timestamp.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 69 *(outbuffer + offset + 2) = (this->timestamp.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 70 *(outbuffer + offset + 3) = (this->timestamp.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 71 offset += sizeof(this->timestamp.nsec);
Gary Servin 0:04ac6be8229a 72 union {
Gary Servin 0:04ac6be8229a 73 bool real;
Gary Servin 0:04ac6be8229a 74 uint8_t base;
Gary Servin 0:04ac6be8229a 75 } u_running;
Gary Servin 0:04ac6be8229a 76 u_running.real = this->running;
Gary Servin 0:04ac6be8229a 77 *(outbuffer + offset + 0) = (u_running.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 78 offset += sizeof(this->running);
Gary Servin 0:04ac6be8229a 79 *(outbuffer + offset + 0) = (this->max_time.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 80 *(outbuffer + offset + 1) = (this->max_time.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 81 *(outbuffer + offset + 2) = (this->max_time.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 3) = (this->max_time.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 offset += sizeof(this->max_time.sec);
Gary Servin 0:04ac6be8229a 84 *(outbuffer + offset + 0) = (this->max_time.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 85 *(outbuffer + offset + 1) = (this->max_time.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 86 *(outbuffer + offset + 2) = (this->max_time.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 87 *(outbuffer + offset + 3) = (this->max_time.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 88 offset += sizeof(this->max_time.nsec);
Gary Servin 0:04ac6be8229a 89 *(outbuffer + offset + 0) = (this->mean_time.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 90 *(outbuffer + offset + 1) = (this->mean_time.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 91 *(outbuffer + offset + 2) = (this->mean_time.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 92 *(outbuffer + offset + 3) = (this->mean_time.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 93 offset += sizeof(this->mean_time.sec);
Gary Servin 0:04ac6be8229a 94 *(outbuffer + offset + 0) = (this->mean_time.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 95 *(outbuffer + offset + 1) = (this->mean_time.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 96 *(outbuffer + offset + 2) = (this->mean_time.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 97 *(outbuffer + offset + 3) = (this->mean_time.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 98 offset += sizeof(this->mean_time.nsec);
Gary Servin 0:04ac6be8229a 99 *(outbuffer + offset + 0) = (this->variance_time.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 100 *(outbuffer + offset + 1) = (this->variance_time.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 101 *(outbuffer + offset + 2) = (this->variance_time.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 102 *(outbuffer + offset + 3) = (this->variance_time.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 103 offset += sizeof(this->variance_time.sec);
Gary Servin 0:04ac6be8229a 104 *(outbuffer + offset + 0) = (this->variance_time.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 105 *(outbuffer + offset + 1) = (this->variance_time.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 106 *(outbuffer + offset + 2) = (this->variance_time.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 107 *(outbuffer + offset + 3) = (this->variance_time.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 108 offset += sizeof(this->variance_time.nsec);
Gary Servin 0:04ac6be8229a 109 union {
Gary Servin 0:04ac6be8229a 110 int32_t real;
Gary Servin 0:04ac6be8229a 111 uint32_t base;
Gary Servin 0:04ac6be8229a 112 } u_num_control_loop_overruns;
Gary Servin 0:04ac6be8229a 113 u_num_control_loop_overruns.real = this->num_control_loop_overruns;
Gary Servin 0:04ac6be8229a 114 *(outbuffer + offset + 0) = (u_num_control_loop_overruns.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 115 *(outbuffer + offset + 1) = (u_num_control_loop_overruns.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 116 *(outbuffer + offset + 2) = (u_num_control_loop_overruns.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 117 *(outbuffer + offset + 3) = (u_num_control_loop_overruns.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 118 offset += sizeof(this->num_control_loop_overruns);
Gary Servin 0:04ac6be8229a 119 *(outbuffer + offset + 0) = (this->time_last_control_loop_overrun.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 120 *(outbuffer + offset + 1) = (this->time_last_control_loop_overrun.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 121 *(outbuffer + offset + 2) = (this->time_last_control_loop_overrun.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 122 *(outbuffer + offset + 3) = (this->time_last_control_loop_overrun.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 123 offset += sizeof(this->time_last_control_loop_overrun.sec);
Gary Servin 0:04ac6be8229a 124 *(outbuffer + offset + 0) = (this->time_last_control_loop_overrun.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 125 *(outbuffer + offset + 1) = (this->time_last_control_loop_overrun.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 126 *(outbuffer + offset + 2) = (this->time_last_control_loop_overrun.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 127 *(outbuffer + offset + 3) = (this->time_last_control_loop_overrun.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 128 offset += sizeof(this->time_last_control_loop_overrun.nsec);
Gary Servin 0:04ac6be8229a 129 return offset;
Gary Servin 0:04ac6be8229a 130 }
Gary Servin 0:04ac6be8229a 131
Gary Servin 0:04ac6be8229a 132 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 133 {
Gary Servin 0:04ac6be8229a 134 int offset = 0;
Gary Servin 0:04ac6be8229a 135 uint32_t length_name;
Gary Servin 0:04ac6be8229a 136 arrToVar(length_name, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 137 offset += 4;
Gary Servin 0:04ac6be8229a 138 for(unsigned int k= offset; k< offset+length_name; ++k){
Gary Servin 0:04ac6be8229a 139 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 140 }
Gary Servin 0:04ac6be8229a 141 inbuffer[offset+length_name-1]=0;
Gary Servin 0:04ac6be8229a 142 this->name = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 143 offset += length_name;
Gary Servin 0:04ac6be8229a 144 uint32_t length_type;
Gary Servin 0:04ac6be8229a 145 arrToVar(length_type, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 146 offset += 4;
Gary Servin 0:04ac6be8229a 147 for(unsigned int k= offset; k< offset+length_type; ++k){
Gary Servin 0:04ac6be8229a 148 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 149 }
Gary Servin 0:04ac6be8229a 150 inbuffer[offset+length_type-1]=0;
Gary Servin 0:04ac6be8229a 151 this->type = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 152 offset += length_type;
Gary Servin 0:04ac6be8229a 153 this->timestamp.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 154 this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 155 this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 156 this->timestamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 157 offset += sizeof(this->timestamp.sec);
Gary Servin 0:04ac6be8229a 158 this->timestamp.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 159 this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 160 this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 161 this->timestamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 162 offset += sizeof(this->timestamp.nsec);
Gary Servin 0:04ac6be8229a 163 union {
Gary Servin 0:04ac6be8229a 164 bool real;
Gary Servin 0:04ac6be8229a 165 uint8_t base;
Gary Servin 0:04ac6be8229a 166 } u_running;
Gary Servin 0:04ac6be8229a 167 u_running.base = 0;
Gary Servin 0:04ac6be8229a 168 u_running.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 169 this->running = u_running.real;
Gary Servin 0:04ac6be8229a 170 offset += sizeof(this->running);
Gary Servin 0:04ac6be8229a 171 this->max_time.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 172 this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 173 this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 174 this->max_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 175 offset += sizeof(this->max_time.sec);
Gary Servin 0:04ac6be8229a 176 this->max_time.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 177 this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 178 this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 179 this->max_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 180 offset += sizeof(this->max_time.nsec);
Gary Servin 0:04ac6be8229a 181 this->mean_time.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 182 this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 183 this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 184 this->mean_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 185 offset += sizeof(this->mean_time.sec);
Gary Servin 0:04ac6be8229a 186 this->mean_time.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 187 this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 188 this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 189 this->mean_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 190 offset += sizeof(this->mean_time.nsec);
Gary Servin 0:04ac6be8229a 191 this->variance_time.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 192 this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 193 this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 194 this->variance_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 195 offset += sizeof(this->variance_time.sec);
Gary Servin 0:04ac6be8229a 196 this->variance_time.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 197 this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 198 this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 199 this->variance_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 200 offset += sizeof(this->variance_time.nsec);
Gary Servin 0:04ac6be8229a 201 union {
Gary Servin 0:04ac6be8229a 202 int32_t real;
Gary Servin 0:04ac6be8229a 203 uint32_t base;
Gary Servin 0:04ac6be8229a 204 } u_num_control_loop_overruns;
Gary Servin 0:04ac6be8229a 205 u_num_control_loop_overruns.base = 0;
Gary Servin 0:04ac6be8229a 206 u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 207 u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 208 u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 209 u_num_control_loop_overruns.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 210 this->num_control_loop_overruns = u_num_control_loop_overruns.real;
Gary Servin 0:04ac6be8229a 211 offset += sizeof(this->num_control_loop_overruns);
Gary Servin 0:04ac6be8229a 212 this->time_last_control_loop_overrun.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 213 this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 214 this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 215 this->time_last_control_loop_overrun.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 216 offset += sizeof(this->time_last_control_loop_overrun.sec);
Gary Servin 0:04ac6be8229a 217 this->time_last_control_loop_overrun.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 218 this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 219 this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 220 this->time_last_control_loop_overrun.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 221 offset += sizeof(this->time_last_control_loop_overrun.nsec);
Gary Servin 0:04ac6be8229a 222 return offset;
Gary Servin 0:04ac6be8229a 223 }
Gary Servin 0:04ac6be8229a 224
Gary Servin 0:04ac6be8229a 225 const char * getType(){ return "controller_manager_msgs/ControllerStatistics"; };
Gary Servin 0:04ac6be8229a 226 const char * getMD5(){ return "697780c372c8d8597a1436d0e2ad3ba8"; };
Gary Servin 0:04ac6be8229a 227
Gary Servin 0:04ac6be8229a 228 };
Gary Servin 0:04ac6be8229a 229
Gary Servin 0:04ac6be8229a 230 }
Gary Servin 0:04ac6be8229a 231 #endif