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_roscpp_Logger_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_roscpp_Logger_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 roscpp
garyservin 0:9e9b7db60fd5 10 {
garyservin 0:9e9b7db60fd5 11
garyservin 0:9e9b7db60fd5 12 class Logger : public ros::Msg
garyservin 0:9e9b7db60fd5 13 {
garyservin 0:9e9b7db60fd5 14 public:
garyservin 0:9e9b7db60fd5 15 typedef const char* _name_type;
garyservin 0:9e9b7db60fd5 16 _name_type name;
garyservin 0:9e9b7db60fd5 17 typedef const char* _level_type;
garyservin 0:9e9b7db60fd5 18 _level_type level;
garyservin 0:9e9b7db60fd5 19
garyservin 0:9e9b7db60fd5 20 Logger():
garyservin 0:9e9b7db60fd5 21 name(""),
garyservin 0:9e9b7db60fd5 22 level("")
garyservin 0:9e9b7db60fd5 23 {
garyservin 0:9e9b7db60fd5 24 }
garyservin 0:9e9b7db60fd5 25
garyservin 0:9e9b7db60fd5 26 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 27 {
garyservin 0:9e9b7db60fd5 28 int offset = 0;
garyservin 0:9e9b7db60fd5 29 uint32_t length_name = strlen(this->name);
garyservin 0:9e9b7db60fd5 30 varToArr(outbuffer + offset, length_name);
garyservin 0:9e9b7db60fd5 31 offset += 4;
garyservin 0:9e9b7db60fd5 32 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:9e9b7db60fd5 33 offset += length_name;
garyservin 0:9e9b7db60fd5 34 uint32_t length_level = strlen(this->level);
garyservin 0:9e9b7db60fd5 35 varToArr(outbuffer + offset, length_level);
garyservin 0:9e9b7db60fd5 36 offset += 4;
garyservin 0:9e9b7db60fd5 37 memcpy(outbuffer + offset, this->level, length_level);
garyservin 0:9e9b7db60fd5 38 offset += length_level;
garyservin 0:9e9b7db60fd5 39 return offset;
garyservin 0:9e9b7db60fd5 40 }
garyservin 0:9e9b7db60fd5 41
garyservin 0:9e9b7db60fd5 42 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 43 {
garyservin 0:9e9b7db60fd5 44 int offset = 0;
garyservin 0:9e9b7db60fd5 45 uint32_t length_name;
garyservin 0:9e9b7db60fd5 46 arrToVar(length_name, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 47 offset += 4;
garyservin 0:9e9b7db60fd5 48 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:9e9b7db60fd5 49 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 50 }
garyservin 0:9e9b7db60fd5 51 inbuffer[offset+length_name-1]=0;
garyservin 0:9e9b7db60fd5 52 this->name = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 53 offset += length_name;
garyservin 0:9e9b7db60fd5 54 uint32_t length_level;
garyservin 0:9e9b7db60fd5 55 arrToVar(length_level, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 56 offset += 4;
garyservin 0:9e9b7db60fd5 57 for(unsigned int k= offset; k< offset+length_level; ++k){
garyservin 0:9e9b7db60fd5 58 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 59 }
garyservin 0:9e9b7db60fd5 60 inbuffer[offset+length_level-1]=0;
garyservin 0:9e9b7db60fd5 61 this->level = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 62 offset += length_level;
garyservin 0:9e9b7db60fd5 63 return offset;
garyservin 0:9e9b7db60fd5 64 }
garyservin 0:9e9b7db60fd5 65
garyservin 0:9e9b7db60fd5 66 const char * getType(){ return "roscpp/Logger"; };
garyservin 0:9e9b7db60fd5 67 const char * getMD5(){ return "a6069a2ff40db7bd32143dd66e1f408e"; };
garyservin 0:9e9b7db60fd5 68
garyservin 0:9e9b7db60fd5 69 };
garyservin 0:9e9b7db60fd5 70
garyservin 0:9e9b7db60fd5 71 }
garyservin 0:9e9b7db60fd5 72 #endif