AP_HAL_PX4: trivial console header

This commit is contained in:
Pat Hickey 2012-10-26 22:18:51 -07:00 committed by Andrew Tridgell
parent a4f1f6a5db
commit 2d363e0683
10 changed files with 164 additions and 0 deletions

View File

@ -0,0 +1,26 @@
#include <AP_HAL.h>
#include "AP_HAL_PX4.h"
#include "HAL_PX4.h"
#include "UARTDriver.h"
using namespace AP_HAL;
using namespace AP_HAL_PX4;
const HAL_PX4 AP_HAL_PX4_Instance(
(UARTDriver*) NULL,
(UARTDriver*) NULL,
(UARTDriver*) NULL,
(UARTDriver*) NULL,
(I2CDriver*) NULL,
(SPIDriver*) NULL,
(AnalogIn*) NULL,
(Storage*) NULL,
(Dataflash*) NULL,
(ConsoleDriver*) NULL,
(GPIO*) NULL,
(RCInput*) NULL,
(RCOutput*) NULL,
(Scheduler*) NULL);

View File

@ -0,0 +1,17 @@
#ifndef __AP_HAL_PX4_H__
#define __AP_HAL_PX4_H__
#include <AP_HAL.h>
#include "HAL_PX4.h"
/**
* This module exports AP_HAL instances only.
* All internal drivers must conform to AP_HAL interfaces
* and not expose implementation details.
*/
extern const AP_HAL_PX4::HAL_PX4 AP_HAL_PX4_Instance;
#endif // __AP_HAL_PX4_H__

View File

@ -0,0 +1,12 @@
#ifndef __AP_HAL_PX4_NAMESPACE_H__
#define __AP_HAL_PX4_NAMESPACE_H__
namespace AP_HAL_PX4 {
class HAL_PX4;
class PX4ConsoleDriver;
}
#endif //__AP_HAL_PX4_NAMESPACE_H__

View File

@ -0,0 +1,35 @@
#ifndef __AP_HAL_PX4_CONSOLE_DRIVER_H__
#define __AP_HAL_PX4_CONSOLE_DRIVER_H__
#include <AP_HAL.h>
#include <AP_HAL_PX4_Namespace.h>
class AP_HAL_PX4::PX4ConsoleDriver : public AP_HAL::ConsoleDriver {
PX4ConsoleDriver();
void init(void*);
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);
};
#endif // __AP_HAL_PX4_CONSOLE_DRIVER_H__

View File

@ -0,0 +1,9 @@
#include "HAL_PX4.h"
using namespace AP_HAL_PX4;
void HAL_PX4::init(void* opts) const {
console->init(NULL);
};

View File

@ -0,0 +1,39 @@
#ifndef __AP_HAL_PX4_HAL_PX4_H__
#define __AP_HAL_PX4_HAL_PX4_H__
#include <AP_HAL.h>
#include "AP_HAL_PX4_Namespace.h"
/**
* HAL_PX4 class derives from HAL but provides an PX4-specific
* init method.
*/
class AP_HAL_PX4::HAL_PX4 : public AP_HAL::HAL {
public:
HAL_PX4(
AP_HAL::UARTDriver* _uart0,
AP_HAL::UARTDriver* _uart1,
AP_HAL::UARTDriver* _uart2,
AP_HAL::UARTDriver* _uart3,
AP_HAL::I2CDriver* _i2c,
AP_HAL::SPIDriver* _spi,
AP_HAL::AnalogIn* _analogin,
AP_HAL::Storage* _storage,
AP_HAL::Dataflash* _dataflash,
AP_HAL::ConsoleDriver* _console,
AP_HAL::GPIO* _gpio,
AP_HAL::RCInput* _rcin,
AP_HAL::RCOutput* _rcout,
AP_HAL::Scheduler* _scheduler)
: AP_HAL::HAL( _uart0, _uart1, _uart2, _uart3,
_i2c, _spi, _analogin, _storage,
_dataflash, _console, _gpio, _rcin,
_rcout, _scheduler) {}
void init(void* opts) const;
};
#endif // __AP_HAL_PX4_HAL_PX4_H__

View File

@ -0,0 +1 @@
include ../../../AP_Common/Arduino.mk

View File

@ -0,0 +1,25 @@
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_HAL_PX4.h>
const AP_HAL::HAL& hal = AP_HAL_PX4_Instance;
void loop (void) {
hal.console->println(".");
}
void setup (void) {
hal.console->println("Hello World");
}
extern "C" {
int main (void) {
hal.init(NULL);
setup();
for(;;) loop();
return 0;
}
}