|
|
|
@ -92,7 +92,8 @@ void AVRGPIO::write(uint8_t pin, uint8_t value) {
@@ -92,7 +92,8 @@ void AVRGPIO::write(uint8_t pin, uint8_t value) {
|
|
|
|
|
|
|
|
|
|
/* Implement GPIO Interrupt 6, used for MPU6000 data ready on APM2. */ |
|
|
|
|
bool AVRGPIO::attach_interrupt( |
|
|
|
|
int interrupt_num, AP_HAL::Proc proc, int mode) { |
|
|
|
|
uint8_t interrupt_num, AP_HAL::Proc proc, uint8_t mode) { |
|
|
|
|
if (!((mode == 0)||(mode == 1))) return false; |
|
|
|
|
if (interrupt_num == 6) { |
|
|
|
|
_interrupt_6 = proc; |
|
|
|
|
EICRB = (EICRB & ~((1 << ISC60) | (1 << ISC61))) | (mode << ISC60); |
|
|
|
@ -104,7 +105,7 @@ bool AVRGPIO::attach_interrupt(
@@ -104,7 +105,7 @@ bool AVRGPIO::attach_interrupt(
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
AP_HAL::DigitalSource* AVRGPIO::channel(int pin) { |
|
|
|
|
AP_HAL::DigitalSource* AVRGPIO::channel(uint16_t pin) { |
|
|
|
|
uint8_t bit = digitalPinToBitMask(pin); |
|
|
|
|
uint8_t port = digitalPinToPort(pin); |
|
|
|
|
if (port == NOT_A_PIN) return NULL; |
|
|
|
|