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_rosgraph_msgs_Log_h
garyservin 0:fd24f7ca9688 2 #define _ROS_rosgraph_msgs_Log_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 "std_msgs/Header.h"
garyservin 0:fd24f7ca9688 9
garyservin 0:fd24f7ca9688 10 namespace rosgraph_msgs
garyservin 0:fd24f7ca9688 11 {
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class Log : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 std_msgs::Header header;
garyservin 0:fd24f7ca9688 17 int8_t level;
garyservin 0:fd24f7ca9688 18 const char* name;
garyservin 0:fd24f7ca9688 19 const char* msg;
garyservin 0:fd24f7ca9688 20 const char* file;
garyservin 0:fd24f7ca9688 21 const char* function;
garyservin 0:fd24f7ca9688 22 uint32_t line;
garyservin 0:fd24f7ca9688 23 uint8_t topics_length;
garyservin 0:fd24f7ca9688 24 char* st_topics;
garyservin 0:fd24f7ca9688 25 char* * topics;
garyservin 0:fd24f7ca9688 26 enum { DEBUG = 1 };
garyservin 0:fd24f7ca9688 27 enum { INFO = 2 };
garyservin 0:fd24f7ca9688 28 enum { WARN = 4 };
garyservin 0:fd24f7ca9688 29 enum { ERROR = 8 };
garyservin 0:fd24f7ca9688 30 enum { FATAL = 16 };
garyservin 0:fd24f7ca9688 31
garyservin 0:fd24f7ca9688 32 Log():
garyservin 0:fd24f7ca9688 33 header(),
garyservin 0:fd24f7ca9688 34 level(0),
garyservin 0:fd24f7ca9688 35 name(""),
garyservin 0:fd24f7ca9688 36 msg(""),
garyservin 0:fd24f7ca9688 37 file(""),
garyservin 0:fd24f7ca9688 38 function(""),
garyservin 0:fd24f7ca9688 39 line(0),
garyservin 0:fd24f7ca9688 40 topics_length(0), topics(NULL)
garyservin 0:fd24f7ca9688 41 {
garyservin 0:fd24f7ca9688 42 }
garyservin 0:fd24f7ca9688 43
garyservin 0:fd24f7ca9688 44 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 45 {
garyservin 0:fd24f7ca9688 46 int offset = 0;
garyservin 0:fd24f7ca9688 47 offset += this->header.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 48 union {
garyservin 0:fd24f7ca9688 49 int8_t real;
garyservin 0:fd24f7ca9688 50 uint8_t base;
garyservin 0:fd24f7ca9688 51 } u_level;
garyservin 0:fd24f7ca9688 52 u_level.real = this->level;
garyservin 0:fd24f7ca9688 53 *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 54 offset += sizeof(this->level);
garyservin 0:fd24f7ca9688 55 uint32_t length_name = strlen(this->name);
garyservin 0:fd24f7ca9688 56 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 57 offset += 4;
garyservin 0:fd24f7ca9688 58 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:fd24f7ca9688 59 offset += length_name;
garyservin 0:fd24f7ca9688 60 uint32_t length_msg = strlen(this->msg);
garyservin 0:fd24f7ca9688 61 memcpy(outbuffer + offset, &length_msg, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 62 offset += 4;
garyservin 0:fd24f7ca9688 63 memcpy(outbuffer + offset, this->msg, length_msg);
garyservin 0:fd24f7ca9688 64 offset += length_msg;
garyservin 0:fd24f7ca9688 65 uint32_t length_file = strlen(this->file);
garyservin 0:fd24f7ca9688 66 memcpy(outbuffer + offset, &length_file, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 67 offset += 4;
garyservin 0:fd24f7ca9688 68 memcpy(outbuffer + offset, this->file, length_file);
garyservin 0:fd24f7ca9688 69 offset += length_file;
garyservin 0:fd24f7ca9688 70 uint32_t length_function = strlen(this->function);
garyservin 0:fd24f7ca9688 71 memcpy(outbuffer + offset, &length_function, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 72 offset += 4;
garyservin 0:fd24f7ca9688 73 memcpy(outbuffer + offset, this->function, length_function);
garyservin 0:fd24f7ca9688 74 offset += length_function;
garyservin 0:fd24f7ca9688 75 *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 76 *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 77 *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 78 *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 79 offset += sizeof(this->line);
garyservin 0:fd24f7ca9688 80 *(outbuffer + offset++) = topics_length;
garyservin 0:fd24f7ca9688 81 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 82 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 83 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 84 for( uint8_t i = 0; i < topics_length; i++){
garyservin 0:fd24f7ca9688 85 uint32_t length_topicsi = strlen(this->topics[i]);
garyservin 0:fd24f7ca9688 86 memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 87 offset += 4;
garyservin 0:fd24f7ca9688 88 memcpy(outbuffer + offset, this->topics[i], length_topicsi);
garyservin 0:fd24f7ca9688 89 offset += length_topicsi;
garyservin 0:fd24f7ca9688 90 }
garyservin 0:fd24f7ca9688 91 return offset;
garyservin 0:fd24f7ca9688 92 }
garyservin 0:fd24f7ca9688 93
garyservin 0:fd24f7ca9688 94 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 95 {
garyservin 0:fd24f7ca9688 96 int offset = 0;
garyservin 0:fd24f7ca9688 97 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 98 union {
garyservin 0:fd24f7ca9688 99 int8_t real;
garyservin 0:fd24f7ca9688 100 uint8_t base;
garyservin 0:fd24f7ca9688 101 } u_level;
garyservin 0:fd24f7ca9688 102 u_level.base = 0;
garyservin 0:fd24f7ca9688 103 u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 104 this->level = u_level.real;
garyservin 0:fd24f7ca9688 105 offset += sizeof(this->level);
garyservin 0:fd24f7ca9688 106 uint32_t length_name;
garyservin 0:fd24f7ca9688 107 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 108 offset += 4;
garyservin 0:fd24f7ca9688 109 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:fd24f7ca9688 110 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 111 }
garyservin 0:fd24f7ca9688 112 inbuffer[offset+length_name-1]=0;
garyservin 0:fd24f7ca9688 113 this->name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 114 offset += length_name;
garyservin 0:fd24f7ca9688 115 uint32_t length_msg;
garyservin 0:fd24f7ca9688 116 memcpy(&length_msg, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 117 offset += 4;
garyservin 0:fd24f7ca9688 118 for(unsigned int k= offset; k< offset+length_msg; ++k){
garyservin 0:fd24f7ca9688 119 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 120 }
garyservin 0:fd24f7ca9688 121 inbuffer[offset+length_msg-1]=0;
garyservin 0:fd24f7ca9688 122 this->msg = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 123 offset += length_msg;
garyservin 0:fd24f7ca9688 124 uint32_t length_file;
garyservin 0:fd24f7ca9688 125 memcpy(&length_file, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 126 offset += 4;
garyservin 0:fd24f7ca9688 127 for(unsigned int k= offset; k< offset+length_file; ++k){
garyservin 0:fd24f7ca9688 128 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 129 }
garyservin 0:fd24f7ca9688 130 inbuffer[offset+length_file-1]=0;
garyservin 0:fd24f7ca9688 131 this->file = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 132 offset += length_file;
garyservin 0:fd24f7ca9688 133 uint32_t length_function;
garyservin 0:fd24f7ca9688 134 memcpy(&length_function, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 135 offset += 4;
garyservin 0:fd24f7ca9688 136 for(unsigned int k= offset; k< offset+length_function; ++k){
garyservin 0:fd24f7ca9688 137 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 138 }
garyservin 0:fd24f7ca9688 139 inbuffer[offset+length_function-1]=0;
garyservin 0:fd24f7ca9688 140 this->function = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 141 offset += length_function;
garyservin 0:fd24f7ca9688 142 this->line = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 143 this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 144 this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 145 this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 146 offset += sizeof(this->line);
garyservin 0:fd24f7ca9688 147 uint8_t topics_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 148 if(topics_lengthT > topics_length)
garyservin 0:fd24f7ca9688 149 this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 150 offset += 3;
garyservin 0:fd24f7ca9688 151 topics_length = topics_lengthT;
garyservin 0:fd24f7ca9688 152 for( uint8_t i = 0; i < topics_length; i++){
garyservin 0:fd24f7ca9688 153 uint32_t length_st_topics;
garyservin 0:fd24f7ca9688 154 memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 155 offset += 4;
garyservin 0:fd24f7ca9688 156 for(unsigned int k= offset; k< offset+length_st_topics; ++k){
garyservin 0:fd24f7ca9688 157 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 158 }
garyservin 0:fd24f7ca9688 159 inbuffer[offset+length_st_topics-1]=0;
garyservin 0:fd24f7ca9688 160 this->st_topics = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 161 offset += length_st_topics;
garyservin 0:fd24f7ca9688 162 memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*));
garyservin 0:fd24f7ca9688 163 }
garyservin 0:fd24f7ca9688 164 return offset;
garyservin 0:fd24f7ca9688 165 }
garyservin 0:fd24f7ca9688 166
garyservin 0:fd24f7ca9688 167 const char * getType(){ return "rosgraph_msgs/Log"; };
garyservin 0:fd24f7ca9688 168 const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; };
garyservin 0:fd24f7ca9688 169
garyservin 0:fd24f7ca9688 170 };
garyservin 0:fd24f7ca9688 171
garyservin 0:fd24f7ca9688 172 }
garyservin 0:fd24f7ca9688 173 #endif