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_SERVICE_SpawnModel_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_SpawnModel_h
garyservin 0:fd24f7ca9688 3 #include <stdint.h>
garyservin 0:fd24f7ca9688 4 #include <string.h>
garyservin 0:fd24f7ca9688 5 #include <stdlib.h>
garyservin 0:fd24f7ca9688 6 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 7 #include "geometry_msgs/Pose.h"
garyservin 0:fd24f7ca9688 8
garyservin 0:fd24f7ca9688 9 namespace gazebo_msgs
garyservin 0:fd24f7ca9688 10 {
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 static const char SPAWNMODEL[] = "gazebo_msgs/SpawnModel";
garyservin 0:fd24f7ca9688 13
garyservin 0:fd24f7ca9688 14 class SpawnModelRequest : public ros::Msg
garyservin 0:fd24f7ca9688 15 {
garyservin 0:fd24f7ca9688 16 public:
garyservin 0:fd24f7ca9688 17 const char* model_name;
garyservin 0:fd24f7ca9688 18 const char* model_xml;
garyservin 0:fd24f7ca9688 19 const char* robot_namespace;
garyservin 0:fd24f7ca9688 20 geometry_msgs::Pose initial_pose;
garyservin 0:fd24f7ca9688 21 const char* reference_frame;
garyservin 0:fd24f7ca9688 22
garyservin 0:fd24f7ca9688 23 SpawnModelRequest():
garyservin 0:fd24f7ca9688 24 model_name(""),
garyservin 0:fd24f7ca9688 25 model_xml(""),
garyservin 0:fd24f7ca9688 26 robot_namespace(""),
garyservin 0:fd24f7ca9688 27 initial_pose(),
garyservin 0:fd24f7ca9688 28 reference_frame("")
garyservin 0:fd24f7ca9688 29 {
garyservin 0:fd24f7ca9688 30 }
garyservin 0:fd24f7ca9688 31
garyservin 0:fd24f7ca9688 32 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 33 {
garyservin 0:fd24f7ca9688 34 int offset = 0;
garyservin 0:fd24f7ca9688 35 uint32_t length_model_name = strlen(this->model_name);
garyservin 0:fd24f7ca9688 36 memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 37 offset += 4;
garyservin 0:fd24f7ca9688 38 memcpy(outbuffer + offset, this->model_name, length_model_name);
garyservin 0:fd24f7ca9688 39 offset += length_model_name;
garyservin 0:fd24f7ca9688 40 uint32_t length_model_xml = strlen(this->model_xml);
garyservin 0:fd24f7ca9688 41 memcpy(outbuffer + offset, &length_model_xml, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 42 offset += 4;
garyservin 0:fd24f7ca9688 43 memcpy(outbuffer + offset, this->model_xml, length_model_xml);
garyservin 0:fd24f7ca9688 44 offset += length_model_xml;
garyservin 0:fd24f7ca9688 45 uint32_t length_robot_namespace = strlen(this->robot_namespace);
garyservin 0:fd24f7ca9688 46 memcpy(outbuffer + offset, &length_robot_namespace, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 47 offset += 4;
garyservin 0:fd24f7ca9688 48 memcpy(outbuffer + offset, this->robot_namespace, length_robot_namespace);
garyservin 0:fd24f7ca9688 49 offset += length_robot_namespace;
garyservin 0:fd24f7ca9688 50 offset += this->initial_pose.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 51 uint32_t length_reference_frame = strlen(this->reference_frame);
garyservin 0:fd24f7ca9688 52 memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 53 offset += 4;
garyservin 0:fd24f7ca9688 54 memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
garyservin 0:fd24f7ca9688 55 offset += length_reference_frame;
garyservin 0:fd24f7ca9688 56 return offset;
garyservin 0:fd24f7ca9688 57 }
garyservin 0:fd24f7ca9688 58
garyservin 0:fd24f7ca9688 59 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 60 {
garyservin 0:fd24f7ca9688 61 int offset = 0;
garyservin 0:fd24f7ca9688 62 uint32_t length_model_name;
garyservin 0:fd24f7ca9688 63 memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 64 offset += 4;
garyservin 0:fd24f7ca9688 65 for(unsigned int k= offset; k< offset+length_model_name; ++k){
garyservin 0:fd24f7ca9688 66 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 67 }
garyservin 0:fd24f7ca9688 68 inbuffer[offset+length_model_name-1]=0;
garyservin 0:fd24f7ca9688 69 this->model_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 70 offset += length_model_name;
garyservin 0:fd24f7ca9688 71 uint32_t length_model_xml;
garyservin 0:fd24f7ca9688 72 memcpy(&length_model_xml, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 73 offset += 4;
garyservin 0:fd24f7ca9688 74 for(unsigned int k= offset; k< offset+length_model_xml; ++k){
garyservin 0:fd24f7ca9688 75 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 76 }
garyservin 0:fd24f7ca9688 77 inbuffer[offset+length_model_xml-1]=0;
garyservin 0:fd24f7ca9688 78 this->model_xml = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 79 offset += length_model_xml;
garyservin 0:fd24f7ca9688 80 uint32_t length_robot_namespace;
garyservin 0:fd24f7ca9688 81 memcpy(&length_robot_namespace, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 82 offset += 4;
garyservin 0:fd24f7ca9688 83 for(unsigned int k= offset; k< offset+length_robot_namespace; ++k){
garyservin 0:fd24f7ca9688 84 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 85 }
garyservin 0:fd24f7ca9688 86 inbuffer[offset+length_robot_namespace-1]=0;
garyservin 0:fd24f7ca9688 87 this->robot_namespace = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 88 offset += length_robot_namespace;
garyservin 0:fd24f7ca9688 89 offset += this->initial_pose.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 90 uint32_t length_reference_frame;
garyservin 0:fd24f7ca9688 91 memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 92 offset += 4;
garyservin 0:fd24f7ca9688 93 for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
garyservin 0:fd24f7ca9688 94 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 95 }
garyservin 0:fd24f7ca9688 96 inbuffer[offset+length_reference_frame-1]=0;
garyservin 0:fd24f7ca9688 97 this->reference_frame = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 98 offset += length_reference_frame;
garyservin 0:fd24f7ca9688 99 return offset;
garyservin 0:fd24f7ca9688 100 }
garyservin 0:fd24f7ca9688 101
garyservin 0:fd24f7ca9688 102 const char * getType(){ return SPAWNMODEL; };
garyservin 0:fd24f7ca9688 103 const char * getMD5(){ return "6d0eba5753761cd57e6263a056b79930"; };
garyservin 0:fd24f7ca9688 104
garyservin 0:fd24f7ca9688 105 };
garyservin 0:fd24f7ca9688 106
garyservin 0:fd24f7ca9688 107 class SpawnModelResponse : public ros::Msg
garyservin 0:fd24f7ca9688 108 {
garyservin 0:fd24f7ca9688 109 public:
garyservin 0:fd24f7ca9688 110 bool success;
garyservin 0:fd24f7ca9688 111 const char* status_message;
garyservin 0:fd24f7ca9688 112
garyservin 0:fd24f7ca9688 113 SpawnModelResponse():
garyservin 0:fd24f7ca9688 114 success(0),
garyservin 0:fd24f7ca9688 115 status_message("")
garyservin 0:fd24f7ca9688 116 {
garyservin 0:fd24f7ca9688 117 }
garyservin 0:fd24f7ca9688 118
garyservin 0:fd24f7ca9688 119 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 120 {
garyservin 0:fd24f7ca9688 121 int offset = 0;
garyservin 0:fd24f7ca9688 122 union {
garyservin 0:fd24f7ca9688 123 bool real;
garyservin 0:fd24f7ca9688 124 uint8_t base;
garyservin 0:fd24f7ca9688 125 } u_success;
garyservin 0:fd24f7ca9688 126 u_success.real = this->success;
garyservin 0:fd24f7ca9688 127 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 128 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 129 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:fd24f7ca9688 130 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 131 offset += 4;
garyservin 0:fd24f7ca9688 132 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:fd24f7ca9688 133 offset += length_status_message;
garyservin 0:fd24f7ca9688 134 return offset;
garyservin 0:fd24f7ca9688 135 }
garyservin 0:fd24f7ca9688 136
garyservin 0:fd24f7ca9688 137 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 138 {
garyservin 0:fd24f7ca9688 139 int offset = 0;
garyservin 0:fd24f7ca9688 140 union {
garyservin 0:fd24f7ca9688 141 bool real;
garyservin 0:fd24f7ca9688 142 uint8_t base;
garyservin 0:fd24f7ca9688 143 } u_success;
garyservin 0:fd24f7ca9688 144 u_success.base = 0;
garyservin 0:fd24f7ca9688 145 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 146 this->success = u_success.real;
garyservin 0:fd24f7ca9688 147 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 148 uint32_t length_status_message;
garyservin 0:fd24f7ca9688 149 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 150 offset += 4;
garyservin 0:fd24f7ca9688 151 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:fd24f7ca9688 152 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 153 }
garyservin 0:fd24f7ca9688 154 inbuffer[offset+length_status_message-1]=0;
garyservin 0:fd24f7ca9688 155 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 156 offset += length_status_message;
garyservin 0:fd24f7ca9688 157 return offset;
garyservin 0:fd24f7ca9688 158 }
garyservin 0:fd24f7ca9688 159
garyservin 0:fd24f7ca9688 160 const char * getType(){ return SPAWNMODEL; };
garyservin 0:fd24f7ca9688 161 const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
garyservin 0:fd24f7ca9688 162
garyservin 0:fd24f7ca9688 163 };
garyservin 0:fd24f7ca9688 164
garyservin 0:fd24f7ca9688 165 class SpawnModel {
garyservin 0:fd24f7ca9688 166 public:
garyservin 0:fd24f7ca9688 167 typedef SpawnModelRequest Request;
garyservin 0:fd24f7ca9688 168 typedef SpawnModelResponse Response;
garyservin 0:fd24f7ca9688 169 };
garyservin 0:fd24f7ca9688 170
garyservin 0:fd24f7ca9688 171 }
garyservin 0:fd24f7ca9688 172 #endif