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

Files at revision 1:a849bf78d77f

Name Size Actions
[up]
FollowJointTrajectoryAction.h 1757 Revisions Annotate
FollowJointTrajectoryActionFeedback.h 1571 Revisions Annotate
FollowJointTrajectoryActionGoal.h 1517 Revisions Annotate
FollowJointTrajectoryActionResult.h 1545 Revisions Annotate
FollowJointTrajectoryFeedback.h 3714 Revisions Annotate
FollowJointTrajectoryGoal.h 6179 Revisions Annotate
FollowJointTrajectoryResult.h 2771 Revisions Annotate
GripperCommand.h 3952 Revisions Annotate
GripperCommandAction.h 1680 Revisions Annotate
GripperCommandActionFeedback.h 1522 Revisions Annotate
GripperCommandActionGoal.h 1468 Revisions Annotate
GripperCommandActionResult.h 1496 Revisions Annotate
GripperCommandFeedback.h 5059 Revisions Annotate
GripperCommandGoal.h 954 Revisions Annotate
GripperCommandResult.h 5049 Revisions Annotate
JointControllerState.h 17383 Revisions Annotate
JointTolerance.h 6230 Revisions Annotate
JointTrajectoryAction.h 1691 Revisions Annotate
JointTrajectoryActionFeedback.h 1529 Revisions Annotate
JointTrajectoryActionGoal.h 1475 Revisions Annotate
JointTrajectoryActionResult.h 1503 Revisions Annotate
JointTrajectoryControllerState.h 3719 Revisions Annotate
JointTrajectoryFeedback.h 711 Revisions Annotate
JointTrajectoryGoal.h 985 Revisions Annotate
JointTrajectoryResult.h 701 Revisions Annotate
PidState.h 19584 Revisions Annotate
PointHeadAction.h 1625 Revisions Annotate
PointHeadActionFeedback.h 1487 Revisions Annotate
PointHeadActionGoal.h 1433 Revisions Annotate
PointHeadActionResult.h 1461 Revisions Annotate
PointHeadFeedback.h 2643 Revisions Annotate
PointHeadGoal.h 5312 Revisions Annotate
PointHeadResult.h 671 Revisions Annotate
QueryCalibrationState.h 2054 Revisions Annotate
QueryTrajectoryState.h 13283 Revisions Annotate
SingleJointPositionAction.h 1735 Revisions Annotate
SingleJointPositionActionFeedback.h 1557 Revisions Annotate
SingleJointPositionActionGoal.h 1503 Revisions Annotate
SingleJointPositionActionResult.h 1531 Revisions Annotate
SingleJointPositionFeedback.h 5724 Revisions Annotate
SingleJointPositionGoal.h 5658 Revisions Annotate
SingleJointPositionResult.h 721 Revisions Annotate