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