ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_kinetic s-rov-firmware ROS_HCSR04 DISCO-F469NI_LCDTS_demo ... more

ROSSerial_mbed for Kinetic 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_kinetic

rosserial_mbed Hello World example for Kinetic Kame 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:
Sat Dec 31 00:59:58 2016 +0000
Revision:
1:a849bf78d77f
Parent:
0:9e9b7db60fd5
Add missing round() method

Who changed what in which revision?

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