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_visualization_msgs_InteractiveMarkerFeedback_h
garyservin 0:fd24f7ca9688 2 #define _ROS_visualization_msgs_InteractiveMarkerFeedback_h
garyservin 0:fd24f7ca9688 3
garyservin 0:fd24f7ca9688 4 #include <stdint.h>
garyservin 0:fd24f7ca9688 5 #include <string.h>
garyservin 0:fd24f7ca9688 6 #include <stdlib.h>
garyservin 0:fd24f7ca9688 7 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 8 #include "std_msgs/Header.h"
garyservin 0:fd24f7ca9688 9 #include "geometry_msgs/Pose.h"
garyservin 0:fd24f7ca9688 10 #include "geometry_msgs/Point.h"
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 namespace visualization_msgs
garyservin 0:fd24f7ca9688 13 {
garyservin 0:fd24f7ca9688 14
garyservin 0:fd24f7ca9688 15 class InteractiveMarkerFeedback : public ros::Msg
garyservin 0:fd24f7ca9688 16 {
garyservin 0:fd24f7ca9688 17 public:
garyservin 0:fd24f7ca9688 18 std_msgs::Header header;
garyservin 0:fd24f7ca9688 19 const char* client_id;
garyservin 0:fd24f7ca9688 20 const char* marker_name;
garyservin 0:fd24f7ca9688 21 const char* control_name;
garyservin 0:fd24f7ca9688 22 uint8_t event_type;
garyservin 0:fd24f7ca9688 23 geometry_msgs::Pose pose;
garyservin 0:fd24f7ca9688 24 uint32_t menu_entry_id;
garyservin 0:fd24f7ca9688 25 geometry_msgs::Point mouse_point;
garyservin 0:fd24f7ca9688 26 bool mouse_point_valid;
garyservin 0:fd24f7ca9688 27 enum { KEEP_ALIVE = 0 };
garyservin 0:fd24f7ca9688 28 enum { POSE_UPDATE = 1 };
garyservin 0:fd24f7ca9688 29 enum { MENU_SELECT = 2 };
garyservin 0:fd24f7ca9688 30 enum { BUTTON_CLICK = 3 };
garyservin 0:fd24f7ca9688 31 enum { MOUSE_DOWN = 4 };
garyservin 0:fd24f7ca9688 32 enum { MOUSE_UP = 5 };
garyservin 0:fd24f7ca9688 33
garyservin 0:fd24f7ca9688 34 InteractiveMarkerFeedback():
garyservin 0:fd24f7ca9688 35 header(),
garyservin 0:fd24f7ca9688 36 client_id(""),
garyservin 0:fd24f7ca9688 37 marker_name(""),
garyservin 0:fd24f7ca9688 38 control_name(""),
garyservin 0:fd24f7ca9688 39 event_type(0),
garyservin 0:fd24f7ca9688 40 pose(),
garyservin 0:fd24f7ca9688 41 menu_entry_id(0),
garyservin 0:fd24f7ca9688 42 mouse_point(),
garyservin 0:fd24f7ca9688 43 mouse_point_valid(0)
garyservin 0:fd24f7ca9688 44 {
garyservin 0:fd24f7ca9688 45 }
garyservin 0:fd24f7ca9688 46
garyservin 0:fd24f7ca9688 47 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 48 {
garyservin 0:fd24f7ca9688 49 int offset = 0;
garyservin 0:fd24f7ca9688 50 offset += this->header.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 51 uint32_t length_client_id = strlen(this->client_id);
garyservin 0:fd24f7ca9688 52 memcpy(outbuffer + offset, &length_client_id, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 53 offset += 4;
garyservin 0:fd24f7ca9688 54 memcpy(outbuffer + offset, this->client_id, length_client_id);
garyservin 0:fd24f7ca9688 55 offset += length_client_id;
garyservin 0:fd24f7ca9688 56 uint32_t length_marker_name = strlen(this->marker_name);
garyservin 0:fd24f7ca9688 57 memcpy(outbuffer + offset, &length_marker_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 58 offset += 4;
garyservin 0:fd24f7ca9688 59 memcpy(outbuffer + offset, this->marker_name, length_marker_name);
garyservin 0:fd24f7ca9688 60 offset += length_marker_name;
garyservin 0:fd24f7ca9688 61 uint32_t length_control_name = strlen(this->control_name);
garyservin 0:fd24f7ca9688 62 memcpy(outbuffer + offset, &length_control_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 63 offset += 4;
garyservin 0:fd24f7ca9688 64 memcpy(outbuffer + offset, this->control_name, length_control_name);
garyservin 0:fd24f7ca9688 65 offset += length_control_name;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset + 0) = (this->event_type >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 67 offset += sizeof(this->event_type);
garyservin 0:fd24f7ca9688 68 offset += this->pose.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 69 *(outbuffer + offset + 0) = (this->menu_entry_id >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 70 *(outbuffer + offset + 1) = (this->menu_entry_id >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 71 *(outbuffer + offset + 2) = (this->menu_entry_id >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 72 *(outbuffer + offset + 3) = (this->menu_entry_id >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 73 offset += sizeof(this->menu_entry_id);
garyservin 0:fd24f7ca9688 74 offset += this->mouse_point.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 75 union {
garyservin 0:fd24f7ca9688 76 bool real;
garyservin 0:fd24f7ca9688 77 uint8_t base;
garyservin 0:fd24f7ca9688 78 } u_mouse_point_valid;
garyservin 0:fd24f7ca9688 79 u_mouse_point_valid.real = this->mouse_point_valid;
garyservin 0:fd24f7ca9688 80 *(outbuffer + offset + 0) = (u_mouse_point_valid.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 81 offset += sizeof(this->mouse_point_valid);
garyservin 0:fd24f7ca9688 82 return offset;
garyservin 0:fd24f7ca9688 83 }
garyservin 0:fd24f7ca9688 84
garyservin 0:fd24f7ca9688 85 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 86 {
garyservin 0:fd24f7ca9688 87 int offset = 0;
garyservin 0:fd24f7ca9688 88 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 89 uint32_t length_client_id;
garyservin 0:fd24f7ca9688 90 memcpy(&length_client_id, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 91 offset += 4;
garyservin 0:fd24f7ca9688 92 for(unsigned int k= offset; k< offset+length_client_id; ++k){
garyservin 0:fd24f7ca9688 93 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 94 }
garyservin 0:fd24f7ca9688 95 inbuffer[offset+length_client_id-1]=0;
garyservin 0:fd24f7ca9688 96 this->client_id = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 97 offset += length_client_id;
garyservin 0:fd24f7ca9688 98 uint32_t length_marker_name;
garyservin 0:fd24f7ca9688 99 memcpy(&length_marker_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 100 offset += 4;
garyservin 0:fd24f7ca9688 101 for(unsigned int k= offset; k< offset+length_marker_name; ++k){
garyservin 0:fd24f7ca9688 102 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 103 }
garyservin 0:fd24f7ca9688 104 inbuffer[offset+length_marker_name-1]=0;
garyservin 0:fd24f7ca9688 105 this->marker_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 106 offset += length_marker_name;
garyservin 0:fd24f7ca9688 107 uint32_t length_control_name;
garyservin 0:fd24f7ca9688 108 memcpy(&length_control_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 109 offset += 4;
garyservin 0:fd24f7ca9688 110 for(unsigned int k= offset; k< offset+length_control_name; ++k){
garyservin 0:fd24f7ca9688 111 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 112 }
garyservin 0:fd24f7ca9688 113 inbuffer[offset+length_control_name-1]=0;
garyservin 0:fd24f7ca9688 114 this->control_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 115 offset += length_control_name;
garyservin 0:fd24f7ca9688 116 this->event_type = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 117 offset += sizeof(this->event_type);
garyservin 0:fd24f7ca9688 118 offset += this->pose.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 119 this->menu_entry_id = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 120 this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 121 this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 122 this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 123 offset += sizeof(this->menu_entry_id);
garyservin 0:fd24f7ca9688 124 offset += this->mouse_point.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 125 union {
garyservin 0:fd24f7ca9688 126 bool real;
garyservin 0:fd24f7ca9688 127 uint8_t base;
garyservin 0:fd24f7ca9688 128 } u_mouse_point_valid;
garyservin 0:fd24f7ca9688 129 u_mouse_point_valid.base = 0;
garyservin 0:fd24f7ca9688 130 u_mouse_point_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 131 this->mouse_point_valid = u_mouse_point_valid.real;
garyservin 0:fd24f7ca9688 132 offset += sizeof(this->mouse_point_valid);
garyservin 0:fd24f7ca9688 133 return offset;
garyservin 0:fd24f7ca9688 134 }
garyservin 0:fd24f7ca9688 135
garyservin 0:fd24f7ca9688 136 const char * getType(){ return "visualization_msgs/InteractiveMarkerFeedback"; };
garyservin 0:fd24f7ca9688 137 const char * getMD5(){ return "ab0f1eee058667e28c19ff3ffc3f4b78"; };
garyservin 0:fd24f7ca9688 138
garyservin 0:fd24f7ca9688 139 };
garyservin 0:fd24f7ca9688 140
garyservin 0:fd24f7ca9688 141 }
garyservin 0:fd24f7ca9688 142 #endif