mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_Empty: match plane 3.9.0
This commit is contained in:
parent
388cbf5cbd
commit
ff3322a526
@ -12,12 +12,6 @@ void GPIO::init()
|
|||||||
void GPIO::pinMode(uint8_t pin, uint8_t output)
|
void GPIO::pinMode(uint8_t pin, uint8_t output)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
int8_t GPIO::analogPinToDigitalPin(uint8_t pin)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
uint8_t GPIO::read(uint8_t pin) {
|
uint8_t GPIO::read(uint8_t pin) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -7,7 +7,6 @@ public:
|
|||||||
GPIO();
|
GPIO();
|
||||||
void init();
|
void init();
|
||||||
void pinMode(uint8_t pin, uint8_t output);
|
void pinMode(uint8_t pin, uint8_t output);
|
||||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
|
||||||
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);
|
||||||
void toggle(uint8_t pin);
|
void toggle(uint8_t pin);
|
||||||
|
Loading…
Reference in New Issue
Block a user