Mavlink bridge for Mbed devices

Dependents:   AIT_UWB_Range

Committer:
bhepp
Date:
Sat Feb 13 17:09:45 2016 +0000
Revision:
6:48b46bcdd5cb
Parent:
0:28183cc7963f
Updated messages

Who changed what in which revision?

UserRevisionLine numberNew contents of line
bhepp 0:28183cc7963f 1 #pragma once
bhepp 0:28183cc7963f 2
bhepp 0:28183cc7963f 3 #ifdef __MBED__
bhepp 0:28183cc7963f 4 #include "mbed.h"
bhepp 6:48b46bcdd5cb 5 #include "BufferedSerial.h"
bhepp 0:28183cc7963f 6 #endif
bhepp 0:28183cc7963f 7
bhepp 0:28183cc7963f 8 namespace ait {
bhepp 0:28183cc7963f 9
bhepp 0:28183cc7963f 10 class UART_Interface {
bhepp 0:28183cc7963f 11 public:
bhepp 0:28183cc7963f 12 virtual bool writeChar(uint8_t c) = 0;
bhepp 0:28183cc7963f 13 virtual bool isCharAvailable() = 0;
bhepp 0:28183cc7963f 14 virtual uint8_t readChar(bool* err_flag = NULL) = 0;
bhepp 0:28183cc7963f 15 };
bhepp 0:28183cc7963f 16
bhepp 0:28183cc7963f 17 #ifdef __MBED__
bhepp 0:28183cc7963f 18 class UART_Mbed : public UART_Interface {
bhepp 6:48b46bcdd5cb 19 BufferedSerial* serial_;
bhepp 0:28183cc7963f 20
bhepp 0:28183cc7963f 21 public:
bhepp 6:48b46bcdd5cb 22 UART_Mbed(BufferedSerial* serial)
bhepp 6:48b46bcdd5cb 23 : serial_(serial) {
bhepp 0:28183cc7963f 24 }
bhepp 0:28183cc7963f 25
bhepp 0:28183cc7963f 26 virtual bool writeChar(uint8_t c) {
bhepp 6:48b46bcdd5cb 27 int ret = serial_->putc(c);
bhepp 0:28183cc7963f 28 if (ret == -1) {
bhepp 0:28183cc7963f 29 return false;
bhepp 0:28183cc7963f 30 //throw std::exception("Unable to write on serial port");
bhepp 0:28183cc7963f 31 }
bhepp 0:28183cc7963f 32 return true;
bhepp 0:28183cc7963f 33 }
bhepp 0:28183cc7963f 34
bhepp 0:28183cc7963f 35 virtual bool isCharAvailable() {
bhepp 6:48b46bcdd5cb 36 return serial_->readable();
bhepp 0:28183cc7963f 37 }
bhepp 0:28183cc7963f 38
bhepp 0:28183cc7963f 39 virtual uint8_t readChar(bool* err_flag = NULL) {
bhepp 6:48b46bcdd5cb 40 int c = serial_->getc();
bhepp 0:28183cc7963f 41 if (err_flag != NULL) {
bhepp 0:28183cc7963f 42 if (c == -1)
bhepp 0:28183cc7963f 43 *err_flag = true;
bhepp 0:28183cc7963f 44 else
bhepp 0:28183cc7963f 45 *err_flag = false;
bhepp 0:28183cc7963f 46 }
bhepp 0:28183cc7963f 47 return static_cast<uint8_t>(c);
bhepp 0:28183cc7963f 48 }
bhepp 0:28183cc7963f 49 };
bhepp 0:28183cc7963f 50 #endif // __MBED__
bhepp 0:28183cc7963f 51
bhepp 0:28183cc7963f 52 }