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:59:58 2016 +0000
Revision:
1:a849bf78d77f
Parent:
0:9e9b7db60fd5
Add missing round() method

Who changed what in which revision?

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