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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

ROSSerial_mbed for Indigo 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

rosserial_mbed Hello World

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 14:22:59 2016 +0000
Revision:
0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_nav_msgs_Odometry_h
garyservin 0:fd24f7ca9688 2 #define _ROS_nav_msgs_Odometry_h
garyservin 0:fd24f7ca9688 3
garyservin 0:fd24f7ca9688 4 #include <stdint.h>
garyservin 0:fd24f7ca9688 5 #include <string.h>
garyservin 0:fd24f7ca9688 6 #include <stdlib.h>
garyservin 0:fd24f7ca9688 7 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 8 #include "std_msgs/Header.h"
garyservin 0:fd24f7ca9688 9 #include "geometry_msgs/PoseWithCovariance.h"
garyservin 0:fd24f7ca9688 10 #include "geometry_msgs/TwistWithCovariance.h"
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 namespace nav_msgs
garyservin 0:fd24f7ca9688 13 {
garyservin 0:fd24f7ca9688 14
garyservin 0:fd24f7ca9688 15 class Odometry : public ros::Msg
garyservin 0:fd24f7ca9688 16 {
garyservin 0:fd24f7ca9688 17 public:
garyservin 0:fd24f7ca9688 18 std_msgs::Header header;
garyservin 0:fd24f7ca9688 19 const char* child_frame_id;
garyservin 0:fd24f7ca9688 20 geometry_msgs::PoseWithCovariance pose;
garyservin 0:fd24f7ca9688 21 geometry_msgs::TwistWithCovariance twist;
garyservin 0:fd24f7ca9688 22
garyservin 0:fd24f7ca9688 23 Odometry():
garyservin 0:fd24f7ca9688 24 header(),
garyservin 0:fd24f7ca9688 25 child_frame_id(""),
garyservin 0:fd24f7ca9688 26 pose(),
garyservin 0:fd24f7ca9688 27 twist()
garyservin 0:fd24f7ca9688 28 {
garyservin 0:fd24f7ca9688 29 }
garyservin 0:fd24f7ca9688 30
garyservin 0:fd24f7ca9688 31 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 32 {
garyservin 0:fd24f7ca9688 33 int offset = 0;
garyservin 0:fd24f7ca9688 34 offset += this->header.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 35 uint32_t length_child_frame_id = strlen(this->child_frame_id);
garyservin 0:fd24f7ca9688 36 memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 37 offset += 4;
garyservin 0:fd24f7ca9688 38 memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id);
garyservin 0:fd24f7ca9688 39 offset += length_child_frame_id;
garyservin 0:fd24f7ca9688 40 offset += this->pose.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 41 offset += this->twist.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 42 return offset;
garyservin 0:fd24f7ca9688 43 }
garyservin 0:fd24f7ca9688 44
garyservin 0:fd24f7ca9688 45 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 46 {
garyservin 0:fd24f7ca9688 47 int offset = 0;
garyservin 0:fd24f7ca9688 48 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 49 uint32_t length_child_frame_id;
garyservin 0:fd24f7ca9688 50 memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 51 offset += 4;
garyservin 0:fd24f7ca9688 52 for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
garyservin 0:fd24f7ca9688 53 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 54 }
garyservin 0:fd24f7ca9688 55 inbuffer[offset+length_child_frame_id-1]=0;
garyservin 0:fd24f7ca9688 56 this->child_frame_id = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 57 offset += length_child_frame_id;
garyservin 0:fd24f7ca9688 58 offset += this->pose.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 59 offset += this->twist.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 60 return offset;
garyservin 0:fd24f7ca9688 61 }
garyservin 0:fd24f7ca9688 62
garyservin 0:fd24f7ca9688 63 const char * getType(){ return "nav_msgs/Odometry"; };
garyservin 0:fd24f7ca9688 64 const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; };
garyservin 0:fd24f7ca9688 65
garyservin 0:fd24f7ca9688 66 };
garyservin 0:fd24f7ca9688 67
garyservin 0:fd24f7ca9688 68 }
garyservin 0:fd24f7ca9688 69 #endif