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_actionlib_tutorials_FibonacciResult_h
garyservin 0:a906bb7c7831 2 #define _ROS_actionlib_tutorials_FibonacciResult_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
garyservin 0:a906bb7c7831 9 namespace actionlib_tutorials
garyservin 0:a906bb7c7831 10 {
garyservin 0:a906bb7c7831 11
garyservin 0:a906bb7c7831 12 class FibonacciResult : public ros::Msg
garyservin 0:a906bb7c7831 13 {
garyservin 0:a906bb7c7831 14 public:
garyservin 0:a906bb7c7831 15 uint8_t sequence_length;
garyservin 0:a906bb7c7831 16 int32_t st_sequence;
garyservin 0:a906bb7c7831 17 int32_t * sequence;
garyservin 0:a906bb7c7831 18
garyservin 0:a906bb7c7831 19 FibonacciResult():
garyservin 0:a906bb7c7831 20 sequence_length(0), sequence(NULL)
garyservin 0:a906bb7c7831 21 {
garyservin 0:a906bb7c7831 22 }
garyservin 0:a906bb7c7831 23
garyservin 0:a906bb7c7831 24 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 25 {
garyservin 0:a906bb7c7831 26 int offset = 0;
garyservin 0:a906bb7c7831 27 *(outbuffer + offset++) = sequence_length;
garyservin 0:a906bb7c7831 28 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 29 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 30 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 31 for( uint8_t i = 0; i < sequence_length; i++){
garyservin 0:a906bb7c7831 32 union {
garyservin 0:a906bb7c7831 33 int32_t real;
garyservin 0:a906bb7c7831 34 uint32_t base;
garyservin 0:a906bb7c7831 35 } u_sequencei;
garyservin 0:a906bb7c7831 36 u_sequencei.real = this->sequence[i];
garyservin 0:a906bb7c7831 37 *(outbuffer + offset + 0) = (u_sequencei.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 38 *(outbuffer + offset + 1) = (u_sequencei.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 39 *(outbuffer + offset + 2) = (u_sequencei.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 40 *(outbuffer + offset + 3) = (u_sequencei.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 41 offset += sizeof(this->sequence[i]);
garyservin 0:a906bb7c7831 42 }
garyservin 0:a906bb7c7831 43 return offset;
garyservin 0:a906bb7c7831 44 }
garyservin 0:a906bb7c7831 45
garyservin 0:a906bb7c7831 46 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 47 {
garyservin 0:a906bb7c7831 48 int offset = 0;
garyservin 0:a906bb7c7831 49 uint8_t sequence_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 50 if(sequence_lengthT > sequence_length)
garyservin 0:a906bb7c7831 51 this->sequence = (int32_t*)realloc(this->sequence, sequence_lengthT * sizeof(int32_t));
garyservin 0:a906bb7c7831 52 offset += 3;
garyservin 0:a906bb7c7831 53 sequence_length = sequence_lengthT;
garyservin 0:a906bb7c7831 54 for( uint8_t i = 0; i < sequence_length; i++){
garyservin 0:a906bb7c7831 55 union {
garyservin 0:a906bb7c7831 56 int32_t real;
garyservin 0:a906bb7c7831 57 uint32_t base;
garyservin 0:a906bb7c7831 58 } u_st_sequence;
garyservin 0:a906bb7c7831 59 u_st_sequence.base = 0;
garyservin 0:a906bb7c7831 60 u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 61 u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 62 u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 63 u_st_sequence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 64 this->st_sequence = u_st_sequence.real;
garyservin 0:a906bb7c7831 65 offset += sizeof(this->st_sequence);
garyservin 0:a906bb7c7831 66 memcpy( &(this->sequence[i]), &(this->st_sequence), sizeof(int32_t));
garyservin 0:a906bb7c7831 67 }
garyservin 0:a906bb7c7831 68 return offset;
garyservin 0:a906bb7c7831 69 }
garyservin 0:a906bb7c7831 70
garyservin 0:a906bb7c7831 71 const char * getType(){ return "actionlib_tutorials/FibonacciResult"; };
garyservin 0:a906bb7c7831 72 const char * getMD5(){ return "b81e37d2a31925a0e8ae261a8699cb79"; };
garyservin 0:a906bb7c7831 73
garyservin 0:a906bb7c7831 74 };
garyservin 0:a906bb7c7831 75
garyservin 0:a906bb7c7831 76 }
garyservin 0:a906bb7c7831 77 #endif