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_NodeletLoad_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_NodeletLoad_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 nodelet
garyservin 0:fd24f7ca9688 9 {
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 static const char NODELETLOAD[] = "nodelet/NodeletLoad";
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class NodeletLoadRequest : 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 remap_source_args_length;
garyservin 0:fd24f7ca9688 19 char* st_remap_source_args;
garyservin 0:fd24f7ca9688 20 char* * remap_source_args;
garyservin 0:fd24f7ca9688 21 uint8_t remap_target_args_length;
garyservin 0:fd24f7ca9688 22 char* st_remap_target_args;
garyservin 0:fd24f7ca9688 23 char* * remap_target_args;
garyservin 0:fd24f7ca9688 24 uint8_t my_argv_length;
garyservin 0:fd24f7ca9688 25 char* st_my_argv;
garyservin 0:fd24f7ca9688 26 char* * my_argv;
garyservin 0:fd24f7ca9688 27 const char* bond_id;
garyservin 0:fd24f7ca9688 28
garyservin 0:fd24f7ca9688 29 NodeletLoadRequest():
garyservin 0:fd24f7ca9688 30 name(""),
garyservin 0:fd24f7ca9688 31 type(""),
garyservin 0:fd24f7ca9688 32 remap_source_args_length(0), remap_source_args(NULL),
garyservin 0:fd24f7ca9688 33 remap_target_args_length(0), remap_target_args(NULL),
garyservin 0:fd24f7ca9688 34 my_argv_length(0), my_argv(NULL),
garyservin 0:fd24f7ca9688 35 bond_id("")
garyservin 0:fd24f7ca9688 36 {
garyservin 0:fd24f7ca9688 37 }
garyservin 0:fd24f7ca9688 38
garyservin 0:fd24f7ca9688 39 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 40 {
garyservin 0:fd24f7ca9688 41 int offset = 0;
garyservin 0:fd24f7ca9688 42 uint32_t length_name = strlen(this->name);
garyservin 0:fd24f7ca9688 43 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 44 offset += 4;
garyservin 0:fd24f7ca9688 45 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:fd24f7ca9688 46 offset += length_name;
garyservin 0:fd24f7ca9688 47 uint32_t length_type = strlen(this->type);
garyservin 0:fd24f7ca9688 48 memcpy(outbuffer + offset, &length_type, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 49 offset += 4;
garyservin 0:fd24f7ca9688 50 memcpy(outbuffer + offset, this->type, length_type);
garyservin 0:fd24f7ca9688 51 offset += length_type;
garyservin 0:fd24f7ca9688 52 *(outbuffer + offset++) = remap_source_args_length;
garyservin 0:fd24f7ca9688 53 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 54 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 56 for( uint8_t i = 0; i < remap_source_args_length; i++){
garyservin 0:fd24f7ca9688 57 uint32_t length_remap_source_argsi = strlen(this->remap_source_args[i]);
garyservin 0:fd24f7ca9688 58 memcpy(outbuffer + offset, &length_remap_source_argsi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 59 offset += 4;
garyservin 0:fd24f7ca9688 60 memcpy(outbuffer + offset, this->remap_source_args[i], length_remap_source_argsi);
garyservin 0:fd24f7ca9688 61 offset += length_remap_source_argsi;
garyservin 0:fd24f7ca9688 62 }
garyservin 0:fd24f7ca9688 63 *(outbuffer + offset++) = remap_target_args_length;
garyservin 0:fd24f7ca9688 64 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 65 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 67 for( uint8_t i = 0; i < remap_target_args_length; i++){
garyservin 0:fd24f7ca9688 68 uint32_t length_remap_target_argsi = strlen(this->remap_target_args[i]);
garyservin 0:fd24f7ca9688 69 memcpy(outbuffer + offset, &length_remap_target_argsi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 70 offset += 4;
garyservin 0:fd24f7ca9688 71 memcpy(outbuffer + offset, this->remap_target_args[i], length_remap_target_argsi);
garyservin 0:fd24f7ca9688 72 offset += length_remap_target_argsi;
garyservin 0:fd24f7ca9688 73 }
garyservin 0:fd24f7ca9688 74 *(outbuffer + offset++) = my_argv_length;
garyservin 0:fd24f7ca9688 75 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 76 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 77 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 78 for( uint8_t i = 0; i < my_argv_length; i++){
garyservin 0:fd24f7ca9688 79 uint32_t length_my_argvi = strlen(this->my_argv[i]);
garyservin 0:fd24f7ca9688 80 memcpy(outbuffer + offset, &length_my_argvi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 81 offset += 4;
garyservin 0:fd24f7ca9688 82 memcpy(outbuffer + offset, this->my_argv[i], length_my_argvi);
garyservin 0:fd24f7ca9688 83 offset += length_my_argvi;
garyservin 0:fd24f7ca9688 84 }
garyservin 0:fd24f7ca9688 85 uint32_t length_bond_id = strlen(this->bond_id);
garyservin 0:fd24f7ca9688 86 memcpy(outbuffer + offset, &length_bond_id, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 87 offset += 4;
garyservin 0:fd24f7ca9688 88 memcpy(outbuffer + offset, this->bond_id, length_bond_id);
garyservin 0:fd24f7ca9688 89 offset += length_bond_id;
garyservin 0:fd24f7ca9688 90 return offset;
garyservin 0:fd24f7ca9688 91 }
garyservin 0:fd24f7ca9688 92
garyservin 0:fd24f7ca9688 93 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 94 {
garyservin 0:fd24f7ca9688 95 int offset = 0;
garyservin 0:fd24f7ca9688 96 uint32_t length_name;
garyservin 0:fd24f7ca9688 97 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 98 offset += 4;
garyservin 0:fd24f7ca9688 99 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:fd24f7ca9688 100 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 101 }
garyservin 0:fd24f7ca9688 102 inbuffer[offset+length_name-1]=0;
garyservin 0:fd24f7ca9688 103 this->name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 104 offset += length_name;
garyservin 0:fd24f7ca9688 105 uint32_t length_type;
garyservin 0:fd24f7ca9688 106 memcpy(&length_type, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 107 offset += 4;
garyservin 0:fd24f7ca9688 108 for(unsigned int k= offset; k< offset+length_type; ++k){
garyservin 0:fd24f7ca9688 109 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 110 }
garyservin 0:fd24f7ca9688 111 inbuffer[offset+length_type-1]=0;
garyservin 0:fd24f7ca9688 112 this->type = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 113 offset += length_type;
garyservin 0:fd24f7ca9688 114 uint8_t remap_source_args_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 115 if(remap_source_args_lengthT > remap_source_args_length)
garyservin 0:fd24f7ca9688 116 this->remap_source_args = (char**)realloc(this->remap_source_args, remap_source_args_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 117 offset += 3;
garyservin 0:fd24f7ca9688 118 remap_source_args_length = remap_source_args_lengthT;
garyservin 0:fd24f7ca9688 119 for( uint8_t i = 0; i < remap_source_args_length; i++){
garyservin 0:fd24f7ca9688 120 uint32_t length_st_remap_source_args;
garyservin 0:fd24f7ca9688 121 memcpy(&length_st_remap_source_args, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 122 offset += 4;
garyservin 0:fd24f7ca9688 123 for(unsigned int k= offset; k< offset+length_st_remap_source_args; ++k){
garyservin 0:fd24f7ca9688 124 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 125 }
garyservin 0:fd24f7ca9688 126 inbuffer[offset+length_st_remap_source_args-1]=0;
garyservin 0:fd24f7ca9688 127 this->st_remap_source_args = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 128 offset += length_st_remap_source_args;
garyservin 0:fd24f7ca9688 129 memcpy( &(this->remap_source_args[i]), &(this->st_remap_source_args), sizeof(char*));
garyservin 0:fd24f7ca9688 130 }
garyservin 0:fd24f7ca9688 131 uint8_t remap_target_args_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 132 if(remap_target_args_lengthT > remap_target_args_length)
garyservin 0:fd24f7ca9688 133 this->remap_target_args = (char**)realloc(this->remap_target_args, remap_target_args_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 134 offset += 3;
garyservin 0:fd24f7ca9688 135 remap_target_args_length = remap_target_args_lengthT;
garyservin 0:fd24f7ca9688 136 for( uint8_t i = 0; i < remap_target_args_length; i++){
garyservin 0:fd24f7ca9688 137 uint32_t length_st_remap_target_args;
garyservin 0:fd24f7ca9688 138 memcpy(&length_st_remap_target_args, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 139 offset += 4;
garyservin 0:fd24f7ca9688 140 for(unsigned int k= offset; k< offset+length_st_remap_target_args; ++k){
garyservin 0:fd24f7ca9688 141 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 142 }
garyservin 0:fd24f7ca9688 143 inbuffer[offset+length_st_remap_target_args-1]=0;
garyservin 0:fd24f7ca9688 144 this->st_remap_target_args = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 145 offset += length_st_remap_target_args;
garyservin 0:fd24f7ca9688 146 memcpy( &(this->remap_target_args[i]), &(this->st_remap_target_args), sizeof(char*));
garyservin 0:fd24f7ca9688 147 }
garyservin 0:fd24f7ca9688 148 uint8_t my_argv_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 149 if(my_argv_lengthT > my_argv_length)
garyservin 0:fd24f7ca9688 150 this->my_argv = (char**)realloc(this->my_argv, my_argv_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 151 offset += 3;
garyservin 0:fd24f7ca9688 152 my_argv_length = my_argv_lengthT;
garyservin 0:fd24f7ca9688 153 for( uint8_t i = 0; i < my_argv_length; i++){
garyservin 0:fd24f7ca9688 154 uint32_t length_st_my_argv;
garyservin 0:fd24f7ca9688 155 memcpy(&length_st_my_argv, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 156 offset += 4;
garyservin 0:fd24f7ca9688 157 for(unsigned int k= offset; k< offset+length_st_my_argv; ++k){
garyservin 0:fd24f7ca9688 158 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 159 }
garyservin 0:fd24f7ca9688 160 inbuffer[offset+length_st_my_argv-1]=0;
garyservin 0:fd24f7ca9688 161 this->st_my_argv = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 162 offset += length_st_my_argv;
garyservin 0:fd24f7ca9688 163 memcpy( &(this->my_argv[i]), &(this->st_my_argv), sizeof(char*));
garyservin 0:fd24f7ca9688 164 }
garyservin 0:fd24f7ca9688 165 uint32_t length_bond_id;
garyservin 0:fd24f7ca9688 166 memcpy(&length_bond_id, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 167 offset += 4;
garyservin 0:fd24f7ca9688 168 for(unsigned int k= offset; k< offset+length_bond_id; ++k){
garyservin 0:fd24f7ca9688 169 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 170 }
garyservin 0:fd24f7ca9688 171 inbuffer[offset+length_bond_id-1]=0;
garyservin 0:fd24f7ca9688 172 this->bond_id = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 173 offset += length_bond_id;
garyservin 0:fd24f7ca9688 174 return offset;
garyservin 0:fd24f7ca9688 175 }
garyservin 0:fd24f7ca9688 176
garyservin 0:fd24f7ca9688 177 const char * getType(){ return NODELETLOAD; };
garyservin 0:fd24f7ca9688 178 const char * getMD5(){ return "c6e28cc4d2e259249d96cfb50658fbec"; };
garyservin 0:fd24f7ca9688 179
garyservin 0:fd24f7ca9688 180 };
garyservin 0:fd24f7ca9688 181
garyservin 0:fd24f7ca9688 182 class NodeletLoadResponse : public ros::Msg
garyservin 0:fd24f7ca9688 183 {
garyservin 0:fd24f7ca9688 184 public:
garyservin 0:fd24f7ca9688 185 bool success;
garyservin 0:fd24f7ca9688 186
garyservin 0:fd24f7ca9688 187 NodeletLoadResponse():
garyservin 0:fd24f7ca9688 188 success(0)
garyservin 0:fd24f7ca9688 189 {
garyservin 0:fd24f7ca9688 190 }
garyservin 0:fd24f7ca9688 191
garyservin 0:fd24f7ca9688 192 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 193 {
garyservin 0:fd24f7ca9688 194 int offset = 0;
garyservin 0:fd24f7ca9688 195 union {
garyservin 0:fd24f7ca9688 196 bool real;
garyservin 0:fd24f7ca9688 197 uint8_t base;
garyservin 0:fd24f7ca9688 198 } u_success;
garyservin 0:fd24f7ca9688 199 u_success.real = this->success;
garyservin 0:fd24f7ca9688 200 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 201 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 202 return offset;
garyservin 0:fd24f7ca9688 203 }
garyservin 0:fd24f7ca9688 204
garyservin 0:fd24f7ca9688 205 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 206 {
garyservin 0:fd24f7ca9688 207 int offset = 0;
garyservin 0:fd24f7ca9688 208 union {
garyservin 0:fd24f7ca9688 209 bool real;
garyservin 0:fd24f7ca9688 210 uint8_t base;
garyservin 0:fd24f7ca9688 211 } u_success;
garyservin 0:fd24f7ca9688 212 u_success.base = 0;
garyservin 0:fd24f7ca9688 213 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 214 this->success = u_success.real;
garyservin 0:fd24f7ca9688 215 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 216 return offset;
garyservin 0:fd24f7ca9688 217 }
garyservin 0:fd24f7ca9688 218
garyservin 0:fd24f7ca9688 219 const char * getType(){ return NODELETLOAD; };
garyservin 0:fd24f7ca9688 220 const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; };
garyservin 0:fd24f7ca9688 221
garyservin 0:fd24f7ca9688 222 };
garyservin 0:fd24f7ca9688 223
garyservin 0:fd24f7ca9688 224 class NodeletLoad {
garyservin 0:fd24f7ca9688 225 public:
garyservin 0:fd24f7ca9688 226 typedef NodeletLoadRequest Request;
garyservin 0:fd24f7ca9688 227 typedef NodeletLoadResponse Response;
garyservin 0:fd24f7ca9688 228 };
garyservin 0:fd24f7ca9688 229
garyservin 0:fd24f7ca9688 230 }
garyservin 0:fd24f7ca9688 231 #endif