AP_HAL_AVR: Stub implementations of AP_HAL_AVR concrete classes

This commit is contained in:
Pat Hickey 2012-08-20 11:38:09 -07:00 committed by Andrew Tridgell
parent dc03b1190f
commit 00920b0483
14 changed files with 291 additions and 0 deletions

View File

@ -0,0 +1,65 @@
#include <AP_HAL.h>
#include "AP_HAL_AVR.h"
/* Include AVR-specific implementations of the HAL classes */
#include "UARTDriver.h"
#include "I2CDriver.h"
#include "SPIDriver.h"
#include "AnalogIn.h"
#include "Storage.h"
#include "Log.h"
#include "Console.h"
#include "GPIO.h"
#include "PPMInput.h"
#include "PWMOutput.h"
using namespace AP_HAL;
static AVRUARTDriver avrUart0Driver( 0 );
static AVRUARTDriver avrUart1Driver( 1 );
static AVRUARTDriver avrUart2Driver( 2 );
static AVRUARTDriver avrUart3Driver( 3 );
static AVRI2CDriver avrI2CDriver;
static ArduinoSPIDriver arduinoSPIDriver;
static ArduinoAnalogIn arduinoAnalogIn;
static AVREEPROMStorage avrEEPROMStorage;
static DataFlashAPM1Log apm1DataFlashLog;
static DataFlashAPM2Log apm2DataFlashLog;
static AVRUARTConsole avrUartConsole(&avrUart0Driver);
static ArduinoGPIO arduinoGPIO;
static APM1PPMInput apm1PPMInput;
static APM2PPMInput apm2PPMInput;
static APM1PWMOutput apm1PWMOutput;
static APM2PWMOutput apm2PWMOutput;
const HAL AP_HAL_AVR_APM1(
&avrUart0Driver,
&avrUart1Driver,
&avrUart2Driver,
&avrUart3Driver,
&avrI2CDriver,
&arduinoSPIDriver,
&arduinoAnalogIn,
&avrEEPROMStorage,
&apm1DataFlashLog,
&avrUartConsole,
&arduinoGPIO,
&apm1PPMInput,
&apm1PWMOutput );
const HAL AP_HAL_AVR_APM2(
&avrUart0Driver,
&avrUart1Driver,
&avrUart2Driver,
&avrUart3Driver,
&avrI2CDriver,
&arduinoSPIDriver,
&arduinoAnalogIn,
&avrEEPROMStorage,
&apm2DataFlashLog,
&avrUartConsole,
&arduinoGPIO,
&apm2PPMInput,
&apm2PWMOutput );

View File

@ -0,0 +1,11 @@
#ifndef __AP_HAL_AVR_H__
#define __AP_HAL_AVR_H__
#include <AP_HAL.h>
extern const AP_HAL::HAL AP_HAL_AVR_APM1;
extern const AP_HAL::HAL AP_HAL_AVR_APM2;
#endif // __AP_HAL_AVR_H__

View File

