2012-08-20 15:38:09 -03:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_AVR_GPIO_H__
|
|
|
|
#define __AP_HAL_AVR_GPIO_H__
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
2012-08-21 18:11:24 -03:00
|
|
|
#include "AP_HAL_AVR_Namespace.h"
|
2012-08-20 15:38:09 -03:00
|
|
|
|
2012-11-28 21:53:49 -04:00
|
|
|
class AP_HAL_AVR::AVRDigitalSource : public AP_HAL::DigitalSource {
|
2012-10-02 01:55:52 -03:00
|
|
|
public:
|
2012-11-28 21:53:49 -04:00
|
|
|
AVRDigitalSource(uint8_t bit, uint8_t port) : _bit(bit), _port(port) {}
|
2012-10-02 01:55:52 -03:00
|
|
|
void mode(uint8_t output);
|
|
|
|
uint8_t read();
|
|
|
|
void write(uint8_t value);
|
|
|
|
|
|
|
|
private:
|
2012-11-28 18:52:13 -04:00
|
|
|
const uint8_t _bit;
|
|
|
|
const uint8_t _port;
|
2012-10-02 01:55:52 -03:00
|
|
|
};
|
|
|
|
|
2012-11-28 21:53:49 -04:00
|
|
|
class AP_HAL_AVR::AVRGPIO : public AP_HAL::GPIO {
|
2012-08-20 15:38:09 -03:00
|
|
|
public:
|
2012-11-28 21:53:49 -04:00
|
|
|
AVRGPIO() {}
|
2012-08-23 19:22:24 -03:00
|
|
|
void init() {}
|
|
|
|
void pinMode(uint8_t pin, uint8_t output);
|
2013-03-21 22:31:14 -03:00
|
|
|
int8_t analogPinToDigitalPin(uint8_t pin);
|
2012-08-23 19:22:24 -03:00
|
|
|
uint8_t read(uint8_t pin);
|
|
|
|
void write(uint8_t pin, uint8_t value);
|
2012-12-06 14:45:53 -04:00
|
|
|
AP_HAL::DigitalSource* channel(uint16_t);
|
|
|
|
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc proc,
|
|
|
|
uint8_t mode);
|
2012-10-11 21:25:30 -03:00
|
|
|
/* private-ish: only to be used from the appropriate interrupt */
|
|
|
|
static AP_HAL::Proc _interrupt_6;
|
2012-08-20 15:38:09 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_AVR_GPIO_H__
|
|
|
|
|