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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_jade

ROSSerial_mbed for Jade 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_jade

rosserial_mbed Hello World example for jade 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:
Thu Mar 31 23:23:15 2016 +0000
Revision:
0:a906bb7c7831
ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:a906bb7c7831 1 #ifndef _ROS_nav_msgs_OccupancyGrid_h
garyservin 0:a906bb7c7831 2 #define _ROS_nav_msgs_OccupancyGrid_h
garyservin 0:a906bb7c7831 3
garyservin 0:a906bb7c7831 4 #include <stdint.h>
garyservin 0:a906bb7c7831 5 #include <string.h>
garyservin 0:a906bb7c7831 6 #include <stdlib.h>
garyservin 0:a906bb7c7831 7 #include "ros/msg.h"
garyservin 0:a906bb7c7831 8 #include "std_msgs/Header.h"
garyservin 0:a906bb7c7831 9 #include "nav_msgs/MapMetaData.h"
garyservin 0:a906bb7c7831 10
garyservin 0:a906bb7c7831 11 namespace nav_msgs
garyservin 0:a906bb7c7831 12 {
garyservin 0:a906bb7c7831 13
garyservin 0:a906bb7c7831 14 class OccupancyGrid : public ros::Msg
garyservin 0:a906bb7c7831 15 {
garyservin 0:a906bb7c7831 16 public:
garyservin 0:a906bb7c7831 17 std_msgs::Header header;
garyservin 0:a906bb7c7831 18 nav_msgs::MapMetaData info;
garyservin 0:a906bb7c7831 19 uint8_t data_length;
garyservin 0:a906bb7c7831 20 int8_t st_data;
garyservin 0:a906bb7c7831 21 int8_t * data;
garyservin 0:a906bb7c7831 22
garyservin 0:a906bb7c7831 23 OccupancyGrid():
garyservin 0:a906bb7c7831 24 header(),
garyservin 0:a906bb7c7831 25 info(),
garyservin 0:a906bb7c7831 26 data_length(0), data(NULL)
garyservin 0:a906bb7c7831 27 {
garyservin 0:a906bb7c7831 28 }
garyservin 0:a906bb7c7831 29
garyservin 0:a906bb7c7831 30 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 31 {
garyservin 0:a906bb7c7831 32 int offset = 0;
garyservin 0:a906bb7c7831 33 offset += this->header.serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 34 offset += this->info.serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 35 *(outbuffer + offset++) = data_length;
garyservin 0:a906bb7c7831 36 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 37 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 38 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 39 for( uint8_t i = 0; i < data_length; i++){
garyservin 0:a906bb7c7831 40 union {
garyservin 0:a906bb7c7831 41 int8_t real;
garyservin 0:a906bb7c7831 42 uint8_t base;
garyservin 0:a906bb7c7831 43 } u_datai;
garyservin 0:a906bb7c7831 44 u_datai.real = this->data[i];
garyservin 0:a906bb7c7831 45 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 46 offset += sizeof(this->data[i]);
garyservin 0:a906bb7c7831 47 }
garyservin 0:a906bb7c7831 48 return offset;
garyservin 0:a906bb7c7831 49 }
garyservin 0:a906bb7c7831 50
garyservin 0:a906bb7c7831 51 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 52 {
garyservin 0:a906bb7c7831 53 int offset = 0;
garyservin 0:a906bb7c7831 54 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 55 offset += this->info.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 56 uint8_t data_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 57 if(data_lengthT > data_length)
garyservin 0:a906bb7c7831 58 this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
garyservin 0:a906bb7c7831 59 offset += 3;
garyservin 0:a906bb7c7831 60 data_length = data_lengthT;
garyservin 0:a906bb7c7831 61 for( uint8_t i = 0; i < data_length; i++){
garyservin 0:a906bb7c7831 62 union {
garyservin 0:a906bb7c7831 63 int8_t real;
garyservin 0:a906bb7c7831 64 uint8_t base;
garyservin 0:a906bb7c7831 65 } u_st_data;
garyservin 0:a906bb7c7831 66 u_st_data.base = 0;
garyservin 0:a906bb7c7831 67 u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 68 this->st_data = u_st_data.real;
garyservin 0:a906bb7c7831 69 offset += sizeof(this->st_data);
garyservin 0:a906bb7c7831 70 memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
garyservin 0:a906bb7c7831 71 }
garyservin 0:a906bb7c7831 72 return offset;
garyservin 0:a906bb7c7831 73 }
garyservin 0:a906bb7c7831 74
garyservin 0:a906bb7c7831 75 const char * getType(){ return "nav_msgs/OccupancyGrid"; };
garyservin 0:a906bb7c7831 76 const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; };
garyservin 0:a906bb7c7831 77
garyservin 0:a906bb7c7831 78 };
garyservin 0:a906bb7c7831 79
garyservin 0:a906bb7c7831 80 }
garyservin 0:a906bb7c7831 81 #endif