mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: add GPIO mask getter and GPIO virtual read
This commit is contained in:
parent
f2ade25c54
commit
4811d0458f
|
@ -1360,6 +1360,12 @@ void AP_IOMCU::set_GPIO_mask(uint8_t mask)
|
|||
trigger_event(IOEVENT_GPIO);
|
||||
}
|
||||
|
||||
// Get GPIO mask of channels setup for output
|
||||
uint8_t AP_IOMCU::get_GPIO_mask() const
|
||||
{
|
||||
return GPIO.channel_mask;
|
||||
}
|
||||
|
||||
// write to a output pin
|
||||
void AP_IOMCU::write_GPIO(uint8_t pin, bool value)
|
||||
{
|
||||
|
@ -1377,6 +1383,17 @@ void AP_IOMCU::write_GPIO(uint8_t pin, bool value)
|
|||
trigger_event(IOEVENT_GPIO);
|
||||
}
|
||||
|
||||
// Read the last output value send to the GPIO pin
|
||||
// This is not a real read of the actual pin
|
||||
// This allows callers to check for state change
|
||||
uint8_t AP_IOMCU::read_virtual_GPIO(uint8_t pin) const
|
||||
{
|
||||
if (!convert_pin_number(pin)) {
|
||||
return 0;
|
||||
}
|
||||
return (GPIO.output_mask & (1U << pin)) != 0;
|
||||
}
|
||||
|
||||
// toggle a output pin
|
||||
void AP_IOMCU::toggle_GPIO(uint8_t pin)
|
||||
{
|
||||
|
|
|
@ -157,9 +157,17 @@ public:
|
|||
// set GPIO mask of channels setup for output
|
||||
void set_GPIO_mask(uint8_t mask);
|
||||
|
||||
// Get GPIO mask of channels setup for output
|
||||
uint8_t get_GPIO_mask() const;
|
||||
|
||||
// write to a output pin
|
||||
void write_GPIO(uint8_t pin, bool value);
|
||||
|
||||
// Read the last output value send to the GPIO pin
|
||||
// This is not a real read of the actual pin
|
||||
// This allows callers to check for state change
|
||||
uint8_t read_virtual_GPIO(uint8_t pin) const;
|
||||
|
||||
// toggle a output pin
|
||||
void toggle_GPIO(uint8_t pin);
|
||||
|
||||
|
|
Loading…
Reference in New Issue