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();
    }
}
Download repository: zip gz

Files at revision 0:a906bb7c7831

Name Size Actions
[up]
FollowJointTrajectoryAction.h 1592 Revisions Annotate
FollowJointTrajectoryActionFeedback.h 1444 Revisions Annotate
FollowJointTrajectoryActionGoal.h 1396 Revisions Annotate
FollowJointTrajectoryActionResult.h 1422 Revisions Annotate
FollowJointTrajectoryFeedback.h 3013 Revisions Annotate
FollowJointTrajectoryGoal.h 4901 Revisions Annotate
FollowJointTrajectoryResult.h 2703 Revisions Annotate
GripperCommand.h 3858 Revisions Annotate
GripperCommandAction.h 1515 Revisions Annotate
GripperCommandActionFeedback.h 1395 Revisions Annotate
GripperCommandActionGoal.h 1347 Revisions Annotate
GripperCommandActionResult.h 1373 Revisions Annotate
GripperCommandFeedback.h 4877 Revisions Annotate
GripperCommandGoal.h 911 Revisions Annotate
GripperCommandResult.h 4867 Revisions Annotate
JointControllerState.h 16313 Revisions Annotate
JointTolerance.h 6084 Revisions Annotate
JointTrajectoryAction.h 1526 Revisions Annotate
JointTrajectoryActionFeedback.h 1402 Revisions Annotate
JointTrajectoryActionGoal.h 1354 Revisions Annotate
JointTrajectoryActionResult.h 1380 Revisions Annotate
JointTrajectoryControllerState.h 3018 Revisions Annotate
JointTrajectoryFeedback.h 711 Revisions Annotate
JointTrajectoryGoal.h 936 Revisions Annotate
JointTrajectoryResult.h 701 Revisions Annotate
PointHeadAction.h 1460 Revisions Annotate
PointHeadActionFeedback.h 1360 Revisions Annotate
PointHeadActionGoal.h 1312 Revisions Annotate
PointHeadActionResult.h 1338 Revisions Annotate
PointHeadFeedback.h 2574 Revisions Annotate
PointHeadGoal.h 5087 Revisions Annotate
PointHeadResult.h 671 Revisions Annotate
QueryCalibrationState.h 1999 Revisions Annotate
QueryTrajectoryState.h 11131 Revisions Annotate
SingleJointPositionAction.h 1570 Revisions Annotate
SingleJointPositionActionFeedback.h 1430 Revisions Annotate
SingleJointPositionActionGoal.h 1382 Revisions Annotate
SingleJointPositionActionResult.h 1408 Revisions Annotate
SingleJointPositionFeedback.h 5554 Revisions Annotate
SingleJointPositionGoal.h 5507 Revisions Annotate
SingleJointPositionResult.h 721 Revisions Annotate