GPIO: optimized read, write, and mode for DigitalSource objects
This commit is contained in:
parent
054f35e33d
commit
b7c4cc20ac
@ -8,8 +8,6 @@
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
|
||||
ArduinoGPIO* ArduinoDigitalSource::parent;
|
||||
|
||||
AP_HAL::Proc ArduinoGPIO::_interrupt_6 = NULL;
|
||||
|
||||
SIGNAL(INT6_vect) {
|
||||
@ -106,23 +104,56 @@ bool ArduinoGPIO::attach_interrupt(
|
||||
}
|
||||
|
||||
|
||||
AP_HAL::DigitalSource* ArduinoGPIO::channel(int n) {
|
||||
if (ArduinoDigitalSource::parent == NULL) {
|
||||
ArduinoDigitalSource::parent = this;
|
||||
}
|
||||
return new ArduinoDigitalSource(n);
|
||||
AP_HAL::DigitalSource* ArduinoGPIO::channel(int pin) {
|
||||
uint8_t bit = digitalPinToBitMask(pin);
|
||||
uint8_t port = digitalPinToPort(pin);
|
||||
if (port == NOT_A_PIN) return NULL;
|
||||
return new ArduinoDigitalSource(bit, port);
|
||||
}
|
||||
|
||||
void ArduinoDigitalSource::mode(uint8_t output) {
|
||||
parent->pinMode(_pin, output);
|
||||
const uint8_t bit = _bit;
|
||||
const uint8_t port = _port;
|
||||
|
||||
volatile uint8_t* reg;
|
||||
reg = portModeRegister(port);
|
||||
|
||||
if (output == GPIO_INPUT) {
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
*reg &= ~bit;
|
||||
SREG = oldSREG;
|
||||
} else {
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
*reg |= bit;
|
||||
SREG = oldSREG;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t ArduinoDigitalSource::read() {
|
||||
return parent->read(_pin);
|
||||
const uint8_t bit = _bit;
|
||||
const uint8_t port = _port;
|
||||
if (*portInputRegister(port) & bit) return 1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
void ArduinoDigitalSource::write(uint8_t value) {
|
||||
parent->write(_pin, value);
|
||||
const uint8_t bit = _bit;
|
||||
const uint8_t port = _port;
|
||||
volatile uint8_t* out;
|
||||
out = portOutputRegister(port);
|
||||
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
|
||||
if (value == 0) {
|
||||
*out &= ~bit;
|
||||
} else {
|
||||
*out |= bit;
|
||||
}
|
||||
|
||||
SREG = oldSREG;
|
||||
}
|
||||
|
||||
|
||||
|
@ -7,14 +7,14 @@
|
||||
|
||||
class AP_HAL_AVR::ArduinoDigitalSource : public AP_HAL::DigitalSource {
|
||||
public:
|
||||
ArduinoDigitalSource(int pin) : _pin(pin) {}
|
||||
ArduinoDigitalSource(uint8_t bit, uint8_t port) : _bit(bit), _port(port) {}
|
||||
void mode(uint8_t output);
|
||||
uint8_t read();
|
||||
void write(uint8_t value);
|
||||
|
||||
static ArduinoGPIO* parent;
|
||||
private:
|
||||
int _pin;
|
||||
const uint8_t _bit;
|
||||
const uint8_t _port;
|
||||
};
|
||||
|
||||
class AP_HAL_AVR::ArduinoGPIO : public AP_HAL::GPIO {
|
||||
|
@ -6,16 +6,41 @@
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
|
||||
AP_HAL::DigitalSource *a_led;
|
||||
AP_HAL::DigitalSource *b_led;
|
||||
AP_HAL::DigitalSource *c_led;
|
||||
|
||||
void loop (void) {
|
||||
hal.scheduler->delay(1000);
|
||||
hal.gpio->write(13, 1);
|
||||
|
||||
a_led->write(1);
|
||||
b_led->write(0);
|
||||
c_led->write(1);
|
||||
|
||||
hal.scheduler->delay(1000);
|
||||
hal.gpio->write(13, 0);
|
||||
|
||||
a_led->write(0);
|
||||
b_led->write(1);
|
||||
c_led->write(0);
|
||||
}
|
||||
|
||||
void setup (void) {
|
||||
hal.gpio->pinMode(13, GPIO_OUTPUT);
|
||||
hal.gpio->write(13, 0);
|
||||
|
||||
a_led = hal.gpio->channel(27);
|
||||
b_led = hal.gpio->channel(26);
|
||||
c_led = hal.gpio->channel(25);
|
||||
|
||||
a_led->mode(GPIO_OUTPUT);
|
||||
b_led->mode(GPIO_OUTPUT);
|
||||
c_led->mode(GPIO_OUTPUT);
|
||||
|
||||
a_led->write(0);
|
||||
b_led->write(0);
|
||||
c_led->write(0);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user