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_SERVICE_Test_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_Test_h
garyservin 0:fd24f7ca9688 3 #include <stdint.h>
garyservin 0:fd24f7ca9688 4 #include <string.h>
garyservin 0:fd24f7ca9688 5 #include <stdlib.h>
garyservin 0:fd24f7ca9688 6 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 7
garyservin 0:fd24f7ca9688 8 namespace rosserial_mbed
garyservin 0:fd24f7ca9688 9 {
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 static const char TEST[] = "rosserial_mbed/Test";
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class TestRequest : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 const char* input;
garyservin 0:fd24f7ca9688 17
garyservin 0:fd24f7ca9688 18 TestRequest():
garyservin 0:fd24f7ca9688 19 input("")
garyservin 0:fd24f7ca9688 20 {
garyservin 0:fd24f7ca9688 21 }
garyservin 0:fd24f7ca9688 22
garyservin 0:fd24f7ca9688 23 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 24 {
garyservin 0:fd24f7ca9688 25 int offset = 0;
garyservin 0:fd24f7ca9688 26 uint32_t length_input = strlen(this->input);
garyservin 0:fd24f7ca9688 27 memcpy(outbuffer + offset, &length_input, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 28 offset += 4;
garyservin 0:fd24f7ca9688 29 memcpy(outbuffer + offset, this->input, length_input);
garyservin 0:fd24f7ca9688 30 offset += length_input;
garyservin 0:fd24f7ca9688 31 return offset;
garyservin 0:fd24f7ca9688 32 }
garyservin 0:fd24f7ca9688 33
garyservin 0:fd24f7ca9688 34 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 35 {
garyservin 0:fd24f7ca9688 36 int offset = 0;
garyservin 0:fd24f7ca9688 37 uint32_t length_input;
garyservin 0:fd24f7ca9688 38 memcpy(&length_input, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 39 offset += 4;
garyservin 0:fd24f7ca9688 40 for(unsigned int k= offset; k< offset+length_input; ++k){
garyservin 0:fd24f7ca9688 41 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 42 }
garyservin 0:fd24f7ca9688 43 inbuffer[offset+length_input-1]=0;
garyservin 0:fd24f7ca9688 44 this->input = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 45 offset += length_input;
garyservin 0:fd24f7ca9688 46 return offset;
garyservin 0:fd24f7ca9688 47 }
garyservin 0:fd24f7ca9688 48
garyservin 0:fd24f7ca9688 49 const char * getType(){ return TEST; };
garyservin 0:fd24f7ca9688 50 const char * getMD5(){ return "39e92f1778057359c64c7b8a7d7b19de"; };
garyservin 0:fd24f7ca9688 51
garyservin 0:fd24f7ca9688 52 };
garyservin 0:fd24f7ca9688 53
garyservin 0:fd24f7ca9688 54 class TestResponse : public ros::Msg
garyservin 0:fd24f7ca9688 55 {
garyservin 0:fd24f7ca9688 56 public:
garyservin 0:fd24f7ca9688 57 const char* output;
garyservin 0:fd24f7ca9688 58
garyservin 0:fd24f7ca9688 59 TestResponse():
garyservin 0:fd24f7ca9688 60 output("")
garyservin 0:fd24f7ca9688 61 {
garyservin 0:fd24f7ca9688 62 }
garyservin 0:fd24f7ca9688 63
garyservin 0:fd24f7ca9688 64 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 65 {
garyservin 0:fd24f7ca9688 66 int offset = 0;
garyservin 0:fd24f7ca9688 67 uint32_t length_output = strlen(this->output);
garyservin 0:fd24f7ca9688 68 memcpy(outbuffer + offset, &length_output, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 69 offset += 4;
garyservin 0:fd24f7ca9688 70 memcpy(outbuffer + offset, this->output, length_output);
garyservin 0:fd24f7ca9688 71 offset += length_output;
garyservin 0:fd24f7ca9688 72 return offset;
garyservin 0:fd24f7ca9688 73 }
garyservin 0:fd24f7ca9688 74
garyservin 0:fd24f7ca9688 75 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 76 {
garyservin 0:fd24f7ca9688 77 int offset = 0;
garyservin 0:fd24f7ca9688 78 uint32_t length_output;
garyservin 0:fd24f7ca9688 79 memcpy(&length_output, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 80 offset += 4;
garyservin 0:fd24f7ca9688 81 for(unsigned int k= offset; k< offset+length_output; ++k){
garyservin 0:fd24f7ca9688 82 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 83 }
garyservin 0:fd24f7ca9688 84 inbuffer[offset+length_output-1]=0;
garyservin 0:fd24f7ca9688 85 this->output = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 86 offset += length_output;
garyservin 0:fd24f7ca9688 87 return offset;
garyservin 0:fd24f7ca9688 88 }
garyservin 0:fd24f7ca9688 89
garyservin 0:fd24f7ca9688 90 const char * getType(){ return TEST; };
garyservin 0:fd24f7ca9688 91 const char * getMD5(){ return "0825d95fdfa2c8f4bbb4e9c74bccd3fd"; };
garyservin 0:fd24f7ca9688 92
garyservin 0:fd24f7ca9688 93 };
garyservin 0:fd24f7ca9688 94
garyservin 0:fd24f7ca9688 95 class Test {
garyservin 0:fd24f7ca9688 96 public:
garyservin 0:fd24f7ca9688 97 typedef TestRequest Request;
garyservin 0:fd24f7ca9688 98 typedef TestResponse Response;
garyservin 0:fd24f7ca9688 99 };
garyservin 0:fd24f7ca9688 100
garyservin 0:fd24f7ca9688 101 }
garyservin 0:fd24f7ca9688 102 #endif