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();
    }
}
Committer:
garyservin
Date:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_turtle_actionlib_Velocity_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_turtle_actionlib_Velocity_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8
garyservin 0:9e9b7db60fd5 9 namespace turtle_actionlib
garyservin 0:9e9b7db60fd5 10 {
garyservin 0:9e9b7db60fd5 11
garyservin 0:9e9b7db60fd5 12 class Velocity : public ros::Msg
garyservin 0:9e9b7db60fd5 13 {
garyservin 0:9e9b7db60fd5 14 public:
garyservin 0:9e9b7db60fd5 15 typedef float _linear_type;
garyservin 0:9e9b7db60fd5 16 _linear_type linear;
garyservin 0:9e9b7db60fd5 17 typedef float _angular_type;
garyservin 0:9e9b7db60fd5 18 _angular_type angular;
garyservin 0:9e9b7db60fd5 19
garyservin 0:9e9b7db60fd5 20 Velocity():
garyservin 0:9e9b7db60fd5 21 linear(0),
garyservin 0:9e9b7db60fd5 22 angular(0)
garyservin 0:9e9b7db60fd5 23 {
garyservin 0:9e9b7db60fd5 24 }
garyservin 0:9e9b7db60fd5 25
garyservin 0:9e9b7db60fd5 26 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 27 {
garyservin 0:9e9b7db60fd5 28 int offset = 0;
garyservin 0:9e9b7db60fd5 29 union {
garyservin 0:9e9b7db60fd5 30 float real;
garyservin 0:9e9b7db60fd5 31 uint32_t base;
garyservin 0:9e9b7db60fd5 32 } u_linear;
garyservin 0:9e9b7db60fd5 33 u_linear.real = this->linear;
garyservin 0:9e9b7db60fd5 34 *(outbuffer + offset + 0) = (u_linear.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 35 *(outbuffer + offset + 1) = (u_linear.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 36 *(outbuffer + offset + 2) = (u_linear.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 37 *(outbuffer + offset + 3) = (u_linear.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 38 offset += sizeof(this->linear);
garyservin 0:9e9b7db60fd5 39 union {
garyservin 0:9e9b7db60fd5 40 float real;
garyservin 0:9e9b7db60fd5 41 uint32_t base;
garyservin 0:9e9b7db60fd5 42 } u_angular;
garyservin 0:9e9b7db60fd5 43 u_angular.real = this->angular;
garyservin 0:9e9b7db60fd5 44 *(outbuffer + offset + 0) = (u_angular.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 45 *(outbuffer + offset + 1) = (u_angular.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 46 *(outbuffer + offset + 2) = (u_angular.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 47 *(outbuffer + offset + 3) = (u_angular.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 48 offset += sizeof(this->angular);
garyservin 0:9e9b7db60fd5 49 return offset;
garyservin 0:9e9b7db60fd5 50 }
garyservin 0:9e9b7db60fd5 51
garyservin 0:9e9b7db60fd5 52 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 53 {
garyservin 0:9e9b7db60fd5 54 int offset = 0;
garyservin 0:9e9b7db60fd5 55 union {
garyservin 0:9e9b7db60fd5 56 float real;
garyservin 0:9e9b7db60fd5 57 uint32_t base;
garyservin 0:9e9b7db60fd5 58 } u_linear;
garyservin 0:9e9b7db60fd5 59 u_linear.base = 0;
garyservin 0:9e9b7db60fd5 60 u_linear.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 61 u_linear.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 62 u_linear.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 63 u_linear.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 64 this->linear = u_linear.real;
garyservin 0:9e9b7db60fd5 65 offset += sizeof(this->linear);
garyservin 0:9e9b7db60fd5 66 union {
garyservin 0:9e9b7db60fd5 67 float real;
garyservin 0:9e9b7db60fd5 68 uint32_t base;
garyservin 0:9e9b7db60fd5 69 } u_angular;
garyservin 0:9e9b7db60fd5 70 u_angular.base = 0;
garyservin 0:9e9b7db60fd5 71 u_angular.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 72 u_angular.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 73 u_angular.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 74 u_angular.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 75 this->angular = u_angular.real;
garyservin 0:9e9b7db60fd5 76 offset += sizeof(this->angular);
garyservin 0:9e9b7db60fd5 77 return offset;
garyservin 0:9e9b7db60fd5 78 }
garyservin 0:9e9b7db60fd5 79
garyservin 0:9e9b7db60fd5 80 const char * getType(){ return "turtle_actionlib/Velocity"; };
garyservin 0:9e9b7db60fd5 81 const char * getMD5(){ return "9d5c2dcd348ac8f76ce2a4307bd63a13"; };
garyservin 0:9e9b7db60fd5 82
garyservin 0:9e9b7db60fd5 83 };
garyservin 0:9e9b7db60fd5 84
garyservin 0:9e9b7db60fd5 85 }
garyservin 0:9e9b7db60fd5 86 #endif