mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: use a 16-bit mask for GPIO out
This allows Relay pins to be represented (typically pin 13)
This commit is contained in:
parent
c7327acef7
commit
1eecf07e68
@ -21,8 +21,8 @@ uint8_t GPIO::read(uint8_t pin)
|
|||||||
if (!_sitlState->_sitl) {
|
if (!_sitlState->_sitl) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
uint8_t mask = static_cast<uint8_t>(_sitlState->_sitl->pin_mask.get());
|
uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
|
||||||
return static_cast<uint8_t>((mask & (1U << pin)) ? 1 : 0);
|
return static_cast<uint16_t>((mask & (1U << pin)) ? 1 : 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void GPIO::write(uint8_t pin, uint8_t value)
|
void GPIO::write(uint8_t pin, uint8_t value)
|
||||||
@ -30,8 +30,8 @@ void GPIO::write(uint8_t pin, uint8_t value)
|
|||||||
if (!_sitlState->_sitl) {
|
if (!_sitlState->_sitl) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint8_t mask = static_cast<uint8_t>(_sitlState->_sitl->pin_mask.get());
|
uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
|
||||||
uint8_t new_mask = mask;
|
uint16_t new_mask = mask;
|
||||||
if (value) {
|
if (value) {
|
||||||
new_mask |= (1U << pin);
|
new_mask |= (1U << pin);
|
||||||
} else {
|
} else {
|
||||||
@ -49,7 +49,7 @@ void GPIO::toggle(uint8_t pin)
|
|||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
|
AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
|
||||||
if (n < 8) { // (ie. sizeof(pin_mask)*8)
|
if (n < 16) { // (ie. sizeof(pin_mask)*8)
|
||||||
return new DigitalSource(static_cast<uint8_t>(n));
|
return new DigitalSource(static_cast<uint8_t>(n));
|
||||||
} else {
|
} else {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
Loading…
Reference in New Issue
Block a user