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_sensor_msgs_MultiEchoLaserScan_h
garyservin 0:fd24f7ca9688 2 #define _ROS_sensor_msgs_MultiEchoLaserScan_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 "std_msgs/Header.h"
garyservin 0:fd24f7ca9688 9 #include "sensor_msgs/LaserEcho.h"
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 namespace sensor_msgs
garyservin 0:fd24f7ca9688 12 {
garyservin 0:fd24f7ca9688 13
garyservin 0:fd24f7ca9688 14 class MultiEchoLaserScan : public ros::Msg
garyservin 0:fd24f7ca9688 15 {
garyservin 0:fd24f7ca9688 16 public:
garyservin 0:fd24f7ca9688 17 std_msgs::Header header;
garyservin 0:fd24f7ca9688 18 float angle_min;
garyservin 0:fd24f7ca9688 19 float angle_max;
garyservin 0:fd24f7ca9688 20 float angle_increment;
garyservin 0:fd24f7ca9688 21 float time_increment;
garyservin 0:fd24f7ca9688 22 float scan_time;
garyservin 0:fd24f7ca9688 23 float range_min;
garyservin 0:fd24f7ca9688 24 float range_max;
garyservin 0:fd24f7ca9688 25 uint8_t ranges_length;
garyservin 0:fd24f7ca9688 26 sensor_msgs::LaserEcho st_ranges;
garyservin 0:fd24f7ca9688 27 sensor_msgs::LaserEcho * ranges;
garyservin 0:fd24f7ca9688 28 uint8_t intensities_length;
garyservin 0:fd24f7ca9688 29 sensor_msgs::LaserEcho st_intensities;
garyservin 0:fd24f7ca9688 30 sensor_msgs::LaserEcho * intensities;
garyservin 0:fd24f7ca9688 31
garyservin 0:fd24f7ca9688 32 MultiEchoLaserScan():
garyservin 0:fd24f7ca9688 33 header(),
garyservin 0:fd24f7ca9688 34 angle_min(0),
garyservin 0:fd24f7ca9688 35 angle_max(0),
garyservin 0:fd24f7ca9688 36 angle_increment(0),
garyservin 0:fd24f7ca9688 37 time_increment(0),
garyservin 0:fd24f7ca9688 38 scan_time(0),
garyservin 0:fd24f7ca9688 39 range_min(0),
garyservin 0:fd24f7ca9688 40 range_max(0),
garyservin 0:fd24f7ca9688 41 ranges_length(0), ranges(NULL),
garyservin 0:fd24f7ca9688 42 intensities_length(0), intensities(NULL)
garyservin 0:fd24f7ca9688 43 {
garyservin 0:fd24f7ca9688 44 }
garyservin 0:fd24f7ca9688 45
garyservin 0:fd24f7ca9688 46 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 47 {
garyservin 0:fd24f7ca9688 48 int offset = 0;
garyservin 0:fd24f7ca9688 49 offset += this->header.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 50 union {
garyservin 0:fd24f7ca9688 51 float real;
garyservin 0:fd24f7ca9688 52 uint32_t base;
garyservin 0:fd24f7ca9688 53 } u_angle_min;
garyservin 0:fd24f7ca9688 54 u_angle_min.real = this->angle_min;
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 57 *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 58 *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 59 offset += sizeof(this->angle_min);
garyservin 0:fd24f7ca9688 60 union {
garyservin 0:fd24f7ca9688 61 float real;
garyservin 0:fd24f7ca9688 62 uint32_t base;
garyservin 0:fd24f7ca9688 63 } u_angle_max;
garyservin 0:fd24f7ca9688 64 u_angle_max.real = this->angle_max;
garyservin 0:fd24f7ca9688 65 *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 67 *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 69 offset += sizeof(this->angle_max);
garyservin 0:fd24f7ca9688 70 union {
garyservin 0:fd24f7ca9688 71 float real;
garyservin 0:fd24f7ca9688 72 uint32_t base;
garyservin 0:fd24f7ca9688 73 } u_angle_increment;
garyservin 0:fd24f7ca9688 74 u_angle_increment.real = this->angle_increment;
garyservin 0:fd24f7ca9688 75 *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 76 *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 77 *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 78 *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 79 offset += sizeof(this->angle_increment);
garyservin 0:fd24f7ca9688 80 union {
garyservin 0:fd24f7ca9688 81 float real;
garyservin 0:fd24f7ca9688 82 uint32_t base;
garyservin 0:fd24f7ca9688 83 } u_time_increment;
garyservin 0:fd24f7ca9688 84 u_time_increment.real = this->time_increment;
garyservin 0:fd24f7ca9688 85 *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 86 *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 87 *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 88 *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 89 offset += sizeof(this->time_increment);
garyservin 0:fd24f7ca9688 90 union {
garyservin 0:fd24f7ca9688 91 float real;
garyservin 0:fd24f7ca9688 92 uint32_t base;
garyservin 0:fd24f7ca9688 93 } u_scan_time;
garyservin 0:fd24f7ca9688 94 u_scan_time.real = this->scan_time;
garyservin 0:fd24f7ca9688 95 *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 96 *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 97 *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 98 *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 99 offset += sizeof(this->scan_time);
garyservin 0:fd24f7ca9688 100 union {
garyservin 0:fd24f7ca9688 101 float real;
garyservin 0:fd24f7ca9688 102 uint32_t base;
garyservin 0:fd24f7ca9688 103 } u_range_min;
garyservin 0:fd24f7ca9688 104 u_range_min.real = this->range_min;
garyservin 0:fd24f7ca9688 105 *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 106 *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 107 *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 108 *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 109 offset += sizeof(this->range_min);
garyservin 0:fd24f7ca9688 110 union {
garyservin 0:fd24f7ca9688 111 float real;
garyservin 0:fd24f7ca9688 112 uint32_t base;
garyservin 0:fd24f7ca9688 113 } u_range_max;
garyservin 0:fd24f7ca9688 114 u_range_max.real = this->range_max;
garyservin 0:fd24f7ca9688 115 *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 116 *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 117 *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 118 *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 119 offset += sizeof(this->range_max);
garyservin 0:fd24f7ca9688 120 *(outbuffer + offset++) = ranges_length;
garyservin 0:fd24f7ca9688 121 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 122 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 123 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 124 for( uint8_t i = 0; i < ranges_length; i++){
garyservin 0:fd24f7ca9688 125 offset += this->ranges[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 126 }
garyservin 0:fd24f7ca9688 127 *(outbuffer + offset++) = intensities_length;
garyservin 0:fd24f7ca9688 128 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 129 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 130 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 131 for( uint8_t i = 0; i < intensities_length; i++){
garyservin 0:fd24f7ca9688 132 offset += this->intensities[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 133 }
garyservin 0:fd24f7ca9688 134 return offset;
garyservin 0:fd24f7ca9688 135 }
garyservin 0:fd24f7ca9688 136
garyservin 0:fd24f7ca9688 137 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 138 {
garyservin 0:fd24f7ca9688 139 int offset = 0;
garyservin 0:fd24f7ca9688 140 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 141 union {
garyservin 0:fd24f7ca9688 142 float real;
garyservin 0:fd24f7ca9688 143 uint32_t base;
garyservin 0:fd24f7ca9688 144 } u_angle_min;
garyservin 0:fd24f7ca9688 145 u_angle_min.base = 0;
garyservin 0:fd24f7ca9688 146 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 147 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 148 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 149 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 150 this->angle_min = u_angle_min.real;
garyservin 0:fd24f7ca9688 151 offset += sizeof(this->angle_min);
garyservin 0:fd24f7ca9688 152 union {
garyservin 0:fd24f7ca9688 153 float real;
garyservin 0:fd24f7ca9688 154 uint32_t base;
garyservin 0:fd24f7ca9688 155 } u_angle_max;
garyservin 0:fd24f7ca9688 156 u_angle_max.base = 0;
garyservin 0:fd24f7ca9688 157 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 158 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 159 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 160 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 161 this->angle_max = u_angle_max.real;
garyservin 0:fd24f7ca9688 162 offset += sizeof(this->angle_max);
garyservin 0:fd24f7ca9688 163 union {
garyservin 0:fd24f7ca9688 164 float real;
garyservin 0:fd24f7ca9688 165 uint32_t base;
garyservin 0:fd24f7ca9688 166 } u_angle_increment;
garyservin 0:fd24f7ca9688 167 u_angle_increment.base = 0;
garyservin 0:fd24f7ca9688 168 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 169 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 170 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 171 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 172 this->angle_increment = u_angle_increment.real;
garyservin 0:fd24f7ca9688 173 offset += sizeof(this->angle_increment);
garyservin 0:fd24f7ca9688 174 union {
garyservin 0:fd24f7ca9688 175 float real;
garyservin 0:fd24f7ca9688 176 uint32_t base;
garyservin 0:fd24f7ca9688 177 } u_time_increment;
garyservin 0:fd24f7ca9688 178 u_time_increment.base = 0;
garyservin 0:fd24f7ca9688 179 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 180 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 181 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 182 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 183 this->time_increment = u_time_increment.real;
garyservin 0:fd24f7ca9688 184 offset += sizeof(this->time_increment);
garyservin 0:fd24f7ca9688 185 union {
garyservin 0:fd24f7ca9688 186 float real;
garyservin 0:fd24f7ca9688 187 uint32_t base;
garyservin 0:fd24f7ca9688 188 } u_scan_time;
garyservin 0:fd24f7ca9688 189 u_scan_time.base = 0;
garyservin 0:fd24f7ca9688 190 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 191 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 192 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 193 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 194 this->scan_time = u_scan_time.real;
garyservin 0:fd24f7ca9688 195 offset += sizeof(this->scan_time);
garyservin 0:fd24f7ca9688 196 union {
garyservin 0:fd24f7ca9688 197 float real;
garyservin 0:fd24f7ca9688 198 uint32_t base;
garyservin 0:fd24f7ca9688 199 } u_range_min;
garyservin 0:fd24f7ca9688 200 u_range_min.base = 0;
garyservin 0:fd24f7ca9688 201 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 202 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 203 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 204 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 205 this->range_min = u_range_min.real;
garyservin 0:fd24f7ca9688 206 offset += sizeof(this->range_min);
garyservin 0:fd24f7ca9688 207 union {
garyservin 0:fd24f7ca9688 208 float real;
garyservin 0:fd24f7ca9688 209 uint32_t base;
garyservin 0:fd24f7ca9688 210 } u_range_max;
garyservin 0:fd24f7ca9688 211 u_range_max.base = 0;
garyservin 0:fd24f7ca9688 212 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 213 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 214 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 215 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 216 this->range_max = u_range_max.real;
garyservin 0:fd24f7ca9688 217 offset += sizeof(this->range_max);
garyservin 0:fd24f7ca9688 218 uint8_t ranges_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 219 if(ranges_lengthT > ranges_length)
garyservin 0:fd24f7ca9688 220 this->ranges = (sensor_msgs::LaserEcho*)realloc(this->ranges, ranges_lengthT * sizeof(sensor_msgs::LaserEcho));
garyservin 0:fd24f7ca9688 221 offset += 3;
garyservin 0:fd24f7ca9688 222 ranges_length = ranges_lengthT;
garyservin 0:fd24f7ca9688 223 for( uint8_t i = 0; i < ranges_length; i++){
garyservin 0:fd24f7ca9688 224 offset += this->st_ranges.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 225 memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(sensor_msgs::LaserEcho));
garyservin 0:fd24f7ca9688 226 }
garyservin 0:fd24f7ca9688 227 uint8_t intensities_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 228 if(intensities_lengthT > intensities_length)
garyservin 0:fd24f7ca9688 229 this->intensities = (sensor_msgs::LaserEcho*)realloc(this->intensities, intensities_lengthT * sizeof(sensor_msgs::LaserEcho));
garyservin 0:fd24f7ca9688 230 offset += 3;
garyservin 0:fd24f7ca9688 231 intensities_length = intensities_lengthT;
garyservin 0:fd24f7ca9688 232 for( uint8_t i = 0; i < intensities_length; i++){
garyservin 0:fd24f7ca9688 233 offset += this->st_intensities.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 234 memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(sensor_msgs::LaserEcho));
garyservin 0:fd24f7ca9688 235 }
garyservin 0:fd24f7ca9688 236 return offset;
garyservin 0:fd24f7ca9688 237 }
garyservin 0:fd24f7ca9688 238
garyservin 0:fd24f7ca9688 239 const char * getType(){ return "sensor_msgs/MultiEchoLaserScan"; };
garyservin 0:fd24f7ca9688 240 const char * getMD5(){ return "6fefb0c6da89d7c8abe4b339f5c2f8fb"; };
garyservin 0:fd24f7ca9688 241
garyservin 0:fd24f7ca9688 242 };
garyservin 0:fd24f7ca9688 243
garyservin 0:fd24f7ca9688 244 }
garyservin 0:fd24f7ca9688 245 #endif