@ -0,0 +1,16 @@
#ifndef __AP_HAL_AVR_ANALOG_IN_H__
#define __AP_HAL_AVR_ANALOG_IN_H__
#include <AP_HAL.h>
class AP_HAL::ArduinoAnalogIn : public AP_HAL::AnalogIn {
public:
ArduinoAnalogIn() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
#endif // __AP_HAL_AVR_ANALOG_IN_H__

View File

@ -0,0 +1,19 @@
#ifndef __AP_HAL_AVR_CONSOLE_H__
#define __AP_HAL_AVR_CONSOLE_H__
#include <AP_HAL.h>
#include "UARTDriver.h"
class AP_HAL::AVRUARTConsole : public AP_HAL::Console {
public:
AVRUARTConsole( AVRUARTDriver* driver ) : _driver(driver), _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
const AVRUARTDriver* _driver;
int _init;
};
#endif // __AP_HAL_AVR_CONSOLE_H__

View File

@ -0,0 +1,16 @@
#ifndef __AP_HAL_AVR_GPIO_H__
#define __AP_HAL_AVR_GPIO_H__
#include <AP_HAL.h>
class AP_HAL::ArduinoGPIO : public AP_HAL::GPIO {
public:
ArduinoGPIO() : _init(0) {}
void init(int machtnicht) { _init = machtnicht; }
private:
int _init;
};
#endif // __AP_HAL_AVR_GPIO_H__

View File

@ -0,0 +1,16 @@
#ifndef __AP_HAL_AVR_I2C_DRIVER_H__
#define __AP_HAL_AVR_I2C_DRIVER_H__
#include <AP_HAL.h>
class AP_HAL::AVRI2CDriver : public AP_HAL::I2CDriver {
public:
AVRI2CDriver(): _init(0) {}
void init() { _init = 1; }
private:
int _init;
};
#endif // __AP_HAL_AVR_I2C_DRIVER_H__

View File

@ -0,0 +1,24 @@
#ifndef __AP_HAL_AVR_LOG_H__
#define __AP_HAL_AVR_LOG_H__
#include <AP_HAL.h>
class AP_HAL::DataFlashAPM1Log : public AP_HAL::Log {
public:
DataFlashAPM1Log() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
class AP_HAL::DataFlashAPM2Log : public AP_HAL::Log {
public:
DataFlashAPM2Log() : _init(0) {}
void init(int machtnicht) { _init = 2; }
private:
int _init;
};
#endif // __AP_HAL_AVR_LOG_H__

View File

@ -0,0 +1,24 @@
#ifndef __AP_HAL_AVR_PPM_INPUT_H__
#define __AP_HAL_AVR_PPM_INPUT_H__
#include <AP_HAL.h>
class AP_HAL::APM1PPMInput : public AP_HAL::PPMInput {
public:
APM1PPMInput() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
class AP_HAL::APM2PPMInput : public AP_HAL::PPMInput {
public:
APM2PPMInput() : _init(0) {}
void init(int machtnicht) { _init = 2; }
private:
int _init;
};
#endif // __AP_HAL_AVR_PPM_INPUT_H__

View File

@ -0,0 +1,24 @@
#ifndef __AP_HAL_AVR_PWM_OUTPUT_H__
#define __AP_HAL_AVR_PWM_OUTPUT_H__
#include <AP_HAL.h>
class AP_HAL::APM1PWMOutput : public AP_HAL::PWMOutput {
public:
APM1PWMOutput() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
class AP_HAL::APM2PWMOutput : public AP_HAL::PWMOutput {
public:
APM2PWMOutput() : _init(0) {}
void init(int machtnicht) { _init = 2; }
private:
int _init;
};
#endif // __AP_HAL_AVR_PWM_OUTPUT_H__

View File

@ -0,0 +1,16 @@
#ifndef __AP_HAL_ARDUINO_SPI_DRIVER_H__
#define __AP_HAL_ARDUINO_SPI_DRIVER_H__
#include <AP_HAL.h>
class AP_HAL::ArduinoSPIDriver : public AP_HAL::SPIDriver {
public:
ArduinoSPIDriver() : _init(0) {}
void init() { _init = 1; }
private:
int _init;
};
#endif // __AP_HAL_ARDUINO_SPI_DRIVER_H__

View File

@ -0,0 +1,16 @@
#ifndef __AP_HAL_AVR_STORAGE_H__
#define __AP_HAL_AVR_STORAGE_H__
#include <AP_HAL.h>
class AP_HAL::AVREEPROMStorage : public AP_HAL::Storage {
public:
AVREEPROMStorage() : _init(0) {}
void init(int machtnicht) { _init = 1; }
private:
int _init;
};
#endif // __AP_HAL_AVR_STORAGE_H__

View File

@ -0,0 +1,26 @@
#ifndef __AP_HAL_AVR_UART_DRIVER_H__
#define __AP_HAL_AVR_UART_DRIVER_H__
#include <stdint.h>
#include <AP_HAL.h>
/**
* AVRUARTDriver is an implementation of UARTDriver for the AVR.
* It will be a thin wrapper on FastSerial.
*/
class AP_HAL::AVRUARTDriver : public AP_HAL::UARTDriver {
public:
AVRUARTDriver(int num) : _num(num) {}
void init(uint16_t baud) { _baud = baud; }
/* XXX stub implementation! */
private:
int _num;
uint16_t _baud;
};
#endif // __AP_HAL_AVR_UART_DRIVER_H__

View File

@ -0,0 +1,17 @@
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
const AP_HAL::HAL& hal1 = AP_HAL_AVR_APM1;
const AP_HAL::HAL& hal2 = AP_HAL_AVR_APM2;
void loop (void) {
}
void setup (void) {
hal1.uart0->init(9600);
hal2.uart0->init(9600);
}

View File

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