Browse Source

AP_HAL_AVR: sized ints in GPIO

master
Pat Hickey 12 years ago committed by Andrew Tridgell
parent
commit
ba07ae283f
  1. 5
      libraries/AP_HAL_AVR/GPIO.cpp
  2. 5
      libraries/AP_HAL_AVR/GPIO.h

5
libraries/AP_HAL_AVR/GPIO.cpp

@ -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;

5
libraries/AP_HAL_AVR/GPIO.h

@ -24,8 +24,9 @@ public: @@ -24,8 +24,9 @@ public:
void pinMode(uint8_t pin, uint8_t output);
uint8_t read(uint8_t pin);
void write(uint8_t pin, uint8_t value);
AP_HAL::DigitalSource* channel(int);
bool attach_interrupt(int interrupt_num, AP_HAL::Proc proc, int mode);
AP_HAL::DigitalSource* channel(uint16_t);
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc proc,
uint8_t mode);
/* private-ish: only to be used from the appropriate interrupt */
static AP_HAL::Proc _interrupt_6;
};

Loading…
Cancel
Save