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_gazebo_msgs_LinkStates_h
garyservin 0:fd24f7ca9688 2 #define _ROS_gazebo_msgs_LinkStates_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 "geometry_msgs/Pose.h"
garyservin 0:fd24f7ca9688 9 #include "geometry_msgs/Twist.h"
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 namespace gazebo_msgs
garyservin 0:fd24f7ca9688 12 {
garyservin 0:fd24f7ca9688 13
garyservin 0:fd24f7ca9688 14 class LinkStates : public ros::Msg
garyservin 0:fd24f7ca9688 15 {
garyservin 0:fd24f7ca9688 16 public:
garyservin 0:fd24f7ca9688 17 uint8_t name_length;
garyservin 0:fd24f7ca9688 18 char* st_name;
garyservin 0:fd24f7ca9688 19 char* * name;
garyservin 0:fd24f7ca9688 20 uint8_t pose_length;
garyservin 0:fd24f7ca9688 21 geometry_msgs::Pose st_pose;
garyservin 0:fd24f7ca9688 22 geometry_msgs::Pose * pose;
garyservin 0:fd24f7ca9688 23 uint8_t twist_length;
garyservin 0:fd24f7ca9688 24 geometry_msgs::Twist st_twist;
garyservin 0:fd24f7ca9688 25 geometry_msgs::Twist * twist;
garyservin 0:fd24f7ca9688 26
garyservin 0:fd24f7ca9688 27 LinkStates():
garyservin 0:fd24f7ca9688 28 name_length(0), name(NULL),
garyservin 0:fd24f7ca9688 29 pose_length(0), pose(NULL),
garyservin 0:fd24f7ca9688 30 twist_length(0), twist(NULL)
garyservin 0:fd24f7ca9688 31 {
garyservin 0:fd24f7ca9688 32 }
garyservin 0:fd24f7ca9688 33
garyservin 0:fd24f7ca9688 34 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 35 {
garyservin 0:fd24f7ca9688 36 int offset = 0;
garyservin 0:fd24f7ca9688 37 *(outbuffer + offset++) = name_length;
garyservin 0:fd24f7ca9688 38 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 39 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 40 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 41 for( uint8_t i = 0; i < name_length; i++){
garyservin 0:fd24f7ca9688 42 uint32_t length_namei = strlen(this->name[i]);
garyservin 0:fd24f7ca9688 43 memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 44 offset += 4;
garyservin 0:fd24f7ca9688 45 memcpy(outbuffer + offset, this->name[i], length_namei);
garyservin 0:fd24f7ca9688 46 offset += length_namei;
garyservin 0:fd24f7ca9688 47 }
garyservin 0:fd24f7ca9688 48 *(outbuffer + offset++) = pose_length;
garyservin 0:fd24f7ca9688 49 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 50 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 51 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 52 for( uint8_t i = 0; i < pose_length; i++){
garyservin 0:fd24f7ca9688 53 offset += this->pose[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 54 }
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset++) = twist_length;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 57 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 58 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 59 for( uint8_t i = 0; i < twist_length; i++){
garyservin 0:fd24f7ca9688 60 offset += this->twist[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 61 }
garyservin 0:fd24f7ca9688 62 return offset;
garyservin 0:fd24f7ca9688 63 }
garyservin 0:fd24f7ca9688 64
garyservin 0:fd24f7ca9688 65 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 66 {
garyservin 0:fd24f7ca9688 67 int offset = 0;
garyservin 0:fd24f7ca9688 68 uint8_t name_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 69 if(name_lengthT > name_length)
garyservin 0:fd24f7ca9688 70 this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 71 offset += 3;
garyservin 0:fd24f7ca9688 72 name_length = name_lengthT;
garyservin 0:fd24f7ca9688 73 for( uint8_t i = 0; i < name_length; i++){
garyservin 0:fd24f7ca9688 74 uint32_t length_st_name;
garyservin 0:fd24f7ca9688 75 memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 76 offset += 4;
garyservin 0:fd24f7ca9688 77 for(unsigned int k= offset; k< offset+length_st_name; ++k){
garyservin 0:fd24f7ca9688 78 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 79 }
garyservin 0:fd24f7ca9688 80 inbuffer[offset+length_st_name-1]=0;
garyservin 0:fd24f7ca9688 81 this->st_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 82 offset += length_st_name;
garyservin 0:fd24f7ca9688 83 memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
garyservin 0:fd24f7ca9688 84 }
garyservin 0:fd24f7ca9688 85 uint8_t pose_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 86 if(pose_lengthT > pose_length)
garyservin 0:fd24f7ca9688 87 this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose));
garyservin 0:fd24f7ca9688 88 offset += 3;
garyservin 0:fd24f7ca9688 89 pose_length = pose_lengthT;
garyservin 0:fd24f7ca9688 90 for( uint8_t i = 0; i < pose_length; i++){
garyservin 0:fd24f7ca9688 91 offset += this->st_pose.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 92 memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose));
garyservin 0:fd24f7ca9688 93 }
garyservin 0:fd24f7ca9688 94 uint8_t twist_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 95 if(twist_lengthT > twist_length)
garyservin 0:fd24f7ca9688 96 this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist));
garyservin 0:fd24f7ca9688 97 offset += 3;
garyservin 0:fd24f7ca9688 98 twist_length = twist_lengthT;
garyservin 0:fd24f7ca9688 99 for( uint8_t i = 0; i < twist_length; i++){
garyservin 0:fd24f7ca9688 100 offset += this->st_twist.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 101 memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist));
garyservin 0:fd24f7ca9688 102 }
garyservin 0:fd24f7ca9688 103 return offset;
garyservin 0:fd24f7ca9688 104 }
garyservin 0:fd24f7ca9688 105
garyservin 0:fd24f7ca9688 106 const char * getType(){ return "gazebo_msgs/LinkStates"; };
garyservin 0:fd24f7ca9688 107 const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; };
garyservin 0:fd24f7ca9688 108
garyservin 0:fd24f7ca9688 109 };
garyservin 0:fd24f7ca9688 110
garyservin 0:fd24f7ca9688 111 }
garyservin 0:fd24f7ca9688 112 #endif