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_diagnostic_msgs_DiagnosticStatus_h
garyservin 0:fd24f7ca9688 2 #define _ROS_diagnostic_msgs_DiagnosticStatus_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 "diagnostic_msgs/KeyValue.h"
garyservin 0:fd24f7ca9688 9
garyservin 0:fd24f7ca9688 10 namespace diagnostic_msgs
garyservin 0:fd24f7ca9688 11 {
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class DiagnosticStatus : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 int8_t level;
garyservin 0:fd24f7ca9688 17 const char* name;
garyservin 0:fd24f7ca9688 18 const char* message;
garyservin 0:fd24f7ca9688 19 const char* hardware_id;
garyservin 0:fd24f7ca9688 20 uint8_t values_length;
garyservin 0:fd24f7ca9688 21 diagnostic_msgs::KeyValue st_values;
garyservin 0:fd24f7ca9688 22 diagnostic_msgs::KeyValue * values;
garyservin 0:fd24f7ca9688 23 enum { OK = 0 };
garyservin 0:fd24f7ca9688 24 enum { WARN = 1 };
garyservin 0:fd24f7ca9688 25 enum { ERROR = 2 };
garyservin 0:fd24f7ca9688 26 enum { STALE = 3 };
garyservin 0:fd24f7ca9688 27
garyservin 0:fd24f7ca9688 28 DiagnosticStatus():
garyservin 0:fd24f7ca9688 29 level(0),
garyservin 0:fd24f7ca9688 30 name(""),
garyservin 0:fd24f7ca9688 31 message(""),
garyservin 0:fd24f7ca9688 32 hardware_id(""),
garyservin 0:fd24f7ca9688 33 values_length(0), values(NULL)
garyservin 0:fd24f7ca9688 34 {
garyservin 0:fd24f7ca9688 35 }
garyservin 0:fd24f7ca9688 36
garyservin 0:fd24f7ca9688 37 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 38 {
garyservin 0:fd24f7ca9688 39 int offset = 0;
garyservin 0:fd24f7ca9688 40 union {
garyservin 0:fd24f7ca9688 41 int8_t real;
garyservin 0:fd24f7ca9688 42 uint8_t base;
garyservin 0:fd24f7ca9688 43 } u_level;
garyservin 0:fd24f7ca9688 44 u_level.real = this->level;
garyservin 0:fd24f7ca9688 45 *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 46 offset += sizeof(this->level);
garyservin 0:fd24f7ca9688 47 uint32_t length_name = strlen(this->name);
garyservin 0:fd24f7ca9688 48 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 49 offset += 4;
garyservin 0:fd24f7ca9688 50 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:fd24f7ca9688 51 offset += length_name;
garyservin 0:fd24f7ca9688 52 uint32_t length_message = strlen(this->message);
garyservin 0:fd24f7ca9688 53 memcpy(outbuffer + offset, &length_message, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 54 offset += 4;
garyservin 0:fd24f7ca9688 55 memcpy(outbuffer + offset, this->message, length_message);
garyservin 0:fd24f7ca9688 56 offset += length_message;
garyservin 0:fd24f7ca9688 57 uint32_t length_hardware_id = strlen(this->hardware_id);
garyservin 0:fd24f7ca9688 58 memcpy(outbuffer + offset, &length_hardware_id, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 59 offset += 4;
garyservin 0:fd24f7ca9688 60 memcpy(outbuffer + offset, this->hardware_id, length_hardware_id);
garyservin 0:fd24f7ca9688 61 offset += length_hardware_id;
garyservin 0:fd24f7ca9688 62 *(outbuffer + offset++) = values_length;
garyservin 0:fd24f7ca9688 63 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 64 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 65 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 66 for( uint8_t i = 0; i < values_length; i++){
garyservin 0:fd24f7ca9688 67 offset += this->values[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 68 }
garyservin 0:fd24f7ca9688 69 return offset;
garyservin 0:fd24f7ca9688 70 }
garyservin 0:fd24f7ca9688 71
garyservin 0:fd24f7ca9688 72 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 73 {
garyservin 0:fd24f7ca9688 74 int offset = 0;
garyservin 0:fd24f7ca9688 75 union {
garyservin 0:fd24f7ca9688 76 int8_t real;
garyservin 0:fd24f7ca9688 77 uint8_t base;
garyservin 0:fd24f7ca9688 78 } u_level;
garyservin 0:fd24f7ca9688 79 u_level.base = 0;
garyservin 0:fd24f7ca9688 80 u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 81 this->level = u_level.real;
garyservin 0:fd24f7ca9688 82 offset += sizeof(this->level);
garyservin 0:fd24f7ca9688 83 uint32_t length_name;
garyservin 0:fd24f7ca9688 84 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 85 offset += 4;
garyservin 0:fd24f7ca9688 86 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:fd24f7ca9688 87 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 88 }
garyservin 0:fd24f7ca9688 89 inbuffer[offset+length_name-1]=0;
garyservin 0:fd24f7ca9688 90 this->name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 91 offset += length_name;
garyservin 0:fd24f7ca9688 92 uint32_t length_message;
garyservin 0:fd24f7ca9688 93 memcpy(&length_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 94 offset += 4;
garyservin 0:fd24f7ca9688 95 for(unsigned int k= offset; k< offset+length_message; ++k){
garyservin 0:fd24f7ca9688 96 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 97 }
garyservin 0:fd24f7ca9688 98 inbuffer[offset+length_message-1]=0;
garyservin 0:fd24f7ca9688 99 this->message = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 100 offset += length_message;
garyservin 0:fd24f7ca9688 101 uint32_t length_hardware_id;
garyservin 0:fd24f7ca9688 102 memcpy(&length_hardware_id, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 103 offset += 4;
garyservin 0:fd24f7ca9688 104 for(unsigned int k= offset; k< offset+length_hardware_id; ++k){
garyservin 0:fd24f7ca9688 105 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 106 }
garyservin 0:fd24f7ca9688 107 inbuffer[offset+length_hardware_id-1]=0;
garyservin 0:fd24f7ca9688 108 this->hardware_id = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 109 offset += length_hardware_id;
garyservin 0:fd24f7ca9688 110 uint8_t values_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 111 if(values_lengthT > values_length)
garyservin 0:fd24f7ca9688 112 this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue));
garyservin 0:fd24f7ca9688 113 offset += 3;
garyservin 0:fd24f7ca9688 114 values_length = values_lengthT;
garyservin 0:fd24f7ca9688 115 for( uint8_t i = 0; i < values_length; i++){
garyservin 0:fd24f7ca9688 116 offset += this->st_values.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 117 memcpy( &(this->values[i]), &(this->st_values), sizeof(diagnostic_msgs::KeyValue));
garyservin 0:fd24f7ca9688 118 }
garyservin 0:fd24f7ca9688 119 return offset;
garyservin 0:fd24f7ca9688 120 }
garyservin 0:fd24f7ca9688 121
garyservin 0:fd24f7ca9688 122 const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; };
garyservin 0:fd24f7ca9688 123 const char * getMD5(){ return "d0ce08bc6e5ba34c7754f563a9cabaf1"; };
garyservin 0:fd24f7ca9688 124
garyservin 0:fd24f7ca9688 125 };
garyservin 0:fd24f7ca9688 126
garyservin 0:fd24f7ca9688 127 }
garyservin 0:fd24f7ca9688 128 #endif