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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_jade

ROSSerial_mbed for Jade 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_jade

rosserial_mbed Hello World example for jade 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:
Thu Mar 31 23:23:15 2016 +0000
Revision:
0:a906bb7c7831
ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:a906bb7c7831 1 #ifndef _ROS_SERVICE_GetLinkState_h
garyservin 0:a906bb7c7831 2 #define _ROS_SERVICE_GetLinkState_h
garyservin 0:a906bb7c7831 3 #include <stdint.h>
garyservin 0:a906bb7c7831 4 #include <string.h>
garyservin 0:a906bb7c7831 5 #include <stdlib.h>
garyservin 0:a906bb7c7831 6 #include "ros/msg.h"
garyservin 0:a906bb7c7831 7 #include "gazebo_msgs/LinkState.h"
garyservin 0:a906bb7c7831 8
garyservin 0:a906bb7c7831 9 namespace gazebo_msgs
garyservin 0:a906bb7c7831 10 {
garyservin 0:a906bb7c7831 11
garyservin 0:a906bb7c7831 12 static const char GETLINKSTATE[] = "gazebo_msgs/GetLinkState";
garyservin 0:a906bb7c7831 13
garyservin 0:a906bb7c7831 14 class GetLinkStateRequest : public ros::Msg
garyservin 0:a906bb7c7831 15 {
garyservin 0:a906bb7c7831 16 public:
garyservin 0:a906bb7c7831 17 const char* link_name;
garyservin 0:a906bb7c7831 18 const char* reference_frame;
garyservin 0:a906bb7c7831 19
garyservin 0:a906bb7c7831 20 GetLinkStateRequest():
garyservin 0:a906bb7c7831 21 link_name(""),
garyservin 0:a906bb7c7831 22 reference_frame("")
garyservin 0:a906bb7c7831 23 {
garyservin 0:a906bb7c7831 24 }
garyservin 0:a906bb7c7831 25
garyservin 0:a906bb7c7831 26 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 27 {
garyservin 0:a906bb7c7831 28 int offset = 0;
garyservin 0:a906bb7c7831 29 uint32_t length_link_name = strlen(this->link_name);
garyservin 0:a906bb7c7831 30 memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
garyservin 0:a906bb7c7831 31 offset += 4;
garyservin 0:a906bb7c7831 32 memcpy(outbuffer + offset, this->link_name, length_link_name);
garyservin 0:a906bb7c7831 33 offset += length_link_name;
garyservin 0:a906bb7c7831 34 uint32_t length_reference_frame = strlen(this->reference_frame);
garyservin 0:a906bb7c7831 35 memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
garyservin 0:a906bb7c7831 36 offset += 4;
garyservin 0:a906bb7c7831 37 memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
garyservin 0:a906bb7c7831 38 offset += length_reference_frame;
garyservin 0:a906bb7c7831 39 return offset;
garyservin 0:a906bb7c7831 40 }
garyservin 0:a906bb7c7831 41
garyservin 0:a906bb7c7831 42 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 43 {
garyservin 0:a906bb7c7831 44 int offset = 0;
garyservin 0:a906bb7c7831 45 uint32_t length_link_name;
garyservin 0:a906bb7c7831 46 memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:a906bb7c7831 47 offset += 4;
garyservin 0:a906bb7c7831 48 for(unsigned int k= offset; k< offset+length_link_name; ++k){
garyservin 0:a906bb7c7831 49 inbuffer[k-1]=inbuffer[k];
garyservin 0:a906bb7c7831 50 }
garyservin 0:a906bb7c7831 51 inbuffer[offset+length_link_name-1]=0;
garyservin 0:a906bb7c7831 52 this->link_name = (char *)(inbuffer + offset-1);
garyservin 0:a906bb7c7831 53 offset += length_link_name;
garyservin 0:a906bb7c7831 54 uint32_t length_reference_frame;
garyservin 0:a906bb7c7831 55 memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:a906bb7c7831 56 offset += 4;
garyservin 0:a906bb7c7831 57 for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
garyservin 0:a906bb7c7831 58 inbuffer[k-1]=inbuffer[k];
garyservin 0:a906bb7c7831 59 }
garyservin 0:a906bb7c7831 60 inbuffer[offset+length_reference_frame-1]=0;
garyservin 0:a906bb7c7831 61 this->reference_frame = (char *)(inbuffer + offset-1);
garyservin 0:a906bb7c7831 62 offset += length_reference_frame;
garyservin 0:a906bb7c7831 63 return offset;
garyservin 0:a906bb7c7831 64 }
garyservin 0:a906bb7c7831 65
garyservin 0:a906bb7c7831 66 const char * getType(){ return GETLINKSTATE; };
garyservin 0:a906bb7c7831 67 const char * getMD5(){ return "7551675c30aaa71f7c288d4864552001"; };
garyservin 0:a906bb7c7831 68
garyservin 0:a906bb7c7831 69 };
garyservin 0:a906bb7c7831 70
garyservin 0:a906bb7c7831 71 class GetLinkStateResponse : public ros::Msg
garyservin 0:a906bb7c7831 72 {
garyservin 0:a906bb7c7831 73 public:
garyservin 0:a906bb7c7831 74 gazebo_msgs::LinkState link_state;
garyservin 0:a906bb7c7831 75 bool success;
garyservin 0:a906bb7c7831 76 const char* status_message;
garyservin 0:a906bb7c7831 77
garyservin 0:a906bb7c7831 78 GetLinkStateResponse():
garyservin 0:a906bb7c7831 79 link_state(),
garyservin 0:a906bb7c7831 80 success(0),
garyservin 0:a906bb7c7831 81 status_message("")
garyservin 0:a906bb7c7831 82 {
garyservin 0:a906bb7c7831 83 }
garyservin 0:a906bb7c7831 84
garyservin 0:a906bb7c7831 85 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 86 {
garyservin 0:a906bb7c7831 87 int offset = 0;
garyservin 0:a906bb7c7831 88 offset += this->link_state.serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 89 union {
garyservin 0:a906bb7c7831 90 bool real;
garyservin 0:a906bb7c7831 91 uint8_t base;
garyservin 0:a906bb7c7831 92 } u_success;
garyservin 0:a906bb7c7831 93 u_success.real = this->success;
garyservin 0:a906bb7c7831 94 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 95 offset += sizeof(this->success);
garyservin 0:a906bb7c7831 96 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:a906bb7c7831 97 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
garyservin 0:a906bb7c7831 98 offset += 4;
garyservin 0:a906bb7c7831 99 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:a906bb7c7831 100 offset += length_status_message;
garyservin 0:a906bb7c7831 101 return offset;
garyservin 0:a906bb7c7831 102 }
garyservin 0:a906bb7c7831 103
garyservin 0:a906bb7c7831 104 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 105 {
garyservin 0:a906bb7c7831 106 int offset = 0;
garyservin 0:a906bb7c7831 107 offset += this->link_state.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 108 union {
garyservin 0:a906bb7c7831 109 bool real;
garyservin 0:a906bb7c7831 110 uint8_t base;
garyservin 0:a906bb7c7831 111 } u_success;
garyservin 0:a906bb7c7831 112 u_success.base = 0;
garyservin 0:a906bb7c7831 113 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 114 this->success = u_success.real;
garyservin 0:a906bb7c7831 115 offset += sizeof(this->success);
garyservin 0:a906bb7c7831 116 uint32_t length_status_message;
garyservin 0:a906bb7c7831 117 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:a906bb7c7831 118 offset += 4;
garyservin 0:a906bb7c7831 119 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:a906bb7c7831 120 inbuffer[k-1]=inbuffer[k];
garyservin 0:a906bb7c7831 121 }
garyservin 0:a906bb7c7831 122 inbuffer[offset+length_status_message-1]=0;
garyservin 0:a906bb7c7831 123 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:a906bb7c7831 124 offset += length_status_message;
garyservin 0:a906bb7c7831 125 return offset;
garyservin 0:a906bb7c7831 126 }
garyservin 0:a906bb7c7831 127
garyservin 0:a906bb7c7831 128 const char * getType(){ return GETLINKSTATE; };
garyservin 0:a906bb7c7831 129 const char * getMD5(){ return "8ba55ad34f9c072e75c0de57b089753b"; };
garyservin 0:a906bb7c7831 130
garyservin 0:a906bb7c7831 131 };
garyservin 0:a906bb7c7831 132
garyservin 0:a906bb7c7831 133 class GetLinkState {
garyservin 0:a906bb7c7831 134 public:
garyservin 0:a906bb7c7831 135 typedef GetLinkStateRequest Request;
garyservin 0:a906bb7c7831 136 typedef GetLinkStateResponse Response;
garyservin 0:a906bb7c7831 137 };
garyservin 0:a906bb7c7831 138
garyservin 0:a906bb7c7831 139 }
garyservin 0:a906bb7c7831 140 #endif