mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_HAL_AVR: implement GPIO::attach_interrupt just for interrupt 6
This commit is contained in:
parent
7480707f9e
commit
11bf533c57
@ -1,13 +1,23 @@
|
|||||||
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
#include <avr/io.h>
|
||||||
|
|
||||||
#include "pins_arduino_mega.h"
|
#include "pins_arduino_mega.h"
|
||||||
|
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
using namespace AP_HAL_AVR;
|
using namespace AP_HAL_AVR;
|
||||||
|
|
||||||
|
|
||||||
ArduinoGPIO* ArduinoDigitalSource::parent;
|
ArduinoGPIO* ArduinoDigitalSource::parent;
|
||||||
|
|
||||||
|
AP_HAL::Proc ArduinoGPIO::_interrupt_6 = NULL;
|
||||||
|
|
||||||
|
SIGNAL(INT6_vect) {
|
||||||
|
if (ArduinoGPIO::_interrupt_6) {
|
||||||
|
ArduinoGPIO::_interrupt_6();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Get the bit location within the hardware port of the given virtual pin.
|
// Get the bit location within the hardware port of the given virtual pin.
|
||||||
// This comes from the pins_*.c file for the active board configuration.
|
// This comes from the pins_*.c file for the active board configuration.
|
||||||
|
|
||||||
@ -82,6 +92,20 @@ void ArduinoGPIO::write(uint8_t pin, uint8_t value) {
|
|||||||
SREG = oldSREG;
|
SREG = oldSREG;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* Implement GPIO Interrupt 6, used for MPU6000 data ready on APM2. */
|
||||||
|
bool ArduinoGPIO::attach_interrupt(
|
||||||
|
int interrupt_num, AP_HAL::Proc proc, int mode) {
|
||||||
|
if (interrupt_num == 6) {
|
||||||
|
_interrupt_6 = proc;
|
||||||
|
EICRB = (EICRB & ~((1 << ISC60) | (1 << ISC61))) | (mode << ISC60);
|
||||||
|
EIMSK |= (1 << INT6);
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
AP_HAL::DigitalSource* ArduinoGPIO::channel(int n) {
|
AP_HAL::DigitalSource* ArduinoGPIO::channel(int n) {
|
||||||
if (ArduinoDigitalSource::parent == NULL) {
|
if (ArduinoDigitalSource::parent == NULL) {
|
||||||
ArduinoDigitalSource::parent = this;
|
ArduinoDigitalSource::parent = this;
|
||||||
@ -100,3 +124,5 @@ uint8_t ArduinoDigitalSource::read() {
|
|||||||
void ArduinoDigitalSource::write(uint8_t value) {
|
void ArduinoDigitalSource::write(uint8_t value) {
|
||||||
parent->write(_pin, value);
|
parent->write(_pin, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -25,6 +25,9 @@ public:
|
|||||||
uint8_t read(uint8_t pin);
|
uint8_t read(uint8_t pin);
|
||||||
void write(uint8_t pin, uint8_t value);
|
void write(uint8_t pin, uint8_t value);
|
||||||
AP_HAL::DigitalSource* channel(int);
|
AP_HAL::DigitalSource* channel(int);
|
||||||
|
bool attach_interrupt(int interrupt_num, AP_HAL::Proc proc, int mode);
|
||||||
|
/* private-ish: only to be used from the appropriate interrupt */
|
||||||
|
static AP_HAL::Proc _interrupt_6;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_AVR_GPIO_H__
|
#endif // __AP_HAL_AVR_GPIO_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user