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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

ROSSerial_mbed for Indigo 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

rosserial_mbed Hello World

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 14:22:59 2016 +0000
Revision:
0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_rosgraph_msgs_TopicStatistics_h
garyservin 0:fd24f7ca9688 2 #define _ROS_rosgraph_msgs_TopicStatistics_h
garyservin 0:fd24f7ca9688 3
garyservin 0:fd24f7ca9688 4 #include <stdint.h>
garyservin 0:fd24f7ca9688 5 #include <string.h>
garyservin 0:fd24f7ca9688 6 #include <stdlib.h>
garyservin 0:fd24f7ca9688 7 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 8 #include "ros/time.h"
garyservin 0:fd24f7ca9688 9 #include "ros/duration.h"
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 namespace rosgraph_msgs
garyservin 0:fd24f7ca9688 12 {
garyservin 0:fd24f7ca9688 13
garyservin 0:fd24f7ca9688 14 class TopicStatistics : public ros::Msg
garyservin 0:fd24f7ca9688 15 {
garyservin 0:fd24f7ca9688 16 public:
garyservin 0:fd24f7ca9688 17 const char* topic;
garyservin 0:fd24f7ca9688 18 const char* node_pub;
garyservin 0:fd24f7ca9688 19 const char* node_sub;
garyservin 0:fd24f7ca9688 20 ros::Time window_start;
garyservin 0:fd24f7ca9688 21 ros::Time window_stop;
garyservin 0:fd24f7ca9688 22 int32_t delivered_msgs;
garyservin 0:fd24f7ca9688 23 int32_t dropped_msgs;
garyservin 0:fd24f7ca9688 24 int32_t traffic;
garyservin 0:fd24f7ca9688 25 ros::Duration period_mean;
garyservin 0:fd24f7ca9688 26 ros::Duration period_stddev;
garyservin 0:fd24f7ca9688 27 ros::Duration period_max;
garyservin 0:fd24f7ca9688 28 ros::Duration stamp_age_mean;
garyservin 0:fd24f7ca9688 29 ros::Duration stamp_age_stddev;
garyservin 0:fd24f7ca9688 30 ros::Duration stamp_age_max;
garyservin 0:fd24f7ca9688 31
garyservin 0:fd24f7ca9688 32 TopicStatistics():
garyservin 0:fd24f7ca9688 33 topic(""),
garyservin 0:fd24f7ca9688 34 node_pub(""),
garyservin 0:fd24f7ca9688 35 node_sub(""),
garyservin 0:fd24f7ca9688 36 window_start(),
garyservin 0:fd24f7ca9688 37 window_stop(),
garyservin 0:fd24f7ca9688 38 delivered_msgs(0),
garyservin 0:fd24f7ca9688 39 dropped_msgs(0),
garyservin 0:fd24f7ca9688 40 traffic(0),
garyservin 0:fd24f7ca9688 41 period_mean(),
garyservin 0:fd24f7ca9688 42 period_stddev(),
garyservin 0:fd24f7ca9688 43 period_max(),
garyservin 0:fd24f7ca9688 44 stamp_age_mean(),
garyservin 0:fd24f7ca9688 45 stamp_age_stddev(),
garyservin 0:fd24f7ca9688 46 stamp_age_max()
garyservin 0:fd24f7ca9688 47 {
garyservin 0:fd24f7ca9688 48 }
garyservin 0:fd24f7ca9688 49
garyservin 0:fd24f7ca9688 50 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 51 {
garyservin 0:fd24f7ca9688 52 int offset = 0;
garyservin 0:fd24f7ca9688 53 uint32_t length_topic = strlen(this->topic);
garyservin 0:fd24f7ca9688 54 memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 55 offset += 4;
garyservin 0:fd24f7ca9688 56 memcpy(outbuffer + offset, this->topic, length_topic);
garyservin 0:fd24f7ca9688 57 offset += length_topic;
garyservin 0:fd24f7ca9688 58 uint32_t length_node_pub = strlen(this->node_pub);
garyservin 0:fd24f7ca9688 59 memcpy(outbuffer + offset, &length_node_pub, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 60 offset += 4;
garyservin 0:fd24f7ca9688 61 memcpy(outbuffer + offset, this->node_pub, length_node_pub);
garyservin 0:fd24f7ca9688 62 offset += length_node_pub;
garyservin 0:fd24f7ca9688 63 uint32_t length_node_sub = strlen(this->node_sub);
garyservin 0:fd24f7ca9688 64 memcpy(outbuffer + offset, &length_node_sub, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 65 offset += 4;
garyservin 0:fd24f7ca9688 66 memcpy(outbuffer + offset, this->node_sub, length_node_sub);
garyservin 0:fd24f7ca9688 67 offset += length_node_sub;
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset + 0) = (this->window_start.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 69 *(outbuffer + offset + 1) = (this->window_start.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 70 *(outbuffer + offset + 2) = (this->window_start.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 71 *(outbuffer + offset + 3) = (this->window_start.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 72 offset += sizeof(this->window_start.sec);
garyservin 0:fd24f7ca9688 73 *(outbuffer + offset + 0) = (this->window_start.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 74 *(outbuffer + offset + 1) = (this->window_start.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 75 *(outbuffer + offset + 2) = (this->window_start.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 76 *(outbuffer + offset + 3) = (this->window_start.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 77 offset += sizeof(this->window_start.nsec);
garyservin 0:fd24f7ca9688 78 *(outbuffer + offset + 0) = (this->window_stop.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 79 *(outbuffer + offset + 1) = (this->window_stop.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 80 *(outbuffer + offset + 2) = (this->window_stop.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 81 *(outbuffer + offset + 3) = (this->window_stop.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 82 offset += sizeof(this->window_stop.sec);
garyservin 0:fd24f7ca9688 83 *(outbuffer + offset + 0) = (this->window_stop.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 84 *(outbuffer + offset + 1) = (this->window_stop.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 85 *(outbuffer + offset + 2) = (this->window_stop.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 86 *(outbuffer + offset + 3) = (this->window_stop.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 87 offset += sizeof(this->window_stop.nsec);
garyservin 0:fd24f7ca9688 88 union {
garyservin 0:fd24f7ca9688 89 int32_t real;
garyservin 0:fd24f7ca9688 90 uint32_t base;
garyservin 0:fd24f7ca9688 91 } u_delivered_msgs;
garyservin 0:fd24f7ca9688 92 u_delivered_msgs.real = this->delivered_msgs;
garyservin 0:fd24f7ca9688 93 *(outbuffer + offset + 0) = (u_delivered_msgs.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 94 *(outbuffer + offset + 1) = (u_delivered_msgs.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 95 *(outbuffer + offset + 2) = (u_delivered_msgs.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 96 *(outbuffer + offset + 3) = (u_delivered_msgs.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 97 offset += sizeof(this->delivered_msgs);
garyservin 0:fd24f7ca9688 98 union {
garyservin 0:fd24f7ca9688 99 int32_t real;
garyservin 0:fd24f7ca9688 100 uint32_t base;
garyservin 0:fd24f7ca9688 101 } u_dropped_msgs;
garyservin 0:fd24f7ca9688 102 u_dropped_msgs.real = this->dropped_msgs;
garyservin 0:fd24f7ca9688 103 *(outbuffer + offset + 0) = (u_dropped_msgs.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 104 *(outbuffer + offset + 1) = (u_dropped_msgs.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 105 *(outbuffer + offset + 2) = (u_dropped_msgs.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 106 *(outbuffer + offset + 3) = (u_dropped_msgs.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 107 offset += sizeof(this->dropped_msgs);
garyservin 0:fd24f7ca9688 108 union {
garyservin 0:fd24f7ca9688 109 int32_t real;
garyservin 0:fd24f7ca9688 110 uint32_t base;
garyservin 0:fd24f7ca9688 111 } u_traffic;
garyservin 0:fd24f7ca9688 112 u_traffic.real = this->traffic;
garyservin 0:fd24f7ca9688 113 *(outbuffer + offset + 0) = (u_traffic.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 114 *(outbuffer + offset + 1) = (u_traffic.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 115 *(outbuffer + offset + 2) = (u_traffic.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 116 *(outbuffer + offset + 3) = (u_traffic.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 117 offset += sizeof(this->traffic);
garyservin 0:fd24f7ca9688 118 *(outbuffer + offset + 0) = (this->period_mean.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 119 *(outbuffer + offset + 1) = (this->period_mean.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 120 *(outbuffer + offset + 2) = (this->period_mean.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 121 *(outbuffer + offset + 3) = (this->period_mean.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 122 offset += sizeof(this->period_mean.sec);
garyservin 0:fd24f7ca9688 123 *(outbuffer + offset + 0) = (this->period_mean.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 124 *(outbuffer + offset + 1) = (this->period_mean.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 125 *(outbuffer + offset + 2) = (this->period_mean.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 126 *(outbuffer + offset + 3) = (this->period_mean.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 127 offset += sizeof(this->period_mean.nsec);
garyservin 0:fd24f7ca9688 128 *(outbuffer + offset + 0) = (this->period_stddev.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 129 *(outbuffer + offset + 1) = (this->period_stddev.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 130 *(outbuffer + offset + 2) = (this->period_stddev.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 131 *(outbuffer + offset + 3) = (this->period_stddev.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 132 offset += sizeof(this->period_stddev.sec);
garyservin 0:fd24f7ca9688 133 *(outbuffer + offset + 0) = (this->period_stddev.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 134 *(outbuffer + offset + 1) = (this->period_stddev.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 135 *(outbuffer + offset + 2) = (this->period_stddev.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 136 *(outbuffer + offset + 3) = (this->period_stddev.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 137 offset += sizeof(this->period_stddev.nsec);
garyservin 0:fd24f7ca9688 138 *(outbuffer + offset + 0) = (this->period_max.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 139 *(outbuffer + offset + 1) = (this->period_max.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 140 *(outbuffer + offset + 2) = (this->period_max.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 141 *(outbuffer + offset + 3) = (this->period_max.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 142 offset += sizeof(this->period_max.sec);
garyservin 0:fd24f7ca9688 143 *(outbuffer + offset + 0) = (this->period_max.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 144 *(outbuffer + offset + 1) = (this->period_max.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 145 *(outbuffer + offset + 2) = (this->period_max.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 146 *(outbuffer + offset + 3) = (this->period_max.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 147 offset += sizeof(this->period_max.nsec);
garyservin 0:fd24f7ca9688 148 *(outbuffer + offset + 0) = (this->stamp_age_mean.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 149 *(outbuffer + offset + 1) = (this->stamp_age_mean.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 150 *(outbuffer + offset + 2) = (this->stamp_age_mean.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 151 *(outbuffer + offset + 3) = (this->stamp_age_mean.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 152 offset += sizeof(this->stamp_age_mean.sec);
garyservin 0:fd24f7ca9688 153 *(outbuffer + offset + 0) = (this->stamp_age_mean.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 154 *(outbuffer + offset + 1) = (this->stamp_age_mean.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 155 *(outbuffer + offset + 2) = (this->stamp_age_mean.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 156 *(outbuffer + offset + 3) = (this->stamp_age_mean.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 157 offset += sizeof(this->stamp_age_mean.nsec);
garyservin 0:fd24f7ca9688 158 *(outbuffer + offset + 0) = (this->stamp_age_stddev.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 159 *(outbuffer + offset + 1) = (this->stamp_age_stddev.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 160 *(outbuffer + offset + 2) = (this->stamp_age_stddev.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 161 *(outbuffer + offset + 3) = (this->stamp_age_stddev.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 162 offset += sizeof(this->stamp_age_stddev.sec);
garyservin 0:fd24f7ca9688 163 *(outbuffer + offset + 0) = (this->stamp_age_stddev.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 164 *(outbuffer + offset + 1) = (this->stamp_age_stddev.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 165 *(outbuffer + offset + 2) = (this->stamp_age_stddev.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 166 *(outbuffer + offset + 3) = (this->stamp_age_stddev.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 167 offset += sizeof(this->stamp_age_stddev.nsec);
garyservin 0:fd24f7ca9688 168 *(outbuffer + offset + 0) = (this->stamp_age_max.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 169 *(outbuffer + offset + 1) = (this->stamp_age_max.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 170 *(outbuffer + offset + 2) = (this->stamp_age_max.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 171 *(outbuffer + offset + 3) = (this->stamp_age_max.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 172 offset += sizeof(this->stamp_age_max.sec);
garyservin 0:fd24f7ca9688 173 *(outbuffer + offset + 0) = (this->stamp_age_max.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 174 *(outbuffer + offset + 1) = (this->stamp_age_max.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 175 *(outbuffer + offset + 2) = (this->stamp_age_max.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 176 *(outbuffer + offset + 3) = (this->stamp_age_max.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 177 offset += sizeof(this->stamp_age_max.nsec);
garyservin 0:fd24f7ca9688 178 return offset;
garyservin 0:fd24f7ca9688 179 }
garyservin 0:fd24f7ca9688 180
garyservin 0:fd24f7ca9688 181 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 182 {
garyservin 0:fd24f7ca9688 183 int offset = 0;
garyservin 0:fd24f7ca9688 184 uint32_t length_topic;
garyservin 0:fd24f7ca9688 185 memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 186 offset += 4;
garyservin 0:fd24f7ca9688 187 for(unsigned int k= offset; k< offset+length_topic; ++k){
garyservin 0:fd24f7ca9688 188 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 189 }
garyservin 0:fd24f7ca9688 190 inbuffer[offset+length_topic-1]=0;
garyservin 0:fd24f7ca9688 191 this->topic = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 192 offset += length_topic;
garyservin 0:fd24f7ca9688 193 uint32_t length_node_pub;
garyservin 0:fd24f7ca9688 194 memcpy(&length_node_pub, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 195 offset += 4;
garyservin 0:fd24f7ca9688 196 for(unsigned int k= offset; k< offset+length_node_pub; ++k){
garyservin 0:fd24f7ca9688 197 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 198 }
garyservin 0:fd24f7ca9688 199 inbuffer[offset+length_node_pub-1]=0;
garyservin 0:fd24f7ca9688 200 this->node_pub = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 201 offset += length_node_pub;
garyservin 0:fd24f7ca9688 202 uint32_t length_node_sub;
garyservin 0:fd24f7ca9688 203 memcpy(&length_node_sub, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 204 offset += 4;
garyservin 0:fd24f7ca9688 205 for(unsigned int k= offset; k< offset+length_node_sub; ++k){
garyservin 0:fd24f7ca9688 206 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 207 }
garyservin 0:fd24f7ca9688 208 inbuffer[offset+length_node_sub-1]=0;
garyservin 0:fd24f7ca9688 209 this->node_sub = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 210 offset += length_node_sub;
garyservin 0:fd24f7ca9688 211 this->window_start.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 212 this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 213 this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 214 this->window_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 215 offset += sizeof(this->window_start.sec);
garyservin 0:fd24f7ca9688 216 this->window_start.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 217 this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 218 this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 219 this->window_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 220 offset += sizeof(this->window_start.nsec);
garyservin 0:fd24f7ca9688 221 this->window_stop.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 222 this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 223 this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 224 this->window_stop.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 225 offset += sizeof(this->window_stop.sec);
garyservin 0:fd24f7ca9688 226 this->window_stop.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 227 this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 228 this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 229 this->window_stop.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 230 offset += sizeof(this->window_stop.nsec);
garyservin 0:fd24f7ca9688 231 union {
garyservin 0:fd24f7ca9688 232 int32_t real;
garyservin 0:fd24f7ca9688 233 uint32_t base;
garyservin 0:fd24f7ca9688 234 } u_delivered_msgs;
garyservin 0:fd24f7ca9688 235 u_delivered_msgs.base = 0;
garyservin 0:fd24f7ca9688 236 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 237 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 238 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 239 u_delivered_msgs.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 240 this->delivered_msgs = u_delivered_msgs.real;
garyservin 0:fd24f7ca9688 241 offset += sizeof(this->delivered_msgs);
garyservin 0:fd24f7ca9688 242 union {
garyservin 0:fd24f7ca9688 243 int32_t real;
garyservin 0:fd24f7ca9688 244 uint32_t base;
garyservin 0:fd24f7ca9688 245 } u_dropped_msgs;
garyservin 0:fd24f7ca9688 246 u_dropped_msgs.base = 0;
garyservin 0:fd24f7ca9688 247 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 248 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 249 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 250 u_dropped_msgs.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 251 this->dropped_msgs = u_dropped_msgs.real;
garyservin 0:fd24f7ca9688 252 offset += sizeof(this->dropped_msgs);
garyservin 0:fd24f7ca9688 253 union {
garyservin 0:fd24f7ca9688 254 int32_t real;
garyservin 0:fd24f7ca9688 255 uint32_t base;
garyservin 0:fd24f7ca9688 256 } u_traffic;
garyservin 0:fd24f7ca9688 257 u_traffic.base = 0;
garyservin 0:fd24f7ca9688 258 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 259 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 260 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 261 u_traffic.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 262 this->traffic = u_traffic.real;
garyservin 0:fd24f7ca9688 263 offset += sizeof(this->traffic);
garyservin 0:fd24f7ca9688 264 this->period_mean.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 265 this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 266 this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 267 this->period_mean.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 268 offset += sizeof(this->period_mean.sec);
garyservin 0:fd24f7ca9688 269 this->period_mean.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 270 this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 271 this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 272 this->period_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 273 offset += sizeof(this->period_mean.nsec);
garyservin 0:fd24f7ca9688 274 this->period_stddev.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 275 this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 276 this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 277 this->period_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 278 offset += sizeof(this->period_stddev.sec);
garyservin 0:fd24f7ca9688 279 this->period_stddev.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 280 this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 281 this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 282 this->period_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 283 offset += sizeof(this->period_stddev.nsec);
garyservin 0:fd24f7ca9688 284 this->period_max.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 285 this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 286 this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 287 this->period_max.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 288 offset += sizeof(this->period_max.sec);
garyservin 0:fd24f7ca9688 289 this->period_max.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 290 this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 291 this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 292 this->period_max.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 293 offset += sizeof(this->period_max.nsec);
garyservin 0:fd24f7ca9688 294 this->stamp_age_mean.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 295 this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 296 this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 297 this->stamp_age_mean.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 298 offset += sizeof(this->stamp_age_mean.sec);
garyservin 0:fd24f7ca9688 299 this->stamp_age_mean.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 300 this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 301 this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 302 this->stamp_age_mean.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 303 offset += sizeof(this->stamp_age_mean.nsec);
garyservin 0:fd24f7ca9688 304 this->stamp_age_stddev.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 305 this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 306 this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 307 this->stamp_age_stddev.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 308 offset += sizeof(this->stamp_age_stddev.sec);
garyservin 0:fd24f7ca9688 309 this->stamp_age_stddev.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 310 this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 311 this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 312 this->stamp_age_stddev.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 313 offset += sizeof(this->stamp_age_stddev.nsec);
garyservin 0:fd24f7ca9688 314 this->stamp_age_max.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 315 this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 316 this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 317 this->stamp_age_max.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 318 offset += sizeof(this->stamp_age_max.sec);
garyservin 0:fd24f7ca9688 319 this->stamp_age_max.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 320 this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 321 this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 322 this->stamp_age_max.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 323 offset += sizeof(this->stamp_age_max.nsec);
garyservin 0:fd24f7ca9688 324 return offset;
garyservin 0:fd24f7ca9688 325 }
garyservin 0:fd24f7ca9688 326
garyservin 0:fd24f7ca9688 327 const char * getType(){ return "rosgraph_msgs/TopicStatistics"; };
garyservin 0:fd24f7ca9688 328 const char * getMD5(){ return "10152ed868c5097a5e2e4a89d7daa710"; };
garyservin 0:fd24f7ca9688 329
garyservin 0:fd24f7ca9688 330 };
garyservin 0:fd24f7ca9688 331
garyservin 0:fd24f7ca9688 332 }
garyservin 0:fd24f7ca9688 333 #endif