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_rosserial_mbed_Adc_h
garyservin 0:a906bb7c7831 2 #define _ROS_rosserial_mbed_Adc_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 rosserial_mbed
garyservin 0:a906bb7c7831 10 {
garyservin 0:a906bb7c7831 11
garyservin 0:a906bb7c7831 12 class Adc : public ros::Msg
garyservin 0:a906bb7c7831 13 {
garyservin 0:a906bb7c7831 14 public:
garyservin 0:a906bb7c7831 15 uint16_t adc0;
garyservin 0:a906bb7c7831 16 uint16_t adc1;
garyservin 0:a906bb7c7831 17 uint16_t adc2;
garyservin 0:a906bb7c7831 18 uint16_t adc3;
garyservin 0:a906bb7c7831 19 uint16_t adc4;
garyservin 0:a906bb7c7831 20 uint16_t adc5;
garyservin 0:a906bb7c7831 21
garyservin 0:a906bb7c7831 22 Adc():
garyservin 0:a906bb7c7831 23 adc0(0),
garyservin 0:a906bb7c7831 24 adc1(0),
garyservin 0:a906bb7c7831 25 adc2(0),
garyservin 0:a906bb7c7831 26 adc3(0),
garyservin 0:a906bb7c7831 27 adc4(0),
garyservin 0:a906bb7c7831 28 adc5(0)
garyservin 0:a906bb7c7831 29 {
garyservin 0:a906bb7c7831 30 }
garyservin 0:a906bb7c7831 31
garyservin 0:a906bb7c7831 32 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 33 {
garyservin 0:a906bb7c7831 34 int offset = 0;
garyservin 0:a906bb7c7831 35 *(outbuffer + offset + 0) = (this->adc0 >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 36 *(outbuffer + offset + 1) = (this->adc0 >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 37 offset += sizeof(this->adc0);
garyservin 0:a906bb7c7831 38 *(outbuffer + offset + 0) = (this->adc1 >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 39 *(outbuffer + offset + 1) = (this->adc1 >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 40 offset += sizeof(this->adc1);
garyservin 0:a906bb7c7831 41 *(outbuffer + offset + 0) = (this->adc2 >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 42 *(outbuffer + offset + 1) = (this->adc2 >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 43 offset += sizeof(this->adc2);
garyservin 0:a906bb7c7831 44 *(outbuffer + offset + 0) = (this->adc3 >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 45 *(outbuffer + offset + 1) = (this->adc3 >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 46 offset += sizeof(this->adc3);
garyservin 0:a906bb7c7831 47 *(outbuffer + offset + 0) = (this->adc4 >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 48 *(outbuffer + offset + 1) = (this->adc4 >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 49 offset += sizeof(this->adc4);
garyservin 0:a906bb7c7831 50 *(outbuffer + offset + 0) = (this->adc5 >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 51 *(outbuffer + offset + 1) = (this->adc5 >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 52 offset += sizeof(this->adc5);
garyservin 0:a906bb7c7831 53 return offset;
garyservin 0:a906bb7c7831 54 }
garyservin 0:a906bb7c7831 55
garyservin 0:a906bb7c7831 56 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 57 {
garyservin 0:a906bb7c7831 58 int offset = 0;
garyservin 0:a906bb7c7831 59 this->adc0 = ((uint16_t) (*(inbuffer + offset)));
garyservin 0:a906bb7c7831 60 this->adc0 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 61 offset += sizeof(this->adc0);
garyservin 0:a906bb7c7831 62 this->adc1 = ((uint16_t) (*(inbuffer + offset)));
garyservin 0:a906bb7c7831 63 this->adc1 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 64 offset += sizeof(this->adc1);
garyservin 0:a906bb7c7831 65 this->adc2 = ((uint16_t) (*(inbuffer + offset)));
garyservin 0:a906bb7c7831 66 this->adc2 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 67 offset += sizeof(this->adc2);
garyservin 0:a906bb7c7831 68 this->adc3 = ((uint16_t) (*(inbuffer + offset)));
garyservin 0:a906bb7c7831 69 this->adc3 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 70 offset += sizeof(this->adc3);
garyservin 0:a906bb7c7831 71 this->adc4 = ((uint16_t) (*(inbuffer + offset)));
garyservin 0:a906bb7c7831 72 this->adc4 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 73 offset += sizeof(this->adc4);
garyservin 0:a906bb7c7831 74 this->adc5 = ((uint16_t) (*(inbuffer + offset)));
garyservin 0:a906bb7c7831 75 this->adc5 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 76 offset += sizeof(this->adc5);
garyservin 0:a906bb7c7831 77 return offset;
garyservin 0:a906bb7c7831 78 }
garyservin 0:a906bb7c7831 79
garyservin 0:a906bb7c7831 80 const char * getType(){ return "rosserial_mbed/Adc"; };
garyservin 0:a906bb7c7831 81 const char * getMD5(){ return "6d7853a614e2e821319068311f2af25b"; };
garyservin 0:a906bb7c7831 82
garyservin 0:a906bb7c7831 83 };
garyservin 0:a906bb7c7831 84
garyservin 0:a906bb7c7831 85 }
garyservin 0:a906bb7c7831 86 #endif