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_GetWorldProperties_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_GetWorldProperties_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 gazebo_msgs
garyservin 0:fd24f7ca9688 9 {
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 static const char GETWORLDPROPERTIES[] = "gazebo_msgs/GetWorldProperties";
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class GetWorldPropertiesRequest : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16
garyservin 0:fd24f7ca9688 17 GetWorldPropertiesRequest()
garyservin 0:fd24f7ca9688 18 {
garyservin 0:fd24f7ca9688 19 }
garyservin 0:fd24f7ca9688 20
garyservin 0:fd24f7ca9688 21 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 22 {
garyservin 0:fd24f7ca9688 23 int offset = 0;
garyservin 0:fd24f7ca9688 24 return offset;
garyservin 0:fd24f7ca9688 25 }
garyservin 0:fd24f7ca9688 26
garyservin 0:fd24f7ca9688 27 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 28 {
garyservin 0:fd24f7ca9688 29 int offset = 0;
garyservin 0:fd24f7ca9688 30 return offset;
garyservin 0:fd24f7ca9688 31 }
garyservin 0:fd24f7ca9688 32
garyservin 0:fd24f7ca9688 33 const char * getType(){ return GETWORLDPROPERTIES; };
garyservin 0:fd24f7ca9688 34 const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
garyservin 0:fd24f7ca9688 35
garyservin 0:fd24f7ca9688 36 };
garyservin 0:fd24f7ca9688 37
garyservin 0:fd24f7ca9688 38 class GetWorldPropertiesResponse : public ros::Msg
garyservin 0:fd24f7ca9688 39 {
garyservin 0:fd24f7ca9688 40 public:
garyservin 0:fd24f7ca9688 41 double sim_time;
garyservin 0:fd24f7ca9688 42 uint8_t model_names_length;
garyservin 0:fd24f7ca9688 43 char* st_model_names;
garyservin 0:fd24f7ca9688 44 char* * model_names;
garyservin 0:fd24f7ca9688 45 bool rendering_enabled;
garyservin 0:fd24f7ca9688 46 bool success;
garyservin 0:fd24f7ca9688 47 const char* status_message;
garyservin 0:fd24f7ca9688 48
garyservin 0:fd24f7ca9688 49 GetWorldPropertiesResponse():
garyservin 0:fd24f7ca9688 50 sim_time(0),
garyservin 0:fd24f7ca9688 51 model_names_length(0), model_names(NULL),
garyservin 0:fd24f7ca9688 52 rendering_enabled(0),
garyservin 0:fd24f7ca9688 53 success(0),
garyservin 0:fd24f7ca9688 54 status_message("")
garyservin 0:fd24f7ca9688 55 {
garyservin 0:fd24f7ca9688 56 }
garyservin 0:fd24f7ca9688 57
garyservin 0:fd24f7ca9688 58 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 59 {
garyservin 0:fd24f7ca9688 60 int offset = 0;
garyservin 0:fd24f7ca9688 61 union {
garyservin 0:fd24f7ca9688 62 double real;
garyservin 0:fd24f7ca9688 63 uint64_t base;
garyservin 0:fd24f7ca9688 64 } u_sim_time;
garyservin 0:fd24f7ca9688 65 u_sim_time.real = this->sim_time;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset + 0) = (u_sim_time.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 67 *(outbuffer + offset + 1) = (u_sim_time.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset + 2) = (u_sim_time.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 69 *(outbuffer + offset + 3) = (u_sim_time.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 70 *(outbuffer + offset + 4) = (u_sim_time.base >> (8 * 4)) & 0xFF;
garyservin 0:fd24f7ca9688 71 *(outbuffer + offset + 5) = (u_sim_time.base >> (8 * 5)) & 0xFF;
garyservin 0:fd24f7ca9688 72 *(outbuffer + offset + 6) = (u_sim_time.base >> (8 * 6)) & 0xFF;
garyservin 0:fd24f7ca9688 73 *(outbuffer + offset + 7) = (u_sim_time.base >> (8 * 7)) & 0xFF;
garyservin 0:fd24f7ca9688 74 offset += sizeof(this->sim_time);
garyservin 0:fd24f7ca9688 75 *(outbuffer + offset++) = model_names_length;
garyservin 0:fd24f7ca9688 76 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 77 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 78 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 79 for( uint8_t i = 0; i < model_names_length; i++){
garyservin 0:fd24f7ca9688 80 uint32_t length_model_namesi = strlen(this->model_names[i]);
garyservin 0:fd24f7ca9688 81 memcpy(outbuffer + offset, &length_model_namesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 82 offset += 4;
garyservin 0:fd24f7ca9688 83 memcpy(outbuffer + offset, this->model_names[i], length_model_namesi);
garyservin 0:fd24f7ca9688 84 offset += length_model_namesi;
garyservin 0:fd24f7ca9688 85 }
garyservin 0:fd24f7ca9688 86 union {
garyservin 0:fd24f7ca9688 87 bool real;
garyservin 0:fd24f7ca9688 88 uint8_t base;
garyservin 0:fd24f7ca9688 89 } u_rendering_enabled;
garyservin 0:fd24f7ca9688 90 u_rendering_enabled.real = this->rendering_enabled;
garyservin 0:fd24f7ca9688 91 *(outbuffer + offset + 0) = (u_rendering_enabled.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 92 offset += sizeof(this->rendering_enabled);
garyservin 0:fd24f7ca9688 93 union {
garyservin 0:fd24f7ca9688 94 bool real;
garyservin 0:fd24f7ca9688 95 uint8_t base;
garyservin 0:fd24f7ca9688 96 } u_success;
garyservin 0:fd24f7ca9688 97 u_success.real = this->success;
garyservin 0:fd24f7ca9688 98 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 99 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 100 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:fd24f7ca9688 101 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 102 offset += 4;
garyservin 0:fd24f7ca9688 103 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:fd24f7ca9688 104 offset += length_status_message;
garyservin 0:fd24f7ca9688 105 return offset;
garyservin 0:fd24f7ca9688 106 }
garyservin 0:fd24f7ca9688 107
garyservin 0:fd24f7ca9688 108 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 109 {
garyservin 0:fd24f7ca9688 110 int offset = 0;
garyservin 0:fd24f7ca9688 111 union {
garyservin 0:fd24f7ca9688 112 double real;
garyservin 0:fd24f7ca9688 113 uint64_t base;
garyservin 0:fd24f7ca9688 114 } u_sim_time;
garyservin 0:fd24f7ca9688 115 u_sim_time.base = 0;
garyservin 0:fd24f7ca9688 116 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 117 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 118 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 119 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 120 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:fd24f7ca9688 121 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:fd24f7ca9688 122 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:fd24f7ca9688 123 u_sim_time.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:fd24f7ca9688 124 this->sim_time = u_sim_time.real;
garyservin 0:fd24f7ca9688 125 offset += sizeof(this->sim_time);
garyservin 0:fd24f7ca9688 126 uint8_t model_names_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 127 if(model_names_lengthT > model_names_length)
garyservin 0:fd24f7ca9688 128 this->model_names = (char**)realloc(this->model_names, model_names_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 129 offset += 3;
garyservin 0:fd24f7ca9688 130 model_names_length = model_names_lengthT;
garyservin 0:fd24f7ca9688 131 for( uint8_t i = 0; i < model_names_length; i++){
garyservin 0:fd24f7ca9688 132 uint32_t length_st_model_names;
garyservin 0:fd24f7ca9688 133 memcpy(&length_st_model_names, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 134 offset += 4;
garyservin 0:fd24f7ca9688 135 for(unsigned int k= offset; k< offset+length_st_model_names; ++k){
garyservin 0:fd24f7ca9688 136 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 137 }
garyservin 0:fd24f7ca9688 138 inbuffer[offset+length_st_model_names-1]=0;
garyservin 0:fd24f7ca9688 139 this->st_model_names = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 140 offset += length_st_model_names;
garyservin 0:fd24f7ca9688 141 memcpy( &(this->model_names[i]), &(this->st_model_names), sizeof(char*));
garyservin 0:fd24f7ca9688 142 }
garyservin 0:fd24f7ca9688 143 union {
garyservin 0:fd24f7ca9688 144 bool real;
garyservin 0:fd24f7ca9688 145 uint8_t base;
garyservin 0:fd24f7ca9688 146 } u_rendering_enabled;
garyservin 0:fd24f7ca9688 147 u_rendering_enabled.base = 0;
garyservin 0:fd24f7ca9688 148 u_rendering_enabled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 149 this->rendering_enabled = u_rendering_enabled.real;
garyservin 0:fd24f7ca9688 150 offset += sizeof(this->rendering_enabled);
garyservin 0:fd24f7ca9688 151 union {
garyservin 0:fd24f7ca9688 152 bool real;
garyservin 0:fd24f7ca9688 153 uint8_t base;
garyservin 0:fd24f7ca9688 154 } u_success;
garyservin 0:fd24f7ca9688 155 u_success.base = 0;
garyservin 0:fd24f7ca9688 156 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 157 this->success = u_success.real;
garyservin 0:fd24f7ca9688 158 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 159 uint32_t length_status_message;
garyservin 0:fd24f7ca9688 160 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 161 offset += 4;
garyservin 0:fd24f7ca9688 162 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:fd24f7ca9688 163 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 164 }
garyservin 0:fd24f7ca9688 165 inbuffer[offset+length_status_message-1]=0;
garyservin 0:fd24f7ca9688 166 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 167 offset += length_status_message;
garyservin 0:fd24f7ca9688 168 return offset;
garyservin 0:fd24f7ca9688 169 }
garyservin 0:fd24f7ca9688 170
garyservin 0:fd24f7ca9688 171 const char * getType(){ return GETWORLDPROPERTIES; };
garyservin 0:fd24f7ca9688 172 const char * getMD5(){ return "36bb0f2eccf4d8be971410c22818ba3f"; };
garyservin 0:fd24f7ca9688 173
garyservin 0:fd24f7ca9688 174 };
garyservin 0:fd24f7ca9688 175
garyservin 0:fd24f7ca9688 176 class GetWorldProperties {
garyservin 0:fd24f7ca9688 177 public:
garyservin 0:fd24f7ca9688 178 typedef GetWorldPropertiesRequest Request;
garyservin 0:fd24f7ca9688 179 typedef GetWorldPropertiesResponse Response;
garyservin 0:fd24f7ca9688 180 };
garyservin 0:fd24f7ca9688 181
garyservin 0:fd24f7ca9688 182 }
garyservin 0:fd24f7ca9688 183 #endif