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

Dependencies:   BufferedSerial

Dependents:   mbed-os-example-blinky

Committer:
garyservin
Date:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 /*
garyservin 0:9e9b7db60fd5 2 * MbedHardware
garyservin 0:9e9b7db60fd5 3 *
garyservin 0:9e9b7db60fd5 4 * Created on: Aug 17, 2011
garyservin 0:9e9b7db60fd5 5 * Author: nucho
garyservin 0:9e9b7db60fd5 6 */
garyservin 0:9e9b7db60fd5 7
garyservin 0:9e9b7db60fd5 8 #ifndef ROS_MBED_HARDWARE_H_
garyservin 0:9e9b7db60fd5 9 #define ROS_MBED_HARDWARE_H_
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 #include "mbed.h"
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 #include "BufferedSerial.h"
garyservin 0:9e9b7db60fd5 14
garyservin 0:9e9b7db60fd5 15 class MbedHardware {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 MbedHardware(PinName tx, PinName rx, long baud = 57600)
garyservin 0:9e9b7db60fd5 18 :iostream(tx, rx){
garyservin 0:9e9b7db60fd5 19 baud_ = baud;
garyservin 0:9e9b7db60fd5 20 t.start();
garyservin 0:9e9b7db60fd5 21 }
garyservin 0:9e9b7db60fd5 22
garyservin 0:9e9b7db60fd5 23 MbedHardware()
garyservin 0:9e9b7db60fd5 24 :iostream(USBTX, USBRX) {
garyservin 0:9e9b7db60fd5 25 baud_ = 57600;
garyservin 0:9e9b7db60fd5 26 t.start();
garyservin 0:9e9b7db60fd5 27 }
garyservin 0:9e9b7db60fd5 28
garyservin 0:9e9b7db60fd5 29 void setBaud(long baud){
garyservin 0:9e9b7db60fd5 30 this->baud_= baud;
garyservin 0:9e9b7db60fd5 31 }
garyservin 0:9e9b7db60fd5 32
garyservin 0:9e9b7db60fd5 33 int getBaud(){return baud_;}
garyservin 0:9e9b7db60fd5 34
garyservin 0:9e9b7db60fd5 35 void init(){
garyservin 0:9e9b7db60fd5 36 iostream.baud(baud_);
garyservin 0:9e9b7db60fd5 37 }
garyservin 0:9e9b7db60fd5 38
garyservin 0:9e9b7db60fd5 39 int read(){
garyservin 0:9e9b7db60fd5 40 if (iostream.readable()) {
garyservin 0:9e9b7db60fd5 41 return iostream.getc();
garyservin 0:9e9b7db60fd5 42 } else {
garyservin 0:9e9b7db60fd5 43 return -1;
garyservin 0:9e9b7db60fd5 44 }
garyservin 0:9e9b7db60fd5 45 };
garyservin 0:9e9b7db60fd5 46 void write(uint8_t* data, int length) {
garyservin 0:9e9b7db60fd5 47 for (int i=0; i<length; i++)
garyservin 0:9e9b7db60fd5 48 iostream.putc(data[i]);
garyservin 0:9e9b7db60fd5 49 }
garyservin 0:9e9b7db60fd5 50
garyservin 0:9e9b7db60fd5 51 unsigned long time(){return t.read_ms();}
garyservin 0:9e9b7db60fd5 52
garyservin 0:9e9b7db60fd5 53 protected:
garyservin 0:9e9b7db60fd5 54 BufferedSerial iostream;
garyservin 0:9e9b7db60fd5 55 long baud_;
garyservin 0:9e9b7db60fd5 56 Timer t;
garyservin 0:9e9b7db60fd5 57 };
garyservin 0:9e9b7db60fd5 58
garyservin 0:9e9b7db60fd5 59
garyservin 0:9e9b7db60fd5 60 #endif /* ROS_MBED_HARDWARE_H_ */