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_visualization_msgs_InteractiveMarker_h
garyservin 0:a906bb7c7831 2 #define _ROS_visualization_msgs_InteractiveMarker_h
garyservin 0:a906bb7c7831 3
garyservin 0:a906bb7c7831 4 #include <stdint.h>
garyservin 0:a906bb7c7831 5 #include <string.h>
garyservin 0:a906bb7c7831 6 #include <stdlib.h>
garyservin 0:a906bb7c7831 7 #include "ros/msg.h"
garyservin 0:a906bb7c7831 8 #include "std_msgs/Header.h"
garyservin 0:a906bb7c7831 9 #include "geometry_msgs/Pose.h"
garyservin 0:a906bb7c7831 10 #include "visualization_msgs/MenuEntry.h"
garyservin 0:a906bb7c7831 11 #include "visualization_msgs/InteractiveMarkerControl.h"
garyservin 0:a906bb7c7831 12
garyservin 0:a906bb7c7831 13 namespace visualization_msgs
garyservin 0:a906bb7c7831 14 {
garyservin 0:a906bb7c7831 15
garyservin 0:a906bb7c7831 16 class InteractiveMarker : public ros::Msg
garyservin 0:a906bb7c7831 17 {
garyservin 0:a906bb7c7831 18 public:
garyservin 0:a906bb7c7831 19 std_msgs::Header header;
garyservin 0:a906bb7c7831 20 geometry_msgs::Pose pose;
garyservin 0:a906bb7c7831 21 const char* name;
garyservin 0:a906bb7c7831 22 const char* description;
garyservin 0:a906bb7c7831 23 float scale;
garyservin 0:a906bb7c7831 24 uint8_t menu_entries_length;
garyservin 0:a906bb7c7831 25 visualization_msgs::MenuEntry st_menu_entries;
garyservin 0:a906bb7c7831 26 visualization_msgs::MenuEntry * menu_entries;
garyservin 0:a906bb7c7831 27 uint8_t controls_length;
garyservin 0:a906bb7c7831 28 visualization_msgs::InteractiveMarkerControl st_controls;
garyservin 0:a906bb7c7831 29 visualization_msgs::InteractiveMarkerControl * controls;
garyservin 0:a906bb7c7831 30
garyservin 0:a906bb7c7831 31 InteractiveMarker():
garyservin 0:a906bb7c7831 32 header(),
garyservin 0:a906bb7c7831 33 pose(),
garyservin 0:a906bb7c7831 34 name(""),
garyservin 0:a906bb7c7831 35 description(""),
garyservin 0:a906bb7c7831 36 scale(0),
garyservin 0:a906bb7c7831 37 menu_entries_length(0), menu_entries(NULL),
garyservin 0:a906bb7c7831 38 controls_length(0), controls(NULL)
garyservin 0:a906bb7c7831 39 {
garyservin 0:a906bb7c7831 40 }
garyservin 0:a906bb7c7831 41
garyservin 0:a906bb7c7831 42 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 43 {
garyservin 0:a906bb7c7831 44 int offset = 0;
garyservin 0:a906bb7c7831 45 offset += this->header.serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 46 offset += this->pose.serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 47 uint32_t length_name = strlen(this->name);
garyservin 0:a906bb7c7831 48 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
garyservin 0:a906bb7c7831 49 offset += 4;
garyservin 0:a906bb7c7831 50 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:a906bb7c7831 51 offset += length_name;
garyservin 0:a906bb7c7831 52 uint32_t length_description = strlen(this->description);
garyservin 0:a906bb7c7831 53 memcpy(outbuffer + offset, &length_description, sizeof(uint32_t));
garyservin 0:a906bb7c7831 54 offset += 4;
garyservin 0:a906bb7c7831 55 memcpy(outbuffer + offset, this->description, length_description);
garyservin 0:a906bb7c7831 56 offset += length_description;
garyservin 0:a906bb7c7831 57 union {
garyservin 0:a906bb7c7831 58 float real;
garyservin 0:a906bb7c7831 59 uint32_t base;
garyservin 0:a906bb7c7831 60 } u_scale;
garyservin 0:a906bb7c7831 61 u_scale.real = this->scale;
garyservin 0:a906bb7c7831 62 *(outbuffer + offset + 0) = (u_scale.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 63 *(outbuffer + offset + 1) = (u_scale.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 64 *(outbuffer + offset + 2) = (u_scale.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 65 *(outbuffer + offset + 3) = (u_scale.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 66 offset += sizeof(this->scale);
garyservin 0:a906bb7c7831 67 *(outbuffer + offset++) = menu_entries_length;
garyservin 0:a906bb7c7831 68 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 69 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 70 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 71 for( uint8_t i = 0; i < menu_entries_length; i++){
garyservin 0:a906bb7c7831 72 offset += this->menu_entries[i].serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 73 }
garyservin 0:a906bb7c7831 74 *(outbuffer + offset++) = controls_length;
garyservin 0:a906bb7c7831 75 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 76 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 77 *(outbuffer + offset++) = 0;
garyservin 0:a906bb7c7831 78 for( uint8_t i = 0; i < controls_length; i++){
garyservin 0:a906bb7c7831 79 offset += this->controls[i].serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 80 }
garyservin 0:a906bb7c7831 81 return offset;
garyservin 0:a906bb7c7831 82 }
garyservin 0:a906bb7c7831 83
garyservin 0:a906bb7c7831 84 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 85 {
garyservin 0:a906bb7c7831 86 int offset = 0;
garyservin 0:a906bb7c7831 87 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 88 offset += this->pose.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 89 uint32_t length_name;
garyservin 0:a906bb7c7831 90 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:a906bb7c7831 91 offset += 4;
garyservin 0:a906bb7c7831 92 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:a906bb7c7831 93 inbuffer[k-1]=inbuffer[k];
garyservin 0:a906bb7c7831 94 }
garyservin 0:a906bb7c7831 95 inbuffer[offset+length_name-1]=0;
garyservin 0:a906bb7c7831 96 this->name = (char *)(inbuffer + offset-1);
garyservin 0:a906bb7c7831 97 offset += length_name;
garyservin 0:a906bb7c7831 98 uint32_t length_description;
garyservin 0:a906bb7c7831 99 memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:a906bb7c7831 100 offset += 4;
garyservin 0:a906bb7c7831 101 for(unsigned int k= offset; k< offset+length_description; ++k){
garyservin 0:a906bb7c7831 102 inbuffer[k-1]=inbuffer[k];
garyservin 0:a906bb7c7831 103 }
garyservin 0:a906bb7c7831 104 inbuffer[offset+length_description-1]=0;
garyservin 0:a906bb7c7831 105 this->description = (char *)(inbuffer + offset-1);
garyservin 0:a906bb7c7831 106 offset += length_description;
garyservin 0:a906bb7c7831 107 union {
garyservin 0:a906bb7c7831 108 float real;
garyservin 0:a906bb7c7831 109 uint32_t base;
garyservin 0:a906bb7c7831 110 } u_scale;
garyservin 0:a906bb7c7831 111 u_scale.base = 0;
garyservin 0:a906bb7c7831 112 u_scale.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 113 u_scale.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 114 u_scale.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 115 u_scale.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 116 this->scale = u_scale.real;
garyservin 0:a906bb7c7831 117 offset += sizeof(this->scale);
garyservin 0:a906bb7c7831 118 uint8_t menu_entries_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 119 if(menu_entries_lengthT > menu_entries_length)
garyservin 0:a906bb7c7831 120 this->menu_entries = (visualization_msgs::MenuEntry*)realloc(this->menu_entries, menu_entries_lengthT * sizeof(visualization_msgs::MenuEntry));
garyservin 0:a906bb7c7831 121 offset += 3;
garyservin 0:a906bb7c7831 122 menu_entries_length = menu_entries_lengthT;
garyservin 0:a906bb7c7831 123 for( uint8_t i = 0; i < menu_entries_length; i++){
garyservin 0:a906bb7c7831 124 offset += this->st_menu_entries.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 125 memcpy( &(this->menu_entries[i]), &(this->st_menu_entries), sizeof(visualization_msgs::MenuEntry));
garyservin 0:a906bb7c7831 126 }
garyservin 0:a906bb7c7831 127 uint8_t controls_lengthT = *(inbuffer + offset++);
garyservin 0:a906bb7c7831 128 if(controls_lengthT > controls_length)
garyservin 0:a906bb7c7831 129 this->controls = (visualization_msgs::InteractiveMarkerControl*)realloc(this->controls, controls_lengthT * sizeof(visualization_msgs::InteractiveMarkerControl));
garyservin 0:a906bb7c7831 130 offset += 3;
garyservin 0:a906bb7c7831 131 controls_length = controls_lengthT;
garyservin 0:a906bb7c7831 132 for( uint8_t i = 0; i < controls_length; i++){
garyservin 0:a906bb7c7831 133 offset += this->st_controls.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 134 memcpy( &(this->controls[i]), &(this->st_controls), sizeof(visualization_msgs::InteractiveMarkerControl));
garyservin 0:a906bb7c7831 135 }
garyservin 0:a906bb7c7831 136 return offset;
garyservin 0:a906bb7c7831 137 }
garyservin 0:a906bb7c7831 138
garyservin 0:a906bb7c7831 139 const char * getType(){ return "visualization_msgs/InteractiveMarker"; };
garyservin 0:a906bb7c7831 140 const char * getMD5(){ return "dd86d22909d5a3364b384492e35c10af"; };
garyservin 0:a906bb7c7831 141
garyservin 0:a906bb7c7831 142 };
garyservin 0:a906bb7c7831 143
garyservin 0:a906bb7c7831 144 }
garyservin 0:a906bb7c7831 145 #endif