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