ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more

ROSSerial_mbed for Melodic 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_melodic

rosserial_mbed Hello World example for Melodic Morenia 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:
Gary Servin
Date:
Fri Nov 08 14:55:04 2019 -0300
Revision:
1:da82487f547e
Parent:
0:04ac6be8229a
Add missing round() method

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_tf2_msgs_LookupTransformGoal_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_tf2_msgs_LookupTransformGoal_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "ros/time.h"
Gary Servin 0:04ac6be8229a 9 #include "ros/duration.h"
Gary Servin 0:04ac6be8229a 10
Gary Servin 0:04ac6be8229a 11 namespace tf2_msgs
Gary Servin 0:04ac6be8229a 12 {
Gary Servin 0:04ac6be8229a 13
Gary Servin 0:04ac6be8229a 14 class LookupTransformGoal : public ros::Msg
Gary Servin 0:04ac6be8229a 15 {
Gary Servin 0:04ac6be8229a 16 public:
Gary Servin 0:04ac6be8229a 17 typedef const char* _target_frame_type;
Gary Servin 0:04ac6be8229a 18 _target_frame_type target_frame;
Gary Servin 0:04ac6be8229a 19 typedef const char* _source_frame_type;
Gary Servin 0:04ac6be8229a 20 _source_frame_type source_frame;
Gary Servin 0:04ac6be8229a 21 typedef ros::Time _source_time_type;
Gary Servin 0:04ac6be8229a 22 _source_time_type source_time;
Gary Servin 0:04ac6be8229a 23 typedef ros::Duration _timeout_type;
Gary Servin 0:04ac6be8229a 24 _timeout_type timeout;
Gary Servin 0:04ac6be8229a 25 typedef ros::Time _target_time_type;
Gary Servin 0:04ac6be8229a 26 _target_time_type target_time;
Gary Servin 0:04ac6be8229a 27 typedef const char* _fixed_frame_type;
Gary Servin 0:04ac6be8229a 28 _fixed_frame_type fixed_frame;
Gary Servin 0:04ac6be8229a 29 typedef bool _advanced_type;
Gary Servin 0:04ac6be8229a 30 _advanced_type advanced;
Gary Servin 0:04ac6be8229a 31
Gary Servin 0:04ac6be8229a 32 LookupTransformGoal():
Gary Servin 0:04ac6be8229a 33 target_frame(""),
Gary Servin 0:04ac6be8229a 34 source_frame(""),
Gary Servin 0:04ac6be8229a 35 source_time(),
Gary Servin 0:04ac6be8229a 36 timeout(),
Gary Servin 0:04ac6be8229a 37 target_time(),
Gary Servin 0:04ac6be8229a 38 fixed_frame(""),
Gary Servin 0:04ac6be8229a 39 advanced(0)
Gary Servin 0:04ac6be8229a 40 {
Gary Servin 0:04ac6be8229a 41 }
Gary Servin 0:04ac6be8229a 42
Gary Servin 0:04ac6be8229a 43 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 44 {
Gary Servin 0:04ac6be8229a 45 int offset = 0;
Gary Servin 0:04ac6be8229a 46 uint32_t length_target_frame = strlen(this->target_frame);
Gary Servin 0:04ac6be8229a 47 varToArr(outbuffer + offset, length_target_frame);
Gary Servin 0:04ac6be8229a 48 offset += 4;
Gary Servin 0:04ac6be8229a 49 memcpy(outbuffer + offset, this->target_frame, length_target_frame);
Gary Servin 0:04ac6be8229a 50 offset += length_target_frame;
Gary Servin 0:04ac6be8229a 51 uint32_t length_source_frame = strlen(this->source_frame);
Gary Servin 0:04ac6be8229a 52 varToArr(outbuffer + offset, length_source_frame);
Gary Servin 0:04ac6be8229a 53 offset += 4;
Gary Servin 0:04ac6be8229a 54 memcpy(outbuffer + offset, this->source_frame, length_source_frame);
Gary Servin 0:04ac6be8229a 55 offset += length_source_frame;
Gary Servin 0:04ac6be8229a 56 *(outbuffer + offset + 0) = (this->source_time.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 57 *(outbuffer + offset + 1) = (this->source_time.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 58 *(outbuffer + offset + 2) = (this->source_time.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 59 *(outbuffer + offset + 3) = (this->source_time.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 60 offset += sizeof(this->source_time.sec);
Gary Servin 0:04ac6be8229a 61 *(outbuffer + offset + 0) = (this->source_time.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 62 *(outbuffer + offset + 1) = (this->source_time.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 63 *(outbuffer + offset + 2) = (this->source_time.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 64 *(outbuffer + offset + 3) = (this->source_time.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 65 offset += sizeof(this->source_time.nsec);
Gary Servin 0:04ac6be8229a 66 *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 67 *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 68 *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 69 *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 70 offset += sizeof(this->timeout.sec);
Gary Servin 0:04ac6be8229a 71 *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 72 *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 73 *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 74 *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 75 offset += sizeof(this->timeout.nsec);
Gary Servin 0:04ac6be8229a 76 *(outbuffer + offset + 0) = (this->target_time.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 77 *(outbuffer + offset + 1) = (this->target_time.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 78 *(outbuffer + offset + 2) = (this->target_time.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 79 *(outbuffer + offset + 3) = (this->target_time.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 80 offset += sizeof(this->target_time.sec);
Gary Servin 0:04ac6be8229a 81 *(outbuffer + offset + 0) = (this->target_time.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 1) = (this->target_time.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 *(outbuffer + offset + 2) = (this->target_time.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 84 *(outbuffer + offset + 3) = (this->target_time.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 85 offset += sizeof(this->target_time.nsec);
Gary Servin 0:04ac6be8229a 86 uint32_t length_fixed_frame = strlen(this->fixed_frame);
Gary Servin 0:04ac6be8229a 87 varToArr(outbuffer + offset, length_fixed_frame);
Gary Servin 0:04ac6be8229a 88 offset += 4;
Gary Servin 0:04ac6be8229a 89 memcpy(outbuffer + offset, this->fixed_frame, length_fixed_frame);
Gary Servin 0:04ac6be8229a 90 offset += length_fixed_frame;
Gary Servin 0:04ac6be8229a 91 union {
Gary Servin 0:04ac6be8229a 92 bool real;
Gary Servin 0:04ac6be8229a 93 uint8_t base;
Gary Servin 0:04ac6be8229a 94 } u_advanced;
Gary Servin 0:04ac6be8229a 95 u_advanced.real = this->advanced;
Gary Servin 0:04ac6be8229a 96 *(outbuffer + offset + 0) = (u_advanced.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 97 offset += sizeof(this->advanced);
Gary Servin 0:04ac6be8229a 98 return offset;
Gary Servin 0:04ac6be8229a 99 }
Gary Servin 0:04ac6be8229a 100
Gary Servin 0:04ac6be8229a 101 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 102 {
Gary Servin 0:04ac6be8229a 103 int offset = 0;
Gary Servin 0:04ac6be8229a 104 uint32_t length_target_frame;
Gary Servin 0:04ac6be8229a 105 arrToVar(length_target_frame, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 106 offset += 4;
Gary Servin 0:04ac6be8229a 107 for(unsigned int k= offset; k< offset+length_target_frame; ++k){
Gary Servin 0:04ac6be8229a 108 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 109 }
Gary Servin 0:04ac6be8229a 110 inbuffer[offset+length_target_frame-1]=0;
Gary Servin 0:04ac6be8229a 111 this->target_frame = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 112 offset += length_target_frame;
Gary Servin 0:04ac6be8229a 113 uint32_t length_source_frame;
Gary Servin 0:04ac6be8229a 114 arrToVar(length_source_frame, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 115 offset += 4;
Gary Servin 0:04ac6be8229a 116 for(unsigned int k= offset; k< offset+length_source_frame; ++k){
Gary Servin 0:04ac6be8229a 117 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 118 }
Gary Servin 0:04ac6be8229a 119 inbuffer[offset+length_source_frame-1]=0;
Gary Servin 0:04ac6be8229a 120 this->source_frame = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 121 offset += length_source_frame;
Gary Servin 0:04ac6be8229a 122 this->source_time.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 123 this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 124 this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 125 this->source_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 126 offset += sizeof(this->source_time.sec);
Gary Servin 0:04ac6be8229a 127 this->source_time.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 128 this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 129 this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 130 this->source_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 131 offset += sizeof(this->source_time.nsec);
Gary Servin 0:04ac6be8229a 132 this->timeout.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 133 this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 134 this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 135 this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 136 offset += sizeof(this->timeout.sec);
Gary Servin 0:04ac6be8229a 137 this->timeout.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 138 this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 139 this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 140 this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 141 offset += sizeof(this->timeout.nsec);
Gary Servin 0:04ac6be8229a 142 this->target_time.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 143 this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 144 this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 145 this->target_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 146 offset += sizeof(this->target_time.sec);
Gary Servin 0:04ac6be8229a 147 this->target_time.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 148 this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 149 this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 150 this->target_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 151 offset += sizeof(this->target_time.nsec);
Gary Servin 0:04ac6be8229a 152 uint32_t length_fixed_frame;
Gary Servin 0:04ac6be8229a 153 arrToVar(length_fixed_frame, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 154 offset += 4;
Gary Servin 0:04ac6be8229a 155 for(unsigned int k= offset; k< offset+length_fixed_frame; ++k){
Gary Servin 0:04ac6be8229a 156 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 157 }
Gary Servin 0:04ac6be8229a 158 inbuffer[offset+length_fixed_frame-1]=0;
Gary Servin 0:04ac6be8229a 159 this->fixed_frame = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 160 offset += length_fixed_frame;
Gary Servin 0:04ac6be8229a 161 union {
Gary Servin 0:04ac6be8229a 162 bool real;
Gary Servin 0:04ac6be8229a 163 uint8_t base;
Gary Servin 0:04ac6be8229a 164 } u_advanced;
Gary Servin 0:04ac6be8229a 165 u_advanced.base = 0;
Gary Servin 0:04ac6be8229a 166 u_advanced.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 167 this->advanced = u_advanced.real;
Gary Servin 0:04ac6be8229a 168 offset += sizeof(this->advanced);
Gary Servin 0:04ac6be8229a 169 return offset;
Gary Servin 0:04ac6be8229a 170 }
Gary Servin 0:04ac6be8229a 171
Gary Servin 0:04ac6be8229a 172 const char * getType(){ return "tf2_msgs/LookupTransformGoal"; };
Gary Servin 0:04ac6be8229a 173 const char * getMD5(){ return "35e3720468131d675a18bb6f3e5f22f8"; };
Gary Servin 0:04ac6be8229a 174
Gary Servin 0:04ac6be8229a 175 };
Gary Servin 0:04ac6be8229a 176
Gary Servin 0:04ac6be8229a 177 }
Gary Servin 0:04ac6be8229a 178 #endif