mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL: added gpio->analogPinToDigitalPin() API
This commit is contained in:
parent
a88ac50e6c
commit
eb6c66af7e
@ -27,6 +27,8 @@ public:
|
||||
virtual void pinMode(uint8_t pin, uint8_t output) = 0;
|
||||
virtual uint8_t read(uint8_t pin) = 0;
|
||||
virtual void write(uint8_t pin, uint8_t value) = 0;
|
||||
virtual int8_t analogPinToDigitalPin(uint8_t pin) = 0;
|
||||
|
||||
/* Alternative interface: */
|
||||
virtual AP_HAL::DigitalSource* channel(uint16_t n) = 0;
|
||||
|
||||
|
@ -61,6 +61,11 @@ void AVRGPIO::pinMode(uint8_t pin, uint8_t mode) {
|
||||
}
|
||||
}
|
||||
|
||||
int8_t AVRGPIO::analogPinToDigitalPin(uint8_t pin)
|
||||
{
|
||||
return analogInputToDigitalPin(pin);
|
||||
}
|
||||
|
||||
uint8_t AVRGPIO::read(uint8_t pin) {
|
||||
uint8_t bit = digitalPinToBitMask(pin);
|
||||
uint8_t port = digitalPinToPort(pin);
|
||||
|
@ -22,6 +22,7 @@ public:
|
||||
AVRGPIO() {}
|
||||
void init() {}
|
||||
void pinMode(uint8_t pin, uint8_t output);
|
||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||
uint8_t read(uint8_t pin);
|
||||
void write(uint8_t pin, uint8_t value);
|
||||
AP_HAL::DigitalSource* channel(uint16_t);
|
||||
|
@ -12,6 +12,11 @@ void EmptyGPIO::init()
|
||||
void EmptyGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
{}
|
||||
|
||||
int8_t EmptyGPIO::analogPinToDigitalPin(uint8_t pin)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
uint8_t EmptyGPIO::read(uint8_t pin) {
|
||||
return 0;
|
||||
|
@ -9,6 +9,7 @@ public:
|
||||
EmptyGPIO();
|
||||
void init();
|
||||
void pinMode(uint8_t pin, uint8_t output);
|
||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||
uint8_t read(uint8_t pin);
|
||||
void write(uint8_t pin, uint8_t value);
|
||||
|
||||
|
@ -15,6 +15,11 @@ void SMACCMGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
{
|
||||
}
|
||||
|
||||
int8_t SMACCMGPIO::analogPinToDigitalPin(uint8_t pin)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint8_t SMACCMGPIO::read(uint8_t pin)
|
||||
{
|
||||
return 0;
|
||||
|
@ -9,6 +9,7 @@ public:
|
||||
SMACCMGPIO();
|
||||
void init();
|
||||
void pinMode(uint8_t pin, uint8_t output);
|
||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||
uint8_t read(uint8_t pin);
|
||||
void write(uint8_t pin, uint8_t value);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user