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_rosserial_msgs_TopicInfo_h
garyservin 0:fd24f7ca9688 2 #define _ROS_rosserial_msgs_TopicInfo_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
garyservin 0:fd24f7ca9688 9 namespace rosserial_msgs
garyservin 0:fd24f7ca9688 10 {
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 class TopicInfo : public ros::Msg
garyservin 0:fd24f7ca9688 13 {
garyservin 0:fd24f7ca9688 14 public:
garyservin 0:fd24f7ca9688 15 uint16_t topic_id;
garyservin 0:fd24f7ca9688 16 const char* topic_name;
garyservin 0:fd24f7ca9688 17 const char* message_type;
garyservin 0:fd24f7ca9688 18 const char* md5sum;
garyservin 0:fd24f7ca9688 19 int32_t buffer_size;
garyservin 0:fd24f7ca9688 20 enum { ID_PUBLISHER = 0 };
garyservin 0:fd24f7ca9688 21 enum { ID_SUBSCRIBER = 1 };
garyservin 0:fd24f7ca9688 22 enum { ID_SERVICE_SERVER = 2 };
garyservin 0:fd24f7ca9688 23 enum { ID_SERVICE_CLIENT = 4 };
garyservin 0:fd24f7ca9688 24 enum { ID_PARAMETER_REQUEST = 6 };
garyservin 0:fd24f7ca9688 25 enum { ID_LOG = 7 };
garyservin 0:fd24f7ca9688 26 enum { ID_TIME = 10 };
garyservin 0:fd24f7ca9688 27 enum { ID_TX_STOP = 11 };
garyservin 0:fd24f7ca9688 28
garyservin 0:fd24f7ca9688 29 TopicInfo():
garyservin 0:fd24f7ca9688 30 topic_id(0),
garyservin 0:fd24f7ca9688 31 topic_name(""),
garyservin 0:fd24f7ca9688 32 message_type(""),
garyservin 0:fd24f7ca9688 33 md5sum(""),
garyservin 0:fd24f7ca9688 34 buffer_size(0)
garyservin 0:fd24f7ca9688 35 {
garyservin 0:fd24f7ca9688 36 }
garyservin 0:fd24f7ca9688 37
garyservin 0:fd24f7ca9688 38 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 39 {
garyservin 0:fd24f7ca9688 40 int offset = 0;
garyservin 0:fd24f7ca9688 41 *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 42 *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 43 offset += sizeof(this->topic_id);
garyservin 0:fd24f7ca9688 44 uint32_t length_topic_name = strlen(this->topic_name);
garyservin 0:fd24f7ca9688 45 memcpy(outbuffer + offset, &length_topic_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 46 offset += 4;
garyservin 0:fd24f7ca9688 47 memcpy(outbuffer + offset, this->topic_name, length_topic_name);
garyservin 0:fd24f7ca9688 48 offset += length_topic_name;
garyservin 0:fd24f7ca9688 49 uint32_t length_message_type = strlen(this->message_type);
garyservin 0:fd24f7ca9688 50 memcpy(outbuffer + offset, &length_message_type, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 51 offset += 4;
garyservin 0:fd24f7ca9688 52 memcpy(outbuffer + offset, this->message_type, length_message_type);
garyservin 0:fd24f7ca9688 53 offset += length_message_type;
garyservin 0:fd24f7ca9688 54 uint32_t length_md5sum = strlen(this->md5sum);
garyservin 0:fd24f7ca9688 55 memcpy(outbuffer + offset, &length_md5sum, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 56 offset += 4;
garyservin 0:fd24f7ca9688 57 memcpy(outbuffer + offset, this->md5sum, length_md5sum);
garyservin 0:fd24f7ca9688 58 offset += length_md5sum;
garyservin 0:fd24f7ca9688 59 union {
garyservin 0:fd24f7ca9688 60 int32_t real;
garyservin 0:fd24f7ca9688 61 uint32_t base;
garyservin 0:fd24f7ca9688 62 } u_buffer_size;
garyservin 0:fd24f7ca9688 63 u_buffer_size.real = this->buffer_size;
garyservin 0:fd24f7ca9688 64 *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 65 *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 67 *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 68 offset += sizeof(this->buffer_size);
garyservin 0:fd24f7ca9688 69 return offset;
garyservin 0:fd24f7ca9688 70 }
garyservin 0:fd24f7ca9688 71
garyservin 0:fd24f7ca9688 72 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 73 {
garyservin 0:fd24f7ca9688 74 int offset = 0;
garyservin 0:fd24f7ca9688 75 this->topic_id = ((uint16_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 76 this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 77 offset += sizeof(this->topic_id);
garyservin 0:fd24f7ca9688 78 uint32_t length_topic_name;
garyservin 0:fd24f7ca9688 79 memcpy(&length_topic_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 80 offset += 4;
garyservin 0:fd24f7ca9688 81 for(unsigned int k= offset; k< offset+length_topic_name; ++k){
garyservin 0:fd24f7ca9688 82 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 83 }
garyservin 0:fd24f7ca9688 84 inbuffer[offset+length_topic_name-1]=0;
garyservin 0:fd24f7ca9688 85 this->topic_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 86 offset += length_topic_name;
garyservin 0:fd24f7ca9688 87 uint32_t length_message_type;
garyservin 0:fd24f7ca9688 88 memcpy(&length_message_type, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 89 offset += 4;
garyservin 0:fd24f7ca9688 90 for(unsigned int k= offset; k< offset+length_message_type; ++k){
garyservin 0:fd24f7ca9688 91 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 92 }
garyservin 0:fd24f7ca9688 93 inbuffer[offset+length_message_type-1]=0;
garyservin 0:fd24f7ca9688 94 this->message_type = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 95 offset += length_message_type;
garyservin 0:fd24f7ca9688 96 uint32_t length_md5sum;
garyservin 0:fd24f7ca9688 97 memcpy(&length_md5sum, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 98 offset += 4;
garyservin 0:fd24f7ca9688 99 for(unsigned int k= offset; k< offset+length_md5sum; ++k){
garyservin 0:fd24f7ca9688 100 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 101 }
garyservin 0:fd24f7ca9688 102 inbuffer[offset+length_md5sum-1]=0;
garyservin 0:fd24f7ca9688 103 this->md5sum = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 104 offset += length_md5sum;
garyservin 0:fd24f7ca9688 105 union {
garyservin 0:fd24f7ca9688 106 int32_t real;
garyservin 0:fd24f7ca9688 107 uint32_t base;
garyservin 0:fd24f7ca9688 108 } u_buffer_size;
garyservin 0:fd24f7ca9688 109 u_buffer_size.base = 0;
garyservin 0:fd24f7ca9688 110 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 111 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 112 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 113 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 114 this->buffer_size = u_buffer_size.real;
garyservin 0:fd24f7ca9688 115 offset += sizeof(this->buffer_size);
garyservin 0:fd24f7ca9688 116 return offset;
garyservin 0:fd24f7ca9688 117 }
garyservin 0:fd24f7ca9688 118
garyservin 0:fd24f7ca9688 119 const char * getType(){ return "rosserial_msgs/TopicInfo"; };
garyservin 0:fd24f7ca9688 120 const char * getMD5(){ return "0ad51f88fc44892f8c10684077646005"; };
garyservin 0:fd24f7ca9688 121
garyservin 0:fd24f7ca9688 122 };
garyservin 0:fd24f7ca9688 123
garyservin 0:fd24f7ca9688 124 }
garyservin 0:fd24f7ca9688 125 #endif