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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more

ROSSerial_mbed for Melodic 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_melodic

rosserial_mbed Hello World example for Melodic Morenia 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:
Gary Servin
Date:
Fri Nov 08 14:55:04 2019 -0300
Revision:
1:da82487f547e
Parent:
0:04ac6be8229a
Add missing round() method

Who changed what in which revision?

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