ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
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();
}
}
MbedHardware.h@0:fd24f7ca9688, 2016-03-31 (annotated)
- 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?
| User | Revision | Line number | New contents of line |
|---|---|---|---|
| garyservin | 0:fd24f7ca9688 | 1 | /* |
| garyservin | 0:fd24f7ca9688 | 2 | * MbedHardware |
| garyservin | 0:fd24f7ca9688 | 3 | * |
| garyservin | 0:fd24f7ca9688 | 4 | * Created on: Aug 17, 2011 |
| garyservin | 0:fd24f7ca9688 | 5 | * Author: nucho |
| garyservin | 0:fd24f7ca9688 | 6 | */ |
| garyservin | 0:fd24f7ca9688 | 7 | |
| garyservin | 0:fd24f7ca9688 | 8 | #ifndef ROS_MBED_HARDWARE_H_ |
| garyservin | 0:fd24f7ca9688 | 9 | #define ROS_MBED_HARDWARE_H_ |
| garyservin | 0:fd24f7ca9688 | 10 | |
| garyservin | 0:fd24f7ca9688 | 11 | #include "mbed.h" |
| garyservin | 0:fd24f7ca9688 | 12 | |
| garyservin | 0:fd24f7ca9688 | 13 | #include "BufferedSerial.h" |
| garyservin | 0:fd24f7ca9688 | 14 | |
| garyservin | 0:fd24f7ca9688 | 15 | class MbedHardware { |
| garyservin | 0:fd24f7ca9688 | 16 | public: |
| garyservin | 0:fd24f7ca9688 | 17 | MbedHardware(PinName tx, PinName rx, long baud = 57600) |
| garyservin | 0:fd24f7ca9688 | 18 | :iostream(tx, rx){ |
| garyservin | 0:fd24f7ca9688 | 19 | baud_ = baud; |
| garyservin | 0:fd24f7ca9688 | 20 | t.start(); |
| garyservin | 0:fd24f7ca9688 | 21 | } |
| garyservin | 0:fd24f7ca9688 | 22 | |
| garyservin | 0:fd24f7ca9688 | 23 | MbedHardware() |
| garyservin | 0:fd24f7ca9688 | 24 | :iostream(USBTX, USBRX) { |
| garyservin | 0:fd24f7ca9688 | 25 | baud_ = 57600; |
| garyservin | 0:fd24f7ca9688 | 26 | t.start(); |
| garyservin | 0:fd24f7ca9688 | 27 | } |
| garyservin | 0:fd24f7ca9688 | 28 | |
| garyservin | 0:fd24f7ca9688 | 29 | void setBaud(long baud){ |
| garyservin | 0:fd24f7ca9688 | 30 | this->baud_= baud; |
| garyservin | 0:fd24f7ca9688 | 31 | } |
| garyservin | 0:fd24f7ca9688 | 32 | |
| garyservin | 0:fd24f7ca9688 | 33 | int getBaud(){return baud_;} |
| garyservin | 0:fd24f7ca9688 | 34 | |
| garyservin | 0:fd24f7ca9688 | 35 | void init(){ |
| garyservin | 0:fd24f7ca9688 | 36 | iostream.baud(baud_); |
| garyservin | 0:fd24f7ca9688 | 37 | } |
| garyservin | 0:fd24f7ca9688 | 38 | |
| garyservin | 0:fd24f7ca9688 | 39 | int read(){ |
| garyservin | 0:fd24f7ca9688 | 40 | if (iostream.readable()) { |
| garyservin | 0:fd24f7ca9688 | 41 | return iostream.getc(); |
| garyservin | 0:fd24f7ca9688 | 42 | } else { |
| garyservin | 0:fd24f7ca9688 | 43 | return -1; |
| garyservin | 0:fd24f7ca9688 | 44 | } |
| garyservin | 0:fd24f7ca9688 | 45 | }; |
| garyservin | 0:fd24f7ca9688 | 46 | void write(uint8_t* data, int length) { |
| garyservin | 0:fd24f7ca9688 | 47 | for (int i=0; i<length; i++) |
| garyservin | 0:fd24f7ca9688 | 48 | iostream.putc(data[i]); |
| garyservin | 0:fd24f7ca9688 | 49 | } |
| garyservin | 0:fd24f7ca9688 | 50 | |
| garyservin | 0:fd24f7ca9688 | 51 | unsigned long time(){return t.read_ms();} |
| garyservin | 0:fd24f7ca9688 | 52 | |
| garyservin | 0:fd24f7ca9688 | 53 | protected: |
| garyservin | 0:fd24f7ca9688 | 54 | BufferedSerial iostream; |
| garyservin | 0:fd24f7ca9688 | 55 | long baud_; |
| garyservin | 0:fd24f7ca9688 | 56 | Timer t; |
| garyservin | 0:fd24f7ca9688 | 57 | }; |
| garyservin | 0:fd24f7ca9688 | 58 | |
| garyservin | 0:fd24f7ca9688 | 59 | |
| garyservin | 0:fd24f7ca9688 | 60 | #endif /* ROS_MBED_HARDWARE_H_ */ |
Gary Servin
