mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 15:08:28 -04:00
73ccfaf2d7
* GPIO's complement to AnalogSource
103 lines
2.7 KiB
C++
103 lines
2.7 KiB
C++
|
|
#include <avr/interrupt.h>
|
|
|
|
#include "pins_arduino_mega.h"
|
|
|
|
#include "GPIO.h"
|
|
using namespace AP_HAL_AVR;
|
|
|
|
ArduinoGPIO* ArduinoDigitalSource::parent;
|
|
|
|
// 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.
|
|
|
|
#define analogInPinToBit(P) (P)
|
|
|
|
|
|
// 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.
|
|
//
|
|
// These perform slightly better as macros compared to inline functions
|
|
//
|
|
#define digitalPinToPort(P) ( pgm_read_byte( digital_pin_to_port_PGM + (P) ) )
|
|
#define digitalPinToBitMask(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM + (P) ) )
|
|
#define digitalPinToTimer(P) ( pgm_read_byte( digital_pin_to_timer_PGM + (P) ) )
|
|
#define analogInPinToBit(P) (P)
|
|
#define portOutputRegister(P) ( (volatile uint8_t *)( pgm_read_word( port_to_output_PGM + (P))) )
|
|
#define portInputRegister(P) ( (volatile uint8_t *)( pgm_read_word( port_to_input_PGM + (P))) )
|
|
#define portModeRegister(P) ( (volatile uint8_t *)( pgm_read_word( port_to_mode_PGM + (P))) )
|
|
|
|
|
|
void ArduinoGPIO::pinMode(uint8_t pin, uint8_t mode) {
|
|
uint8_t bit = digitalPinToBitMask(pin);
|
|
uint8_t port = digitalPinToPort(pin);
|
|
volatile uint8_t *reg;
|
|
|
|
if (port == NOT_A_PIN) return;
|
|
|
|
// JWS: can I let the optimizer do this?
|
|
reg = portModeRegister(port);
|
|
|
|
if (mode == GPIO_INPUT) {
|
|
uint8_t oldSREG = SREG;
|
|
cli();
|
|
*reg &= ~bit;
|
|
SREG = oldSREG;
|
|
} else {
|
|
uint8_t oldSREG = SREG;
|
|
cli();
|
|
*reg |= bit;
|
|
SREG = oldSREG;
|
|
}
|
|
}
|
|
|
|
uint8_t ArduinoGPIO::read(uint8_t pin) {
|
|
uint8_t bit = digitalPinToBitMask(pin);
|
|
uint8_t port = digitalPinToPort(pin);
|
|
|
|
if (port == NOT_A_PIN) return 0;
|
|
|
|
if (*portInputRegister(port) & bit) return 1;
|
|
return 0;
|
|
}
|
|
|
|
void ArduinoGPIO::write(uint8_t pin, uint8_t value) {
|
|
uint8_t bit = digitalPinToBitMask(pin);
|
|
uint8_t port = digitalPinToPort(pin);
|
|
volatile uint8_t *out;
|
|
|
|
if (port == NOT_A_PIN) return;
|
|
|
|
out = portOutputRegister(port);
|
|
|
|
uint8_t oldSREG = SREG;
|
|
cli();
|
|
|
|
if (value == 0) {
|
|
*out &= ~bit;
|
|
} else {
|
|
*out |= bit;
|
|
}
|
|
|
|
SREG = oldSREG;
|
|
}
|
|
|
|
AP_HAL::DigitalSource* ArduinoGPIO::channel(int n) {
|
|
if (ArduinoDigitalSource::parent == NULL) {
|
|
ArduinoDigitalSource::parent = this;
|
|
}
|
|
return new ArduinoDigitalSource(n);
|
|
}
|
|
|
|
void ArduinoDigitalSource::mode(uint8_t output) {
|
|
parent->pinMode(_pin, output);
|
|
}
|
|
|
|
uint8_t ArduinoDigitalSource::read() {
|
|
return parent->read(_pin);
|
|
}
|
|
|
|
void ArduinoDigitalSource::write(uint8_t value) {
|
|
parent->write(_pin, value);
|
|
}
|