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_sensor_msgs_NavSatStatus_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_sensor_msgs_NavSatStatus_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 sensor_msgs
Gary Servin 0:04ac6be8229a 10 {
Gary Servin 0:04ac6be8229a 11
Gary Servin 0:04ac6be8229a 12 class NavSatStatus : public ros::Msg
Gary Servin 0:04ac6be8229a 13 {
Gary Servin 0:04ac6be8229a 14 public:
Gary Servin 0:04ac6be8229a 15 typedef int8_t _status_type;
Gary Servin 0:04ac6be8229a 16 _status_type status;
Gary Servin 0:04ac6be8229a 17 typedef uint16_t _service_type;
Gary Servin 0:04ac6be8229a 18 _service_type service;
Gary Servin 0:04ac6be8229a 19 enum { STATUS_NO_FIX = -1 };
Gary Servin 0:04ac6be8229a 20 enum { STATUS_FIX = 0 };
Gary Servin 0:04ac6be8229a 21 enum { STATUS_SBAS_FIX = 1 };
Gary Servin 0:04ac6be8229a 22 enum { STATUS_GBAS_FIX = 2 };
Gary Servin 0:04ac6be8229a 23 enum { SERVICE_GPS = 1 };
Gary Servin 0:04ac6be8229a 24 enum { SERVICE_GLONASS = 2 };
Gary Servin 0:04ac6be8229a 25 enum { SERVICE_COMPASS = 4 };
Gary Servin 0:04ac6be8229a 26 enum { SERVICE_GALILEO = 8 };
Gary Servin 0:04ac6be8229a 27
Gary Servin 0:04ac6be8229a 28 NavSatStatus():
Gary Servin 0:04ac6be8229a 29 status(0),
Gary Servin 0:04ac6be8229a 30 service(0)
Gary Servin 0:04ac6be8229a 31 {
Gary Servin 0:04ac6be8229a 32 }
Gary Servin 0:04ac6be8229a 33
Gary Servin 0:04ac6be8229a 34 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 35 {
Gary Servin 0:04ac6be8229a 36 int offset = 0;
Gary Servin 0:04ac6be8229a 37 union {
Gary Servin 0:04ac6be8229a 38 int8_t real;
Gary Servin 0:04ac6be8229a 39 uint8_t base;
Gary Servin 0:04ac6be8229a 40 } u_status;
Gary Servin 0:04ac6be8229a 41 u_status.real = this->status;
Gary Servin 0:04ac6be8229a 42 *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 43 offset += sizeof(this->status);
Gary Servin 0:04ac6be8229a 44 *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 45 *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 46 offset += sizeof(this->service);
Gary Servin 0:04ac6be8229a 47 return offset;
Gary Servin 0:04ac6be8229a 48 }
Gary Servin 0:04ac6be8229a 49
Gary Servin 0:04ac6be8229a 50 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 51 {
Gary Servin 0:04ac6be8229a 52 int offset = 0;
Gary Servin 0:04ac6be8229a 53 union {
Gary Servin 0:04ac6be8229a 54 int8_t real;
Gary Servin 0:04ac6be8229a 55 uint8_t base;
Gary Servin 0:04ac6be8229a 56 } u_status;
Gary Servin 0:04ac6be8229a 57 u_status.base = 0;
Gary Servin 0:04ac6be8229a 58 u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 59 this->status = u_status.real;
Gary Servin 0:04ac6be8229a 60 offset += sizeof(this->status);
Gary Servin 0:04ac6be8229a 61 this->service = ((uint16_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 62 this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 63 offset += sizeof(this->service);
Gary Servin 0:04ac6be8229a 64 return offset;
Gary Servin 0:04ac6be8229a 65 }
Gary Servin 0:04ac6be8229a 66
Gary Servin 0:04ac6be8229a 67 const char * getType(){ return "sensor_msgs/NavSatStatus"; };
Gary Servin 0:04ac6be8229a 68 const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; };
Gary Servin 0:04ac6be8229a 69
Gary Servin 0:04ac6be8229a 70 };
Gary Servin 0:04ac6be8229a 71
Gary Servin 0:04ac6be8229a 72 }
Gary Servin 0:04ac6be8229a 73 #endif