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_SERVICE_SetBool_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_SERVICE_SetBool_h
Gary Servin 0:04ac6be8229a 3 #include <stdint.h>
Gary Servin 0:04ac6be8229a 4 #include <string.h>
Gary Servin 0:04ac6be8229a 5 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 6 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 7
Gary Servin 0:04ac6be8229a 8 namespace std_srvs
Gary Servin 0:04ac6be8229a 9 {
Gary Servin 0:04ac6be8229a 10
Gary Servin 0:04ac6be8229a 11 static const char SETBOOL[] = "std_srvs/SetBool";
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 class SetBoolRequest : public ros::Msg
Gary Servin 0:04ac6be8229a 14 {
Gary Servin 0:04ac6be8229a 15 public:
Gary Servin 0:04ac6be8229a 16 typedef bool _data_type;
Gary Servin 0:04ac6be8229a 17 _data_type data;
Gary Servin 0:04ac6be8229a 18
Gary Servin 0:04ac6be8229a 19 SetBoolRequest():
Gary Servin 0:04ac6be8229a 20 data(0)
Gary Servin 0:04ac6be8229a 21 {
Gary Servin 0:04ac6be8229a 22 }
Gary Servin 0:04ac6be8229a 23
Gary Servin 0:04ac6be8229a 24 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 25 {
Gary Servin 0:04ac6be8229a 26 int offset = 0;
Gary Servin 0:04ac6be8229a 27 union {
Gary Servin 0:04ac6be8229a 28 bool real;
Gary Servin 0:04ac6be8229a 29 uint8_t base;
Gary Servin 0:04ac6be8229a 30 } u_data;
Gary Servin 0:04ac6be8229a 31 u_data.real = this->data;
Gary Servin 0:04ac6be8229a 32 *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 33 offset += sizeof(this->data);
Gary Servin 0:04ac6be8229a 34 return offset;
Gary Servin 0:04ac6be8229a 35 }
Gary Servin 0:04ac6be8229a 36
Gary Servin 0:04ac6be8229a 37 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 38 {
Gary Servin 0:04ac6be8229a 39 int offset = 0;
Gary Servin 0:04ac6be8229a 40 union {
Gary Servin 0:04ac6be8229a 41 bool real;
Gary Servin 0:04ac6be8229a 42 uint8_t base;
Gary Servin 0:04ac6be8229a 43 } u_data;
Gary Servin 0:04ac6be8229a 44 u_data.base = 0;
Gary Servin 0:04ac6be8229a 45 u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 46 this->data = u_data.real;
Gary Servin 0:04ac6be8229a 47 offset += sizeof(this->data);
Gary Servin 0:04ac6be8229a 48 return offset;
Gary Servin 0:04ac6be8229a 49 }
Gary Servin 0:04ac6be8229a 50
Gary Servin 0:04ac6be8229a 51 const char * getType(){ return SETBOOL; };
Gary Servin 0:04ac6be8229a 52 const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; };
Gary Servin 0:04ac6be8229a 53
Gary Servin 0:04ac6be8229a 54 };
Gary Servin 0:04ac6be8229a 55
Gary Servin 0:04ac6be8229a 56 class SetBoolResponse : public ros::Msg
Gary Servin 0:04ac6be8229a 57 {
Gary Servin 0:04ac6be8229a 58 public:
Gary Servin 0:04ac6be8229a 59 typedef bool _success_type;
Gary Servin 0:04ac6be8229a 60 _success_type success;
Gary Servin 0:04ac6be8229a 61 typedef const char* _message_type;
Gary Servin 0:04ac6be8229a 62 _message_type message;
Gary Servin 0:04ac6be8229a 63
Gary Servin 0:04ac6be8229a 64 SetBoolResponse():
Gary Servin 0:04ac6be8229a 65 success(0),
Gary Servin 0:04ac6be8229a 66 message("")
Gary Servin 0:04ac6be8229a 67 {
Gary Servin 0:04ac6be8229a 68 }
Gary Servin 0:04ac6be8229a 69
Gary Servin 0:04ac6be8229a 70 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 71 {
Gary Servin 0:04ac6be8229a 72 int offset = 0;
Gary Servin 0:04ac6be8229a 73 union {
Gary Servin 0:04ac6be8229a 74 bool real;
Gary Servin 0:04ac6be8229a 75 uint8_t base;
Gary Servin 0:04ac6be8229a 76 } u_success;
Gary Servin 0:04ac6be8229a 77 u_success.real = this->success;
Gary Servin 0:04ac6be8229a 78 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 79 offset += sizeof(this->success);
Gary Servin 0:04ac6be8229a 80 uint32_t length_message = strlen(this->message);
Gary Servin 0:04ac6be8229a 81 varToArr(outbuffer + offset, length_message);
Gary Servin 0:04ac6be8229a 82 offset += 4;
Gary Servin 0:04ac6be8229a 83 memcpy(outbuffer + offset, this->message, length_message);
Gary Servin 0:04ac6be8229a 84 offset += length_message;
Gary Servin 0:04ac6be8229a 85 return offset;
Gary Servin 0:04ac6be8229a 86 }
Gary Servin 0:04ac6be8229a 87
Gary Servin 0:04ac6be8229a 88 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 89 {
Gary Servin 0:04ac6be8229a 90 int offset = 0;
Gary Servin 0:04ac6be8229a 91 union {
Gary Servin 0:04ac6be8229a 92 bool real;
Gary Servin 0:04ac6be8229a 93 uint8_t base;
Gary Servin 0:04ac6be8229a 94 } u_success;
Gary Servin 0:04ac6be8229a 95 u_success.base = 0;
Gary Servin 0:04ac6be8229a 96 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 97 this->success = u_success.real;
Gary Servin 0:04ac6be8229a 98 offset += sizeof(this->success);
Gary Servin 0:04ac6be8229a 99 uint32_t length_message;
Gary Servin 0:04ac6be8229a 100 arrToVar(length_message, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 101 offset += 4;
Gary Servin 0:04ac6be8229a 102 for(unsigned int k= offset; k< offset+length_message; ++k){
Gary Servin 0:04ac6be8229a 103 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 104 }
Gary Servin 0:04ac6be8229a 105 inbuffer[offset+length_message-1]=0;
Gary Servin 0:04ac6be8229a 106 this->message = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 107 offset += length_message;
Gary Servin 0:04ac6be8229a 108 return offset;
Gary Servin 0:04ac6be8229a 109 }
Gary Servin 0:04ac6be8229a 110
Gary Servin 0:04ac6be8229a 111 const char * getType(){ return SETBOOL; };
Gary Servin 0:04ac6be8229a 112 const char * getMD5(){ return "937c9679a518e3a18d831e57125ea522"; };
Gary Servin 0:04ac6be8229a 113
Gary Servin 0:04ac6be8229a 114 };
Gary Servin 0:04ac6be8229a 115
Gary Servin 0:04ac6be8229a 116 class SetBool {
Gary Servin 0:04ac6be8229a 117 public:
Gary Servin 0:04ac6be8229a 118 typedef SetBoolRequest Request;
Gary Servin 0:04ac6be8229a 119 typedef SetBoolResponse Response;
Gary Servin 0:04ac6be8229a 120 };
Gary Servin 0:04ac6be8229a 121
Gary Servin 0:04ac6be8229a 122 }
Gary Servin 0:04ac6be8229a 123 #endif