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_smach_msgs_SmachContainerStructure_h
garyservin 0:fd24f7ca9688 2 #define _ROS_smach_msgs_SmachContainerStructure_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
garyservin 0:fd24f7ca9688 10 namespace smach_msgs
garyservin 0:fd24f7ca9688 11 {
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class SmachContainerStructure : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 std_msgs::Header header;
garyservin 0:fd24f7ca9688 17 const char* path;
garyservin 0:fd24f7ca9688 18 uint8_t children_length;
garyservin 0:fd24f7ca9688 19 char* st_children;
garyservin 0:fd24f7ca9688 20 char* * children;
garyservin 0:fd24f7ca9688 21 uint8_t internal_outcomes_length;
garyservin 0:fd24f7ca9688 22 char* st_internal_outcomes;
garyservin 0:fd24f7ca9688 23 char* * internal_outcomes;
garyservin 0:fd24f7ca9688 24 uint8_t outcomes_from_length;
garyservin 0:fd24f7ca9688 25 char* st_outcomes_from;
garyservin 0:fd24f7ca9688 26 char* * outcomes_from;
garyservin 0:fd24f7ca9688 27 uint8_t outcomes_to_length;
garyservin 0:fd24f7ca9688 28 char* st_outcomes_to;
garyservin 0:fd24f7ca9688 29 char* * outcomes_to;
garyservin 0:fd24f7ca9688 30 uint8_t container_outcomes_length;
garyservin 0:fd24f7ca9688 31 char* st_container_outcomes;
garyservin 0:fd24f7ca9688 32 char* * container_outcomes;
garyservin 0:fd24f7ca9688 33
garyservin 0:fd24f7ca9688 34 SmachContainerStructure():
garyservin 0:fd24f7ca9688 35 header(),
garyservin 0:fd24f7ca9688 36 path(""),
garyservin 0:fd24f7ca9688 37 children_length(0), children(NULL),
garyservin 0:fd24f7ca9688 38 internal_outcomes_length(0), internal_outcomes(NULL),
garyservin 0:fd24f7ca9688 39 outcomes_from_length(0), outcomes_from(NULL),
garyservin 0:fd24f7ca9688 40 outcomes_to_length(0), outcomes_to(NULL),
garyservin 0:fd24f7ca9688 41 container_outcomes_length(0), container_outcomes(NULL)
garyservin 0:fd24f7ca9688 42 {
garyservin 0:fd24f7ca9688 43 }
garyservin 0:fd24f7ca9688 44
garyservin 0:fd24f7ca9688 45 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 46 {
garyservin 0:fd24f7ca9688 47 int offset = 0;
garyservin 0:fd24f7ca9688 48 offset += this->header.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 49 uint32_t length_path = strlen(this->path);
garyservin 0:fd24f7ca9688 50 memcpy(outbuffer + offset, &length_path, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 51 offset += 4;
garyservin 0:fd24f7ca9688 52 memcpy(outbuffer + offset, this->path, length_path);
garyservin 0:fd24f7ca9688 53 offset += length_path;
garyservin 0:fd24f7ca9688 54 *(outbuffer + offset++) = children_length;
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 57 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 58 for( uint8_t i = 0; i < children_length; i++){
garyservin 0:fd24f7ca9688 59 uint32_t length_childreni = strlen(this->children[i]);
garyservin 0:fd24f7ca9688 60 memcpy(outbuffer + offset, &length_childreni, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 61 offset += 4;
garyservin 0:fd24f7ca9688 62 memcpy(outbuffer + offset, this->children[i], length_childreni);
garyservin 0:fd24f7ca9688 63 offset += length_childreni;
garyservin 0:fd24f7ca9688 64 }
garyservin 0:fd24f7ca9688 65 *(outbuffer + offset++) = internal_outcomes_length;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 67 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 69 for( uint8_t i = 0; i < internal_outcomes_length; i++){
garyservin 0:fd24f7ca9688 70 uint32_t length_internal_outcomesi = strlen(this->internal_outcomes[i]);
garyservin 0:fd24f7ca9688 71 memcpy(outbuffer + offset, &length_internal_outcomesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 72 offset += 4;
garyservin 0:fd24f7ca9688 73 memcpy(outbuffer + offset, this->internal_outcomes[i], length_internal_outcomesi);
garyservin 0:fd24f7ca9688 74 offset += length_internal_outcomesi;
garyservin 0:fd24f7ca9688 75 }
garyservin 0:fd24f7ca9688 76 *(outbuffer + offset++) = outcomes_from_length;
garyservin 0:fd24f7ca9688 77 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 78 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 79 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 80 for( uint8_t i = 0; i < outcomes_from_length; i++){
garyservin 0:fd24f7ca9688 81 uint32_t length_outcomes_fromi = strlen(this->outcomes_from[i]);
garyservin 0:fd24f7ca9688 82 memcpy(outbuffer + offset, &length_outcomes_fromi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 83 offset += 4;
garyservin 0:fd24f7ca9688 84 memcpy(outbuffer + offset, this->outcomes_from[i], length_outcomes_fromi);
garyservin 0:fd24f7ca9688 85 offset += length_outcomes_fromi;
garyservin 0:fd24f7ca9688 86 }
garyservin 0:fd24f7ca9688 87 *(outbuffer + offset++) = outcomes_to_length;
garyservin 0:fd24f7ca9688 88 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 89 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 90 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 91 for( uint8_t i = 0; i < outcomes_to_length; i++){
garyservin 0:fd24f7ca9688 92 uint32_t length_outcomes_toi = strlen(this->outcomes_to[i]);
garyservin 0:fd24f7ca9688 93 memcpy(outbuffer + offset, &length_outcomes_toi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 94 offset += 4;
garyservin 0:fd24f7ca9688 95 memcpy(outbuffer + offset, this->outcomes_to[i], length_outcomes_toi);
garyservin 0:fd24f7ca9688 96 offset += length_outcomes_toi;
garyservin 0:fd24f7ca9688 97 }
garyservin 0:fd24f7ca9688 98 *(outbuffer + offset++) = container_outcomes_length;
garyservin 0:fd24f7ca9688 99 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 100 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 101 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 102 for( uint8_t i = 0; i < container_outcomes_length; i++){
garyservin 0:fd24f7ca9688 103 uint32_t length_container_outcomesi = strlen(this->container_outcomes[i]);
garyservin 0:fd24f7ca9688 104 memcpy(outbuffer + offset, &length_container_outcomesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 105 offset += 4;
garyservin 0:fd24f7ca9688 106 memcpy(outbuffer + offset, this->container_outcomes[i], length_container_outcomesi);
garyservin 0:fd24f7ca9688 107 offset += length_container_outcomesi;
garyservin 0:fd24f7ca9688 108 }
garyservin 0:fd24f7ca9688 109 return offset;
garyservin 0:fd24f7ca9688 110 }
garyservin 0:fd24f7ca9688 111
garyservin 0:fd24f7ca9688 112 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 113 {
garyservin 0:fd24f7ca9688 114 int offset = 0;
garyservin 0:fd24f7ca9688 115 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 116 uint32_t length_path;
garyservin 0:fd24f7ca9688 117 memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 118 offset += 4;
garyservin 0:fd24f7ca9688 119 for(unsigned int k= offset; k< offset+length_path; ++k){
garyservin 0:fd24f7ca9688 120 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 121 }
garyservin 0:fd24f7ca9688 122 inbuffer[offset+length_path-1]=0;
garyservin 0:fd24f7ca9688 123 this->path = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 124 offset += length_path;
garyservin 0:fd24f7ca9688 125 uint8_t children_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 126 if(children_lengthT > children_length)
garyservin 0:fd24f7ca9688 127 this->children = (char**)realloc(this->children, children_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 128 offset += 3;
garyservin 0:fd24f7ca9688 129 children_length = children_lengthT;
garyservin 0:fd24f7ca9688 130 for( uint8_t i = 0; i < children_length; i++){
garyservin 0:fd24f7ca9688 131 uint32_t length_st_children;
garyservin 0:fd24f7ca9688 132 memcpy(&length_st_children, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 133 offset += 4;
garyservin 0:fd24f7ca9688 134 for(unsigned int k= offset; k< offset+length_st_children; ++k){
garyservin 0:fd24f7ca9688 135 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 136 }
garyservin 0:fd24f7ca9688 137 inbuffer[offset+length_st_children-1]=0;
garyservin 0:fd24f7ca9688 138 this->st_children = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 139 offset += length_st_children;
garyservin 0:fd24f7ca9688 140 memcpy( &(this->children[i]), &(this->st_children), sizeof(char*));
garyservin 0:fd24f7ca9688 141 }
garyservin 0:fd24f7ca9688 142 uint8_t internal_outcomes_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 143 if(internal_outcomes_lengthT > internal_outcomes_length)
garyservin 0:fd24f7ca9688 144 this->internal_outcomes = (char**)realloc(this->internal_outcomes, internal_outcomes_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 145 offset += 3;
garyservin 0:fd24f7ca9688 146 internal_outcomes_length = internal_outcomes_lengthT;
garyservin 0:fd24f7ca9688 147 for( uint8_t i = 0; i < internal_outcomes_length; i++){
garyservin 0:fd24f7ca9688 148 uint32_t length_st_internal_outcomes;
garyservin 0:fd24f7ca9688 149 memcpy(&length_st_internal_outcomes, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 150 offset += 4;
garyservin 0:fd24f7ca9688 151 for(unsigned int k= offset; k< offset+length_st_internal_outcomes; ++k){
garyservin 0:fd24f7ca9688 152 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 153 }
garyservin 0:fd24f7ca9688 154 inbuffer[offset+length_st_internal_outcomes-1]=0;
garyservin 0:fd24f7ca9688 155 this->st_internal_outcomes = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 156 offset += length_st_internal_outcomes;
garyservin 0:fd24f7ca9688 157 memcpy( &(this->internal_outcomes[i]), &(this->st_internal_outcomes), sizeof(char*));
garyservin 0:fd24f7ca9688 158 }
garyservin 0:fd24f7ca9688 159 uint8_t outcomes_from_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 160 if(outcomes_from_lengthT > outcomes_from_length)
garyservin 0:fd24f7ca9688 161 this->outcomes_from = (char**)realloc(this->outcomes_from, outcomes_from_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 162 offset += 3;
garyservin 0:fd24f7ca9688 163 outcomes_from_length = outcomes_from_lengthT;
garyservin 0:fd24f7ca9688 164 for( uint8_t i = 0; i < outcomes_from_length; i++){
garyservin 0:fd24f7ca9688 165 uint32_t length_st_outcomes_from;
garyservin 0:fd24f7ca9688 166 memcpy(&length_st_outcomes_from, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 167 offset += 4;
garyservin 0:fd24f7ca9688 168 for(unsigned int k= offset; k< offset+length_st_outcomes_from; ++k){
garyservin 0:fd24f7ca9688 169 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 170 }
garyservin 0:fd24f7ca9688 171 inbuffer[offset+length_st_outcomes_from-1]=0;
garyservin 0:fd24f7ca9688 172 this->st_outcomes_from = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 173 offset += length_st_outcomes_from;
garyservin 0:fd24f7ca9688 174 memcpy( &(this->outcomes_from[i]), &(this->st_outcomes_from), sizeof(char*));
garyservin 0:fd24f7ca9688 175 }
garyservin 0:fd24f7ca9688 176 uint8_t outcomes_to_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 177 if(outcomes_to_lengthT > outcomes_to_length)
garyservin 0:fd24f7ca9688 178 this->outcomes_to = (char**)realloc(this->outcomes_to, outcomes_to_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 179 offset += 3;
garyservin 0:fd24f7ca9688 180 outcomes_to_length = outcomes_to_lengthT;
garyservin 0:fd24f7ca9688 181 for( uint8_t i = 0; i < outcomes_to_length; i++){
garyservin 0:fd24f7ca9688 182 uint32_t length_st_outcomes_to;
garyservin 0:fd24f7ca9688 183 memcpy(&length_st_outcomes_to, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 184 offset += 4;
garyservin 0:fd24f7ca9688 185 for(unsigned int k= offset; k< offset+length_st_outcomes_to; ++k){
garyservin 0:fd24f7ca9688 186 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 187 }
garyservin 0:fd24f7ca9688 188 inbuffer[offset+length_st_outcomes_to-1]=0;
garyservin 0:fd24f7ca9688 189 this->st_outcomes_to = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 190 offset += length_st_outcomes_to;
garyservin 0:fd24f7ca9688 191 memcpy( &(this->outcomes_to[i]), &(this->st_outcomes_to), sizeof(char*));
garyservin 0:fd24f7ca9688 192 }
garyservin 0:fd24f7ca9688 193 uint8_t container_outcomes_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 194 if(container_outcomes_lengthT > container_outcomes_length)
garyservin 0:fd24f7ca9688 195 this->container_outcomes = (char**)realloc(this->container_outcomes, container_outcomes_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 196 offset += 3;
garyservin 0:fd24f7ca9688 197 container_outcomes_length = container_outcomes_lengthT;
garyservin 0:fd24f7ca9688 198 for( uint8_t i = 0; i < container_outcomes_length; i++){
garyservin 0:fd24f7ca9688 199 uint32_t length_st_container_outcomes;
garyservin 0:fd24f7ca9688 200 memcpy(&length_st_container_outcomes, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 201 offset += 4;
garyservin 0:fd24f7ca9688 202 for(unsigned int k= offset; k< offset+length_st_container_outcomes; ++k){
garyservin 0:fd24f7ca9688 203 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 204 }
garyservin 0:fd24f7ca9688 205 inbuffer[offset+length_st_container_outcomes-1]=0;
garyservin 0:fd24f7ca9688 206 this->st_container_outcomes = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 207 offset += length_st_container_outcomes;
garyservin 0:fd24f7ca9688 208 memcpy( &(this->container_outcomes[i]), &(this->st_container_outcomes), sizeof(char*));
garyservin 0:fd24f7ca9688 209 }
garyservin 0:fd24f7ca9688 210 return offset;
garyservin 0:fd24f7ca9688 211 }
garyservin 0:fd24f7ca9688 212
garyservin 0:fd24f7ca9688 213 const char * getType(){ return "smach_msgs/SmachContainerStructure"; };
garyservin 0:fd24f7ca9688 214 const char * getMD5(){ return "3d3d1e0d0f99779ee9e58101a5dcf7ea"; };
garyservin 0:fd24f7ca9688 215
garyservin 0:fd24f7ca9688 216 };
garyservin 0:fd24f7ca9688 217
garyservin 0:fd24f7ca9688 218 }
garyservin 0:fd24f7ca9688 219 #endif