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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_jade

ROSSerial_mbed for Jade Distribution

The Robot Operating System (ROS) is a flexible framework for writing robot software. It is a collection of tools, libraries, and conventions that aim to simplify the task of creating complex and robust robot behavior across a wide variety of robotic platforms.

The rosserial_mbed package allows to write ROS nodes on any mbed enabled devices and have them connected to a running ROS system on your computer using the serial port.

Hello World (example publisher)

Import programrosserial_mbed_hello_world_publisher_jade

rosserial_mbed Hello World example for jade distribution

Running the Code

Now, launch the roscore in a new terminal window:

Quote:

$ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

Quote:

$ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

Quote:

$ rostopic echo chatter

See Also

More examples

Blink

/*
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle nh;
DigitalOut myled(LED1);

void messageCb(const std_msgs::Empty& toggle_msg){
    myled = !myled;   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);

    while (1) {
        nh.spinOnce();
        wait_ms(1);
    }
}

Push

/*
 * Button Example for Rosserial
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Bool.h>

PinName button = p20;

ros::NodeHandle nh;

std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);

DigitalIn button_pin(button);
DigitalOut led_pin(LED1);

bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;

Timer t;
int main() {
    t.start();
    nh.initNode();
    nh.advertise(pub_button);

    //Enable the pullup resistor on the button
    button_pin.mode(PullUp);

    //The button is a normally button
    last_reading = ! button_pin;

    while (1) {
        bool reading = ! button_pin;

        if (last_reading!= reading) {
            last_debounce_time = t.read_ms();
            published = false;
        }

        //if the button value has not changed for the debounce delay, we know its stable
        if ( !published && (t.read_ms() - last_debounce_time)  > debounce_delay) {
            led_pin = reading;
            pushed_msg.data = reading;
            pub_button.publish(&pushed_msg);
            published = true;
        }

        last_reading = reading;

        nh.spinOnce();
    }
}
Committer:
garyservin
Date:
Thu Mar 31 23:23:15 2016 +0000
Revision:
0:a906bb7c7831
ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Who changed what in which revision?

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