ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_kinetic s-rov-firmware ROS_HCSR04 DISCO-F469NI_LCDTS_demo ... more

ROSSerial_mbed for Kinetic 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_kinetic

rosserial_mbed Hello World example for Kinetic Kame distribution

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:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

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