mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_HAL_Linux: Remove GPIO::analogPinToDigitalPin()
This commit is contained in:
parent
312e21dc2f
commit
1f7ee55211
@ -77,12 +77,6 @@ void GPIO_BBB::pinMode(uint8_t pin, uint8_t output)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int8_t GPIO_BBB::analogPinToDigitalPin(uint8_t pin)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
uint8_t GPIO_BBB::read(uint8_t pin) {
|
uint8_t GPIO_BBB::read(uint8_t pin) {
|
||||||
|
|
||||||
uint8_t bank = pin/32;
|
uint8_t bank = pin/32;
|
||||||
|
@ -122,7 +122,6 @@ public:
|
|||||||
GPIO_BBB();
|
GPIO_BBB();
|
||||||
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);
|
||||||
|
@ -91,11 +91,6 @@ void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int8_t GPIO_RPI::analogPinToDigitalPin(uint8_t pin)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t GPIO_RPI::read(uint8_t pin)
|
uint8_t GPIO_RPI::read(uint8_t pin)
|
||||||
{
|
{
|
||||||
uint32_t value = GPIO_GET(pin);
|
uint32_t value = GPIO_GET(pin);
|
||||||
|
@ -49,7 +49,6 @@ public:
|
|||||||
void init();
|
void init();
|
||||||
void pinMode(uint8_t pin, uint8_t output);
|
void pinMode(uint8_t pin, uint8_t output);
|
||||||
void pinMode(uint8_t pin, uint8_t output, uint8_t alt);
|
void pinMode(uint8_t pin, uint8_t output, uint8_t alt);
|
||||||
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);
|
||||||
|
@ -171,11 +171,6 @@ void GPIO_Sysfs::toggle(uint8_t vpin)
|
|||||||
write(vpin, !read(vpin));
|
write(vpin, !read(vpin));
|
||||||
}
|
}
|
||||||
|
|
||||||
int8_t GPIO_Sysfs::analogPinToDigitalPin(uint8_t vpin)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
AP_HAL::DigitalSource* GPIO_Sysfs::channel(uint16_t vpin)
|
AP_HAL::DigitalSource* GPIO_Sysfs::channel(uint16_t vpin)
|
||||||
{
|
{
|
||||||
assert_vpin(vpin, n_pins, nullptr);
|
assert_vpin(vpin, n_pins, nullptr);
|
||||||
|
@ -49,11 +49,6 @@ public:
|
|||||||
*/
|
*/
|
||||||
AP_HAL::DigitalSource *channel(uint16_t vpin) override;
|
AP_HAL::DigitalSource *channel(uint16_t vpin) override;
|
||||||
|
|
||||||
/*
|
|
||||||
* Currently this function always returns -1.
|
|
||||||
*/
|
|
||||||
int8_t analogPinToDigitalPin(uint8_t vpin) override;
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Currently this function always returns false.
|
* Currently this function always returns false.
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user