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_InteractiveMarkerInit_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_visualization_msgs_InteractiveMarkerInit_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 "visualization_msgs/InteractiveMarker.h"
garyservin 0:9e9b7db60fd5 9
garyservin 0:9e9b7db60fd5 10 namespace visualization_msgs
garyservin 0:9e9b7db60fd5 11 {
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 class InteractiveMarkerInit : public ros::Msg
garyservin 0:9e9b7db60fd5 14 {
garyservin 0:9e9b7db60fd5 15 public:
garyservin 0:9e9b7db60fd5 16 typedef const char* _server_id_type;
garyservin 0:9e9b7db60fd5 17 _server_id_type server_id;
garyservin 0:9e9b7db60fd5 18 typedef uint64_t _seq_num_type;
garyservin 0:9e9b7db60fd5 19 _seq_num_type seq_num;
garyservin 0:9e9b7db60fd5 20 uint32_t markers_length;
garyservin 0:9e9b7db60fd5 21 typedef visualization_msgs::InteractiveMarker _markers_type;
garyservin 0:9e9b7db60fd5 22 _markers_type st_markers;
garyservin 0:9e9b7db60fd5 23 _markers_type * markers;
garyservin 0:9e9b7db60fd5 24
garyservin 0:9e9b7db60fd5 25 InteractiveMarkerInit():
garyservin 0:9e9b7db60fd5 26 server_id(""),
garyservin 0:9e9b7db60fd5 27 seq_num(0),
garyservin 0:9e9b7db60fd5 28 markers_length(0), markers(NULL)
garyservin 0:9e9b7db60fd5 29 {
garyservin 0:9e9b7db60fd5 30 }
garyservin 0:9e9b7db60fd5 31
garyservin 0:9e9b7db60fd5 32 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 33 {
garyservin 0:9e9b7db60fd5 34 int offset = 0;
garyservin 0:9e9b7db60fd5 35 uint32_t length_server_id = strlen(this->server_id);
garyservin 0:9e9b7db60fd5 36 varToArr(outbuffer + offset, length_server_id);
garyservin 0:9e9b7db60fd5 37 offset += 4;
garyservin 0:9e9b7db60fd5 38 memcpy(outbuffer + offset, this->server_id, length_server_id);
garyservin 0:9e9b7db60fd5 39 offset += length_server_id;
garyservin 0:9e9b7db60fd5 40 union {
garyservin 0:9e9b7db60fd5 41 uint64_t real;
garyservin 0:9e9b7db60fd5 42 uint32_t base;
garyservin 0:9e9b7db60fd5 43 } u_seq_num;
garyservin 0:9e9b7db60fd5 44 u_seq_num.real = this->seq_num;
garyservin 0:9e9b7db60fd5 45 *(outbuffer + offset + 0) = (u_seq_num.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 46 *(outbuffer + offset + 1) = (u_seq_num.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 47 *(outbuffer + offset + 2) = (u_seq_num.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 48 *(outbuffer + offset + 3) = (u_seq_num.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 49 offset += sizeof(this->seq_num);
garyservin 0:9e9b7db60fd5 50 *(outbuffer + offset + 0) = (this->markers_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 51 *(outbuffer + offset + 1) = (this->markers_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 52 *(outbuffer + offset + 2) = (this->markers_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 53 *(outbuffer + offset + 3) = (this->markers_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 54 offset += sizeof(this->markers_length);
garyservin 0:9e9b7db60fd5 55 for( uint32_t i = 0; i < markers_length; i++){
garyservin 0:9e9b7db60fd5 56 offset += this->markers[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 57 }
garyservin 0:9e9b7db60fd5 58 return offset;
garyservin 0:9e9b7db60fd5 59 }
garyservin 0:9e9b7db60fd5 60
garyservin 0:9e9b7db60fd5 61 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 62 {
garyservin 0:9e9b7db60fd5 63 int offset = 0;
garyservin 0:9e9b7db60fd5 64 uint32_t length_server_id;
garyservin 0:9e9b7db60fd5 65 arrToVar(length_server_id, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 66 offset += 4;
garyservin 0:9e9b7db60fd5 67 for(unsigned int k= offset; k< offset+length_server_id; ++k){
garyservin 0:9e9b7db60fd5 68 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 69 }
garyservin 0:9e9b7db60fd5 70 inbuffer[offset+length_server_id-1]=0;
garyservin 0:9e9b7db60fd5 71 this->server_id = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 72 offset += length_server_id;
garyservin 0:9e9b7db60fd5 73 union {
garyservin 0:9e9b7db60fd5 74 uint64_t real;
garyservin 0:9e9b7db60fd5 75 uint32_t base;
garyservin 0:9e9b7db60fd5 76 } u_seq_num;
garyservin 0:9e9b7db60fd5 77 u_seq_num.base = 0;
garyservin 0:9e9b7db60fd5 78 u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 79 u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 80 u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 81 u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 82 this->seq_num = u_seq_num.real;
garyservin 0:9e9b7db60fd5 83 offset += sizeof(this->seq_num);
garyservin 0:9e9b7db60fd5 84 uint32_t markers_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 85 markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 86 markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 87 markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 88 offset += sizeof(this->markers_length);
garyservin 0:9e9b7db60fd5 89 if(markers_lengthT > markers_length)
garyservin 0:9e9b7db60fd5 90 this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker));
garyservin 0:9e9b7db60fd5 91 markers_length = markers_lengthT;
garyservin 0:9e9b7db60fd5 92 for( uint32_t i = 0; i < markers_length; i++){
garyservin 0:9e9b7db60fd5 93 offset += this->st_markers.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 94 memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::InteractiveMarker));
garyservin 0:9e9b7db60fd5 95 }
garyservin 0:9e9b7db60fd5 96 return offset;
garyservin 0:9e9b7db60fd5 97 }
garyservin 0:9e9b7db60fd5 98
garyservin 0:9e9b7db60fd5 99 const char * getType(){ return "visualization_msgs/InteractiveMarkerInit"; };
garyservin 0:9e9b7db60fd5 100 const char * getMD5(){ return "d5f2c5045a72456d228676ab91048734"; };
garyservin 0:9e9b7db60fd5 101
garyservin 0:9e9b7db60fd5 102 };
garyservin 0:9e9b7db60fd5 103
garyservin 0:9e9b7db60fd5 104 }
garyservin 0:9e9b7db60fd5 105 #endif