It has only one change from original one. I added robotfeedback message on it.

Dependencies:   BufferedSerial

Dependents:   RobotFeedback mobileRobotITU

Fork of ros_lib_indigo by Gary Servin

Committer:
randalthor
Date:
Sat Mar 04 14:07:56 2017 +0000
Revision:
4:80d9bee5079a
Parent:
0:fd24f7ca9688
fatih

Who changed what in which revision?

UserRevisionLine numberNew 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_ */