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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more

ROSSerial_mbed for Melodic 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_melodic

rosserial_mbed Hello World example for Melodic Morenia 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:da82487f547e

Name Size Actions
[up]
FollowJointTrajectoryAction.h 1758 Revisions Annotate
FollowJointTrajectoryActionFeedback.h 1572 Revisions Annotate
FollowJointTrajectoryActionGoal.h 1518 Revisions Annotate
FollowJointTrajectoryActionResult.h 1546 Revisions Annotate
FollowJointTrajectoryFeedback.h 3715 Revisions Annotate
FollowJointTrajectoryGoal.h 6180 Revisions Annotate
FollowJointTrajectoryResult.h 2772 Revisions Annotate
GripperCommand.h 3953 Revisions Annotate
GripperCommandAction.h 1681 Revisions Annotate
GripperCommandActionFeedback.h 1523 Revisions Annotate
GripperCommandActionGoal.h 1469 Revisions Annotate
GripperCommandActionResult.h 1497 Revisions Annotate
GripperCommandFeedback.h 5060 Revisions Annotate
GripperCommandGoal.h 955 Revisions Annotate
GripperCommandResult.h 5050 Revisions Annotate
JointControllerState.h 17384 Revisions Annotate
JointJog.h 10568 Revisions Annotate
JointTolerance.h 6231 Revisions Annotate
JointTrajectoryAction.h 1692 Revisions Annotate
JointTrajectoryActionFeedback.h 1530 Revisions Annotate
JointTrajectoryActionGoal.h 1476 Revisions Annotate
JointTrajectoryActionResult.h 1504 Revisions Annotate
JointTrajectoryControllerState.h 3720 Revisions Annotate
JointTrajectoryFeedback.h 712 Revisions Annotate
JointTrajectoryGoal.h 986 Revisions Annotate
JointTrajectoryResult.h 702 Revisions Annotate
PidState.h 19585 Revisions Annotate
PointHeadAction.h 1626 Revisions Annotate
PointHeadActionFeedback.h 1488 Revisions Annotate
PointHeadActionGoal.h 1434 Revisions Annotate
PointHeadActionResult.h 1462 Revisions Annotate
PointHeadFeedback.h 2644 Revisions Annotate
PointHeadGoal.h 5313 Revisions Annotate
PointHeadResult.h 672 Revisions Annotate
QueryCalibrationState.h 2054 Revisions Annotate
QueryTrajectoryState.h 13283 Revisions Annotate
SingleJointPositionAction.h 1736 Revisions Annotate
SingleJointPositionActionFeedback.h 1558 Revisions Annotate
SingleJointPositionActionGoal.h 1504 Revisions Annotate
SingleJointPositionActionResult.h 1532 Revisions Annotate
SingleJointPositionFeedback.h 5725 Revisions Annotate
SingleJointPositionGoal.h 5659 Revisions Annotate
SingleJointPositionResult.h 722 Revisions Annotate