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_Range_h
garyservin 0:fd24f7ca9688 2 #define _ROS_sensor_msgs_Range_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
garyservin 0:fd24f7ca9688 10 namespace sensor_msgs
garyservin 0:fd24f7ca9688 11 {
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class Range : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 std_msgs::Header header;
garyservin 0:fd24f7ca9688 17 uint8_t radiation_type;
garyservin 0:fd24f7ca9688 18 float field_of_view;
garyservin 0:fd24f7ca9688 19 float min_range;
garyservin 0:fd24f7ca9688 20 float max_range;
garyservin 0:fd24f7ca9688 21 float range;
garyservin 0:fd24f7ca9688 22 enum { ULTRASOUND = 0 };
garyservin 0:fd24f7ca9688 23 enum { INFRARED = 1 };
garyservin 0:fd24f7ca9688 24
garyservin 0:fd24f7ca9688 25 Range():
garyservin 0:fd24f7ca9688 26 header(),
garyservin 0:fd24f7ca9688 27 radiation_type(0),
garyservin 0:fd24f7ca9688 28 field_of_view(0),
garyservin 0:fd24f7ca9688 29 min_range(0),
garyservin 0:fd24f7ca9688 30 max_range(0),
garyservin 0:fd24f7ca9688 31 range(0)
garyservin 0:fd24f7ca9688 32 {
garyservin 0:fd24f7ca9688 33 }
garyservin 0:fd24f7ca9688 34
garyservin 0:fd24f7ca9688 35 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 36 {
garyservin 0:fd24f7ca9688 37 int offset = 0;
garyservin 0:fd24f7ca9688 38 offset += this->header.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 39 *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 40 offset += sizeof(this->radiation_type);
garyservin 0:fd24f7ca9688 41 union {
garyservin 0:fd24f7ca9688 42 float real;
garyservin 0:fd24f7ca9688 43 uint32_t base;
garyservin 0:fd24f7ca9688 44 } u_field_of_view;
garyservin 0:fd24f7ca9688 45 u_field_of_view.real = this->field_of_view;
garyservin 0:fd24f7ca9688 46 *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 47 *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 48 *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 49 *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 50 offset += sizeof(this->field_of_view);
garyservin 0:fd24f7ca9688 51 union {
garyservin 0:fd24f7ca9688 52 float real;
garyservin 0:fd24f7ca9688 53 uint32_t base;
garyservin 0:fd24f7ca9688 54 } u_min_range;
garyservin 0:fd24f7ca9688 55 u_min_range.real = this->min_range;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 57 *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 58 *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 59 *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 60 offset += sizeof(this->min_range);
garyservin 0:fd24f7ca9688 61 union {
garyservin 0:fd24f7ca9688 62 float real;
garyservin 0:fd24f7ca9688 63 uint32_t base;
garyservin 0:fd24f7ca9688 64 } u_max_range;
garyservin 0:fd24f7ca9688 65 u_max_range.real = this->max_range;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 67 *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 69 *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 70 offset += sizeof(this->max_range);
garyservin 0:fd24f7ca9688 71 union {
garyservin 0:fd24f7ca9688 72 float real;
garyservin 0:fd24f7ca9688 73 uint32_t base;
garyservin 0:fd24f7ca9688 74 } u_range;
garyservin 0:fd24f7ca9688 75 u_range.real = this->range;
garyservin 0:fd24f7ca9688 76 *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 77 *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 78 *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 79 *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 80 offset += sizeof(this->range);
garyservin 0:fd24f7ca9688 81 return offset;
garyservin 0:fd24f7ca9688 82 }
garyservin 0:fd24f7ca9688 83
garyservin 0:fd24f7ca9688 84 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 85 {
garyservin 0:fd24f7ca9688 86 int offset = 0;
garyservin 0:fd24f7ca9688 87 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 88 this->radiation_type = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 89 offset += sizeof(this->radiation_type);
garyservin 0:fd24f7ca9688 90 union {
garyservin 0:fd24f7ca9688 91 float real;
garyservin 0:fd24f7ca9688 92 uint32_t base;
garyservin 0:fd24f7ca9688 93 } u_field_of_view;
garyservin 0:fd24f7ca9688 94 u_field_of_view.base = 0;
garyservin 0:fd24f7ca9688 95 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 96 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 97 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 98 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 99 this->field_of_view = u_field_of_view.real;
garyservin 0:fd24f7ca9688 100 offset += sizeof(this->field_of_view);
garyservin 0:fd24f7ca9688 101 union {
garyservin 0:fd24f7ca9688 102 float real;
garyservin 0:fd24f7ca9688 103 uint32_t base;
garyservin 0:fd24f7ca9688 104 } u_min_range;
garyservin 0:fd24f7ca9688 105 u_min_range.base = 0;
garyservin 0:fd24f7ca9688 106 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 107 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 108 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 109 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 110 this->min_range = u_min_range.real;
garyservin 0:fd24f7ca9688 111 offset += sizeof(this->min_range);
garyservin 0:fd24f7ca9688 112 union {
garyservin 0:fd24f7ca9688 113 float real;
garyservin 0:fd24f7ca9688 114 uint32_t base;
garyservin 0:fd24f7ca9688 115 } u_max_range;
garyservin 0:fd24f7ca9688 116 u_max_range.base = 0;
garyservin 0:fd24f7ca9688 117 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 118 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 119 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 120 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 121 this->max_range = u_max_range.real;
garyservin 0:fd24f7ca9688 122 offset += sizeof(this->max_range);
garyservin 0:fd24f7ca9688 123 union {
garyservin 0:fd24f7ca9688 124 float real;
garyservin 0:fd24f7ca9688 125 uint32_t base;
garyservin 0:fd24f7ca9688 126 } u_range;
garyservin 0:fd24f7ca9688 127 u_range.base = 0;
garyservin 0:fd24f7ca9688 128 u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 129 u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 130 u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 131 u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 132 this->range = u_range.real;
garyservin 0:fd24f7ca9688 133 offset += sizeof(this->range);
garyservin 0:fd24f7ca9688 134 return offset;
garyservin 0:fd24f7ca9688 135 }
garyservin 0:fd24f7ca9688 136
garyservin 0:fd24f7ca9688 137 const char * getType(){ return "sensor_msgs/Range"; };
garyservin 0:fd24f7ca9688 138 const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; };
garyservin 0:fd24f7ca9688 139
garyservin 0:fd24f7ca9688 140 };
garyservin 0:fd24f7ca9688 141
garyservin 0:fd24f7ca9688 142 }
garyservin 0:fd24f7ca9688 143 #endif