9 changed files with 204 additions and 1 deletions
@ -0,0 +1,104 @@
@@ -0,0 +1,104 @@
|
||||
|
||||
#include <limits.h> |
||||
|
||||
#include "vprintf.h" |
||||
|
||||
#include <AP_HAL.h> |
||||
#include "Console.h" |
||||
using namespace AP_HAL_AVR; |
||||
|
||||
AVRConsoleDriver::AVRConsoleDriver() : |
||||
_user_backend(false) |
||||
{} |
||||
|
||||
// ConsoleDriver method implementations ///////////////////////////////////////
|
||||
//
|
||||
void AVRConsoleDriver::init(void* base_uart) { |
||||
_base_uart = (AP_HAL::UARTDriver*) base_uart; |
||||
} |
||||
|
||||
|
||||
void AVRConsoleDriver::backend_open() { |
||||
_user_backend = true; |
||||
} |
||||
|
||||
void AVRConsoleDriver::backend_close() { |
||||
_user_backend = false; |
||||
} |
||||
|
||||
int AVRConsoleDriver::backend_read(uint8_t *data, int len) { |
||||
return 0; |
||||
} |
||||
|
||||
int AVRConsoleDriver::backend_write(const uint8_t *data, int len) { |
||||
return 0; |
||||
} |
||||
// Print method implementations /////////////////////////////////////////
|
||||
|
||||
size_t AVRConsoleDriver::write(uint8_t c) { |
||||
if (_user_backend) { |
||||
return 1; |
||||
} else { |
||||
return _base_uart->write(c); |
||||
} |
||||
} |
||||
|
||||
// BetterStream method implementations /////////////////////////////////////////
|
||||
void AVRConsoleDriver::print_P(const prog_char_t *s) { |
||||
char c; |
||||
while ('\0' != (c = pgm_read_byte((const prog_char *)s++))) |
||||
write(c); |
||||
} |
||||
|
||||
void AVRConsoleDriver::println_P(const prog_char_t *s) { |
||||
print_P(s); |
||||
println(); |
||||
} |
||||
|
||||
void AVRConsoleDriver::printf(const char *fmt, ...) { |
||||
va_list ap; |
||||
va_start(ap, fmt); |
||||
vprintf((AP_HAL::Print*)this, 0, fmt, ap); |
||||
va_end(ap); |
||||
} |
||||
|
||||
void AVRConsoleDriver::_printf_P(const prog_char *fmt, ...) { |
||||
va_list ap; |
||||
va_start(ap, fmt); |
||||
vprintf((AP_HAL::Print*)this, 1, fmt, ap); |
||||
va_end(ap); |
||||
} |
||||
|
||||
// Stream method implementations /////////////////////////////////////////
|
||||
int AVRConsoleDriver::available(void) { |
||||
if (_user_backend) { |
||||
return INT_MAX; |
||||
} else { |
||||
return _base_uart->available(); |
||||
} |
||||
} |
||||
|
||||
int AVRConsoleDriver::txspace(void) { |
||||
if (_user_backend) { |
||||
return INT_MAX; |
||||
} else { |
||||
return _base_uart->txspace(); |
||||
} |
||||
} |
||||
|
||||
int AVRConsoleDriver::read() { |
||||
if (_user_backend) { |
||||
return -1; |
||||
} else { |
||||
return _base_uart->read(); |
||||
} |
||||
} |
||||
|
||||
int AVRConsoleDriver::peek() { |
||||
if (_user_backend) { |
||||
return -1; |
||||
} else { |
||||
return _base_uart->peek(); |
||||
} |
||||
} |
||||
|
@ -0,0 +1,40 @@
@@ -0,0 +1,40 @@
|
||||
|
||||
#ifndef __AP_HAL_AVR_CONSOLE_DRIVER_H__ |
||||
#define __AP_HAL_AVR_CONSOLE_DRIVER_H__ |
||||
|
||||
#include <AP_Common.h> |
||||
#include <AP_HAL.h> |
||||
#include "AP_HAL_AVR_Namespace.h" |
||||
|
||||
class AP_HAL_AVR::AVRConsoleDriver : public AP_HAL::ConsoleDriver { |
||||
public: |
||||
AVRConsoleDriver(); |
||||
void init(void* baseuartdriver); |
||||
void backend_open(); |
||||
void backend_close(); |
||||
int backend_read(uint8_t *data, int len); |
||||
int backend_write(const uint8_t *data, int len); |
||||
|
||||
/* Implementations of BetterStream virtual methods */ |
||||
void print_P(const prog_char_t *s); |
||||
void println_P(const prog_char_t *s); |
||||
void printf(const char *s, ...) |
||||
__attribute__ ((format(__printf__, 2, 3))); |
||||
void _printf_P(const prog_char *s, ...) |
||||
__attribute__ ((format(__printf__, 2, 3))); |
||||
|
||||
/* Implementations of Stream virtual methods */ |
||||
int available(); |
||||
int txspace(); |
||||
int read(); |
||||
int peek(); |
||||
|
||||
/* Implementations of Print virtual methods */ |
||||
size_t write(uint8_t c); |
||||
private: |
||||
AP_HAL::UARTDriver* _base_uart; |
||||
bool _user_backend; |
||||
}; |
||||
|
||||
#endif // __AP_HAL_AVR_CONSOLE_DRIVER_H__
|
||||
|
@ -0,0 +1,55 @@
@@ -0,0 +1,55 @@
|
||||
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- |
||||
|
||||
// |
||||
// Example code for the AP_HAL AVRUARTDriver, based on FastSerial |
||||
// |
||||
// This code is placed into the public domain. |
||||
// |
||||
|
||||
#include <AP_Common.h> |
||||
#include <AP_HAL.h> |
||||
#include <AP_HAL_AVR.h> |
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; |
||||
|
||||
void setup(void) |
||||
{ |
||||
// |
||||
// Set the speed for our replacement serial port. |
||||
// |
||||
hal.uart0->begin(115200); |
||||
// |
||||
// Test printing things |
||||
// |
||||
hal.console->print("test"); |
||||
hal.console->println(" begin"); |
||||
hal.console->println(1000); |
||||
hal.console->println(1000, 8); |
||||
hal.console->println(1000, 10); |
||||
hal.console->println(1000, 16); |
||||
hal.console->println_P(PSTR("progmem")); |
||||
hal.console->printf("printf %d %u %#x %p %f %S\n", -1000, 1000, 1000, 1000, 1.2345, PSTR("progmem")); |
||||
hal.console->printf_P(PSTR("printf_P %d %u %#x %p %f %S\n"), -1000, 1000, 1000, 1000, 1.2345, PSTR("progmem")); |
||||
hal.console->println("done"); |
||||
} |
||||
|
||||
void loop(void) |
||||
{ |
||||
int c; |
||||
// |
||||
// Perform a simple loopback operation. |
||||
// |
||||
c = hal.console->read(); |
||||
if (-1 != c) |
||||
hal.console->write(c); |
||||
} |
||||
|
||||
|
||||
extern "C" { |
||||
int main (void) { |
||||
hal.init(NULL); |
||||
setup(); |
||||
for(;;) loop(); |
||||
return 0; |
||||
} |
||||
} |
@ -0,0 +1,2 @@
@@ -0,0 +1,2 @@
|
||||
BOARD = mega
|
||||
include ../../../AP_Common/Arduino.mk |
Loading…
Reference in new issue