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_SERVICE_RequestParam_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_RequestParam_h
garyservin 0:fd24f7ca9688 3 #include <stdint.h>
garyservin 0:fd24f7ca9688 4 #include <string.h>
garyservin 0:fd24f7ca9688 5 #include <stdlib.h>
garyservin 0:fd24f7ca9688 6 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 7
garyservin 0:fd24f7ca9688 8 namespace rosserial_msgs
garyservin 0:fd24f7ca9688 9 {
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam";
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class RequestParamRequest : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 const char* name;
garyservin 0:fd24f7ca9688 17
garyservin 0:fd24f7ca9688 18 RequestParamRequest():
garyservin 0:fd24f7ca9688 19 name("")
garyservin 0:fd24f7ca9688 20 {
garyservin 0:fd24f7ca9688 21 }
garyservin 0:fd24f7ca9688 22
garyservin 0:fd24f7ca9688 23 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 24 {
garyservin 0:fd24f7ca9688 25 int offset = 0;
garyservin 0:fd24f7ca9688 26 uint32_t length_name = strlen(this->name);
garyservin 0:fd24f7ca9688 27 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 28 offset += 4;
garyservin 0:fd24f7ca9688 29 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:fd24f7ca9688 30 offset += length_name;
garyservin 0:fd24f7ca9688 31 return offset;
garyservin 0:fd24f7ca9688 32 }
garyservin 0:fd24f7ca9688 33
garyservin 0:fd24f7ca9688 34 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 35 {
garyservin 0:fd24f7ca9688 36 int offset = 0;
garyservin 0:fd24f7ca9688 37 uint32_t length_name;
garyservin 0:fd24f7ca9688 38 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 39 offset += 4;
garyservin 0:fd24f7ca9688 40 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:fd24f7ca9688 41 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 42 }
garyservin 0:fd24f7ca9688 43 inbuffer[offset+length_name-1]=0;
garyservin 0:fd24f7ca9688 44 this->name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 45 offset += length_name;
garyservin 0:fd24f7ca9688 46 return offset;
garyservin 0:fd24f7ca9688 47 }
garyservin 0:fd24f7ca9688 48
garyservin 0:fd24f7ca9688 49 const char * getType(){ return REQUESTPARAM; };
garyservin 0:fd24f7ca9688 50 const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
garyservin 0:fd24f7ca9688 51
garyservin 0:fd24f7ca9688 52 };
garyservin 0:fd24f7ca9688 53
garyservin 0:fd24f7ca9688 54 class RequestParamResponse : public ros::Msg
garyservin 0:fd24f7ca9688 55 {
garyservin 0:fd24f7ca9688 56 public:
garyservin 0:fd24f7ca9688 57 uint8_t ints_length;
garyservin 0:fd24f7ca9688 58 int32_t st_ints;
garyservin 0:fd24f7ca9688 59 int32_t * ints;
garyservin 0:fd24f7ca9688 60 uint8_t floats_length;
garyservin 0:fd24f7ca9688 61 float st_floats;
garyservin 0:fd24f7ca9688 62 float * floats;
garyservin 0:fd24f7ca9688 63 uint8_t strings_length;
garyservin 0:fd24f7ca9688 64 char* st_strings;
garyservin 0:fd24f7ca9688 65 char* * strings;
garyservin 0:fd24f7ca9688 66
garyservin 0:fd24f7ca9688 67 RequestParamResponse():
garyservin 0:fd24f7ca9688 68 ints_length(0), ints(NULL),
garyservin 0:fd24f7ca9688 69 floats_length(0), floats(NULL),
garyservin 0:fd24f7ca9688 70 strings_length(0), strings(NULL)
garyservin 0:fd24f7ca9688 71 {
garyservin 0:fd24f7ca9688 72 }
garyservin 0:fd24f7ca9688 73
garyservin 0:fd24f7ca9688 74 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 75 {
garyservin 0:fd24f7ca9688 76 int offset = 0;
garyservin 0:fd24f7ca9688 77 *(outbuffer + offset++) = ints_length;
garyservin 0:fd24f7ca9688 78 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 79 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 80 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 81 for( uint8_t i = 0; i < ints_length; i++){
garyservin 0:fd24f7ca9688 82 union {
garyservin 0:fd24f7ca9688 83 int32_t real;
garyservin 0:fd24f7ca9688 84 uint32_t base;
garyservin 0:fd24f7ca9688 85 } u_intsi;
garyservin 0:fd24f7ca9688 86 u_intsi.real = this->ints[i];
garyservin 0:fd24f7ca9688 87 *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 88 *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 89 *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 90 *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 91 offset += sizeof(this->ints[i]);
garyservin 0:fd24f7ca9688 92 }
garyservin 0:fd24f7ca9688 93 *(outbuffer + offset++) = floats_length;
garyservin 0:fd24f7ca9688 94 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 95 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 96 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 97 for( uint8_t i = 0; i < floats_length; i++){
garyservin 0:fd24f7ca9688 98 union {
garyservin 0:fd24f7ca9688 99 float real;
garyservin 0:fd24f7ca9688 100 uint32_t base;
garyservin 0:fd24f7ca9688 101 } u_floatsi;
garyservin 0:fd24f7ca9688 102 u_floatsi.real = this->floats[i];
garyservin 0:fd24f7ca9688 103 *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 104 *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 105 *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 106 *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 107 offset += sizeof(this->floats[i]);
garyservin 0:fd24f7ca9688 108 }
garyservin 0:fd24f7ca9688 109 *(outbuffer + offset++) = strings_length;
garyservin 0:fd24f7ca9688 110 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 111 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 112 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 113 for( uint8_t i = 0; i < strings_length; i++){
garyservin 0:fd24f7ca9688 114 uint32_t length_stringsi = strlen(this->strings[i]);
garyservin 0:fd24f7ca9688 115 memcpy(outbuffer + offset, &length_stringsi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 116 offset += 4;
garyservin 0:fd24f7ca9688 117 memcpy(outbuffer + offset, this->strings[i], length_stringsi);
garyservin 0:fd24f7ca9688 118 offset += length_stringsi;
garyservin 0:fd24f7ca9688 119 }
garyservin 0:fd24f7ca9688 120 return offset;
garyservin 0:fd24f7ca9688 121 }
garyservin 0:fd24f7ca9688 122
garyservin 0:fd24f7ca9688 123 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 124 {
garyservin 0:fd24f7ca9688 125 int offset = 0;
garyservin 0:fd24f7ca9688 126 uint8_t ints_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 127 if(ints_lengthT > ints_length)
garyservin 0:fd24f7ca9688 128 this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t));
garyservin 0:fd24f7ca9688 129 offset += 3;
garyservin 0:fd24f7ca9688 130 ints_length = ints_lengthT;
garyservin 0:fd24f7ca9688 131 for( uint8_t i = 0; i < ints_length; i++){
garyservin 0:fd24f7ca9688 132 union {
garyservin 0:fd24f7ca9688 133 int32_t real;
garyservin 0:fd24f7ca9688 134 uint32_t base;
garyservin 0:fd24f7ca9688 135 } u_st_ints;
garyservin 0:fd24f7ca9688 136 u_st_ints.base = 0;
garyservin 0:fd24f7ca9688 137 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 138 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 139 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 140 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 141 this->st_ints = u_st_ints.real;
garyservin 0:fd24f7ca9688 142 offset += sizeof(this->st_ints);
garyservin 0:fd24f7ca9688 143 memcpy( &(this->ints[i]), &(this->st_ints), sizeof(int32_t));
garyservin 0:fd24f7ca9688 144 }
garyservin 0:fd24f7ca9688 145 uint8_t floats_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 146 if(floats_lengthT > floats_length)
garyservin 0:fd24f7ca9688 147 this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float));
garyservin 0:fd24f7ca9688 148 offset += 3;
garyservin 0:fd24f7ca9688 149 floats_length = floats_lengthT;
garyservin 0:fd24f7ca9688 150 for( uint8_t i = 0; i < floats_length; i++){
garyservin 0:fd24f7ca9688 151 union {
garyservin 0:fd24f7ca9688 152 float real;
garyservin 0:fd24f7ca9688 153 uint32_t base;
garyservin 0:fd24f7ca9688 154 } u_st_floats;
garyservin 0:fd24f7ca9688 155 u_st_floats.base = 0;
garyservin 0:fd24f7ca9688 156 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 157 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 158 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 159 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 160 this->st_floats = u_st_floats.real;
garyservin 0:fd24f7ca9688 161 offset += sizeof(this->st_floats);
garyservin 0:fd24f7ca9688 162 memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float));
garyservin 0:fd24f7ca9688 163 }
garyservin 0:fd24f7ca9688 164 uint8_t strings_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 165 if(strings_lengthT > strings_length)
garyservin 0:fd24f7ca9688 166 this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 167 offset += 3;
garyservin 0:fd24f7ca9688 168 strings_length = strings_lengthT;
garyservin 0:fd24f7ca9688 169 for( uint8_t i = 0; i < strings_length; i++){
garyservin 0:fd24f7ca9688 170 uint32_t length_st_strings;
garyservin 0:fd24f7ca9688 171 memcpy(&length_st_strings, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 172 offset += 4;
garyservin 0:fd24f7ca9688 173 for(unsigned int k= offset; k< offset+length_st_strings; ++k){
garyservin 0:fd24f7ca9688 174 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 175 }
garyservin 0:fd24f7ca9688 176 inbuffer[offset+length_st_strings-1]=0;
garyservin 0:fd24f7ca9688 177 this->st_strings = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 178 offset += length_st_strings;
garyservin 0:fd24f7ca9688 179 memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*));
garyservin 0:fd24f7ca9688 180 }
garyservin 0:fd24f7ca9688 181 return offset;
garyservin 0:fd24f7ca9688 182 }
garyservin 0:fd24f7ca9688 183
garyservin 0:fd24f7ca9688 184 const char * getType(){ return REQUESTPARAM; };
garyservin 0:fd24f7ca9688 185 const char * getMD5(){ return "9f0e98bda65981986ddf53afa7a40e49"; };
garyservin 0:fd24f7ca9688 186
garyservin 0:fd24f7ca9688 187 };
garyservin 0:fd24f7ca9688 188
garyservin 0:fd24f7ca9688 189 class RequestParam {
garyservin 0:fd24f7ca9688 190 public:
garyservin 0:fd24f7ca9688 191 typedef RequestParamRequest Request;
garyservin 0:fd24f7ca9688 192 typedef RequestParamResponse Response;
garyservin 0:fd24f7ca9688 193 };
garyservin 0:fd24f7ca9688 194
garyservin 0:fd24f7ca9688 195 }
garyservin 0:fd24f7ca9688 196 #endif