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_visualization_msgs_InteractiveMarkerControl_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_visualization_msgs_InteractiveMarkerControl_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "geometry_msgs/Quaternion.h"
garyservin 0:9e9b7db60fd5 9 #include "visualization_msgs/Marker.h"
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 namespace visualization_msgs
garyservin 0:9e9b7db60fd5 12 {
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 class InteractiveMarkerControl : public ros::Msg
garyservin 0:9e9b7db60fd5 15 {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 typedef const char* _name_type;
garyservin 0:9e9b7db60fd5 18 _name_type name;
garyservin 0:9e9b7db60fd5 19 typedef geometry_msgs::Quaternion _orientation_type;
garyservin 0:9e9b7db60fd5 20 _orientation_type orientation;
garyservin 0:9e9b7db60fd5 21 typedef uint8_t _orientation_mode_type;
garyservin 0:9e9b7db60fd5 22 _orientation_mode_type orientation_mode;
garyservin 0:9e9b7db60fd5 23 typedef uint8_t _interaction_mode_type;
garyservin 0:9e9b7db60fd5 24 _interaction_mode_type interaction_mode;
garyservin 0:9e9b7db60fd5 25 typedef bool _always_visible_type;
garyservin 0:9e9b7db60fd5 26 _always_visible_type always_visible;
garyservin 0:9e9b7db60fd5 27 uint32_t markers_length;
garyservin 0:9e9b7db60fd5 28 typedef visualization_msgs::Marker _markers_type;
garyservin 0:9e9b7db60fd5 29 _markers_type st_markers;
garyservin 0:9e9b7db60fd5 30 _markers_type * markers;
garyservin 0:9e9b7db60fd5 31 typedef bool _independent_marker_orientation_type;
garyservin 0:9e9b7db60fd5 32 _independent_marker_orientation_type independent_marker_orientation;
garyservin 0:9e9b7db60fd5 33 typedef const char* _description_type;
garyservin 0:9e9b7db60fd5 34 _description_type description;
garyservin 0:9e9b7db60fd5 35 enum { INHERIT = 0 };
garyservin 0:9e9b7db60fd5 36 enum { FIXED = 1 };
garyservin 0:9e9b7db60fd5 37 enum { VIEW_FACING = 2 };
garyservin 0:9e9b7db60fd5 38 enum { NONE = 0 };
garyservin 0:9e9b7db60fd5 39 enum { MENU = 1 };
garyservin 0:9e9b7db60fd5 40 enum { BUTTON = 2 };
garyservin 0:9e9b7db60fd5 41 enum { MOVE_AXIS = 3 };
garyservin 0:9e9b7db60fd5 42 enum { MOVE_PLANE = 4 };
garyservin 0:9e9b7db60fd5 43 enum { ROTATE_AXIS = 5 };
garyservin 0:9e9b7db60fd5 44 enum { MOVE_ROTATE = 6 };
garyservin 0:9e9b7db60fd5 45 enum { MOVE_3D = 7 };
garyservin 0:9e9b7db60fd5 46 enum { ROTATE_3D = 8 };
garyservin 0:9e9b7db60fd5 47 enum { MOVE_ROTATE_3D = 9 };
garyservin 0:9e9b7db60fd5 48
garyservin 0:9e9b7db60fd5 49 InteractiveMarkerControl():
garyservin 0:9e9b7db60fd5 50 name(""),
garyservin 0:9e9b7db60fd5 51 orientation(),
garyservin 0:9e9b7db60fd5 52 orientation_mode(0),
garyservin 0:9e9b7db60fd5 53 interaction_mode(0),
garyservin 0:9e9b7db60fd5 54 always_visible(0),
garyservin 0:9e9b7db60fd5 55 markers_length(0), markers(NULL),
garyservin 0:9e9b7db60fd5 56 independent_marker_orientation(0),
garyservin 0:9e9b7db60fd5 57 description("")
garyservin 0:9e9b7db60fd5 58 {
garyservin 0:9e9b7db60fd5 59 }
garyservin 0:9e9b7db60fd5 60
garyservin 0:9e9b7db60fd5 61 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 62 {
garyservin 0:9e9b7db60fd5 63 int offset = 0;
garyservin 0:9e9b7db60fd5 64 uint32_t length_name = strlen(this->name);
garyservin 0:9e9b7db60fd5 65 varToArr(outbuffer + offset, length_name);
garyservin 0:9e9b7db60fd5 66 offset += 4;
garyservin 0:9e9b7db60fd5 67 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:9e9b7db60fd5 68 offset += length_name;
garyservin 0:9e9b7db60fd5 69 offset += this->orientation.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 70 *(outbuffer + offset + 0) = (this->orientation_mode >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 71 offset += sizeof(this->orientation_mode);
garyservin 0:9e9b7db60fd5 72 *(outbuffer + offset + 0) = (this->interaction_mode >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 73 offset += sizeof(this->interaction_mode);
garyservin 0:9e9b7db60fd5 74 union {
garyservin 0:9e9b7db60fd5 75 bool real;
garyservin 0:9e9b7db60fd5 76 uint8_t base;
garyservin 0:9e9b7db60fd5 77 } u_always_visible;
garyservin 0:9e9b7db60fd5 78 u_always_visible.real = this->always_visible;
garyservin 0:9e9b7db60fd5 79 *(outbuffer + offset + 0) = (u_always_visible.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 80 offset += sizeof(this->always_visible);
garyservin 0:9e9b7db60fd5 81 *(outbuffer + offset + 0) = (this->markers_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 82 *(outbuffer + offset + 1) = (this->markers_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 83 *(outbuffer + offset + 2) = (this->markers_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 84 *(outbuffer + offset + 3) = (this->markers_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 85 offset += sizeof(this->markers_length);
garyservin 0:9e9b7db60fd5 86 for( uint32_t i = 0; i < markers_length; i++){
garyservin 0:9e9b7db60fd5 87 offset += this->markers[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 88 }
garyservin 0:9e9b7db60fd5 89 union {
garyservin 0:9e9b7db60fd5 90 bool real;
garyservin 0:9e9b7db60fd5 91 uint8_t base;
garyservin 0:9e9b7db60fd5 92 } u_independent_marker_orientation;
garyservin 0:9e9b7db60fd5 93 u_independent_marker_orientation.real = this->independent_marker_orientation;
garyservin 0:9e9b7db60fd5 94 *(outbuffer + offset + 0) = (u_independent_marker_orientation.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 95 offset += sizeof(this->independent_marker_orientation);
garyservin 0:9e9b7db60fd5 96 uint32_t length_description = strlen(this->description);
garyservin 0:9e9b7db60fd5 97 varToArr(outbuffer + offset, length_description);
garyservin 0:9e9b7db60fd5 98 offset += 4;
garyservin 0:9e9b7db60fd5 99 memcpy(outbuffer + offset, this->description, length_description);
garyservin 0:9e9b7db60fd5 100 offset += length_description;
garyservin 0:9e9b7db60fd5 101 return offset;
garyservin 0:9e9b7db60fd5 102 }
garyservin 0:9e9b7db60fd5 103
garyservin 0:9e9b7db60fd5 104 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 105 {
garyservin 0:9e9b7db60fd5 106 int offset = 0;
garyservin 0:9e9b7db60fd5 107 uint32_t length_name;
garyservin 0:9e9b7db60fd5 108 arrToVar(length_name, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 109 offset += 4;
garyservin 0:9e9b7db60fd5 110 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:9e9b7db60fd5 111 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 112 }
garyservin 0:9e9b7db60fd5 113 inbuffer[offset+length_name-1]=0;
garyservin 0:9e9b7db60fd5 114 this->name = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 115 offset += length_name;
garyservin 0:9e9b7db60fd5 116 offset += this->orientation.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 117 this->orientation_mode = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 118 offset += sizeof(this->orientation_mode);
garyservin 0:9e9b7db60fd5 119 this->interaction_mode = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 120 offset += sizeof(this->interaction_mode);
garyservin 0:9e9b7db60fd5 121 union {
garyservin 0:9e9b7db60fd5 122 bool real;
garyservin 0:9e9b7db60fd5 123 uint8_t base;
garyservin 0:9e9b7db60fd5 124 } u_always_visible;
garyservin 0:9e9b7db60fd5 125 u_always_visible.base = 0;
garyservin 0:9e9b7db60fd5 126 u_always_visible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 127 this->always_visible = u_always_visible.real;
garyservin 0:9e9b7db60fd5 128 offset += sizeof(this->always_visible);
garyservin 0:9e9b7db60fd5 129 uint32_t markers_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 130 markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 131 markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 132 markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 133 offset += sizeof(this->markers_length);
garyservin 0:9e9b7db60fd5 134 if(markers_lengthT > markers_length)
garyservin 0:9e9b7db60fd5 135 this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker));
garyservin 0:9e9b7db60fd5 136 markers_length = markers_lengthT;
garyservin 0:9e9b7db60fd5 137 for( uint32_t i = 0; i < markers_length; i++){
garyservin 0:9e9b7db60fd5 138 offset += this->st_markers.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 139 memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker));
garyservin 0:9e9b7db60fd5 140 }
garyservin 0:9e9b7db60fd5 141 union {
garyservin 0:9e9b7db60fd5 142 bool real;
garyservin 0:9e9b7db60fd5 143 uint8_t base;
garyservin 0:9e9b7db60fd5 144 } u_independent_marker_orientation;
garyservin 0:9e9b7db60fd5 145 u_independent_marker_orientation.base = 0;
garyservin 0:9e9b7db60fd5 146 u_independent_marker_orientation.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 147 this->independent_marker_orientation = u_independent_marker_orientation.real;
garyservin 0:9e9b7db60fd5 148 offset += sizeof(this->independent_marker_orientation);
garyservin 0:9e9b7db60fd5 149 uint32_t length_description;
garyservin 0:9e9b7db60fd5 150 arrToVar(length_description, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 151 offset += 4;
garyservin 0:9e9b7db60fd5 152 for(unsigned int k= offset; k< offset+length_description; ++k){
garyservin 0:9e9b7db60fd5 153 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 154 }
garyservin 0:9e9b7db60fd5 155 inbuffer[offset+length_description-1]=0;
garyservin 0:9e9b7db60fd5 156 this->description = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 157 offset += length_description;
garyservin 0:9e9b7db60fd5 158 return offset;
garyservin 0:9e9b7db60fd5 159 }
garyservin 0:9e9b7db60fd5 160
garyservin 0:9e9b7db60fd5 161 const char * getType(){ return "visualization_msgs/InteractiveMarkerControl"; };
garyservin 0:9e9b7db60fd5 162 const char * getMD5(){ return "b3c81e785788195d1840b86c28da1aac"; };
garyservin 0:9e9b7db60fd5 163
garyservin 0:9e9b7db60fd5 164 };
garyservin 0:9e9b7db60fd5 165
garyservin 0:9e9b7db60fd5 166 }
garyservin 0:9e9b7db60fd5 167 #endif