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_gazebo_msgs_LinkState_h
garyservin 0:fd24f7ca9688 2 #define _ROS_gazebo_msgs_LinkState_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 "geometry_msgs/Pose.h"
garyservin 0:fd24f7ca9688 9 #include "geometry_msgs/Twist.h"
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 namespace gazebo_msgs
garyservin 0:fd24f7ca9688 12 {
garyservin 0:fd24f7ca9688 13
garyservin 0:fd24f7ca9688 14 class LinkState : public ros::Msg
garyservin 0:fd24f7ca9688 15 {
garyservin 0:fd24f7ca9688 16 public:
garyservin 0:fd24f7ca9688 17 const char* link_name;
garyservin 0:fd24f7ca9688 18 geometry_msgs::Pose pose;
garyservin 0:fd24f7ca9688 19 geometry_msgs::Twist twist;
garyservin 0:fd24f7ca9688 20 const char* reference_frame;
garyservin 0:fd24f7ca9688 21
garyservin 0:fd24f7ca9688 22 LinkState():
garyservin 0:fd24f7ca9688 23 link_name(""),
garyservin 0:fd24f7ca9688 24 pose(),
garyservin 0:fd24f7ca9688 25 twist(),
garyservin 0:fd24f7ca9688 26 reference_frame("")
garyservin 0:fd24f7ca9688 27 {
garyservin 0:fd24f7ca9688 28 }
garyservin 0:fd24f7ca9688 29
garyservin 0:fd24f7ca9688 30 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 31 {
garyservin 0:fd24f7ca9688 32 int offset = 0;
garyservin 0:fd24f7ca9688 33 uint32_t length_link_name = strlen(this->link_name);
garyservin 0:fd24f7ca9688 34 memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 35 offset += 4;
garyservin 0:fd24f7ca9688 36 memcpy(outbuffer + offset, this->link_name, length_link_name);
garyservin 0:fd24f7ca9688 37 offset += length_link_name;
garyservin 0:fd24f7ca9688 38 offset += this->pose.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 39 offset += this->twist.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 40 uint32_t length_reference_frame = strlen(this->reference_frame);
garyservin 0:fd24f7ca9688 41 memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 42 offset += 4;
garyservin 0:fd24f7ca9688 43 memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
garyservin 0:fd24f7ca9688 44 offset += length_reference_frame;
garyservin 0:fd24f7ca9688 45 return offset;
garyservin 0:fd24f7ca9688 46 }
garyservin 0:fd24f7ca9688 47
garyservin 0:fd24f7ca9688 48 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 49 {
garyservin 0:fd24f7ca9688 50 int offset = 0;
garyservin 0:fd24f7ca9688 51 uint32_t length_link_name;
garyservin 0:fd24f7ca9688 52 memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 53 offset += 4;
garyservin 0:fd24f7ca9688 54 for(unsigned int k= offset; k< offset+length_link_name; ++k){
garyservin 0:fd24f7ca9688 55 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 56 }
garyservin 0:fd24f7ca9688 57 inbuffer[offset+length_link_name-1]=0;
garyservin 0:fd24f7ca9688 58 this->link_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 59 offset += length_link_name;
garyservin 0:fd24f7ca9688 60 offset += this->pose.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 61 offset += this->twist.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 62 uint32_t length_reference_frame;
garyservin 0:fd24f7ca9688 63 memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 64 offset += 4;
garyservin 0:fd24f7ca9688 65 for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
garyservin 0:fd24f7ca9688 66 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 67 }
garyservin 0:fd24f7ca9688 68 inbuffer[offset+length_reference_frame-1]=0;
garyservin 0:fd24f7ca9688 69 this->reference_frame = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 70 offset += length_reference_frame;
garyservin 0:fd24f7ca9688 71 return offset;
garyservin 0:fd24f7ca9688 72 }
garyservin 0:fd24f7ca9688 73
garyservin 0:fd24f7ca9688 74 const char * getType(){ return "gazebo_msgs/LinkState"; };
garyservin 0:fd24f7ca9688 75 const char * getMD5(){ return "0818ebbf28ce3a08d48ab1eaa7309ebe"; };
garyservin 0:fd24f7ca9688 76
garyservin 0:fd24f7ca9688 77 };
garyservin 0:fd24f7ca9688 78
garyservin 0:fd24f7ca9688 79 }
garyservin 0:fd24f7ca9688 80 #endif