mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: fixed undefined behaviour in GPIO
This commit is contained in:
parent
2f7a8769c0
commit
f55aadfedf
|
@ -29,6 +29,9 @@ uint8_t GPIO::read(uint8_t pin)
|
|||
if (!_sitlState->_sitl) {
|
||||
return 0;
|
||||
}
|
||||
if (!valid_pin(pin)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// weight on wheels pin support
|
||||
if (pin == _sitlState->_sitl->wow_pin.get()) {
|
||||
|
@ -45,6 +48,9 @@ void GPIO::write(uint8_t pin, uint8_t value)
|
|||
return;
|
||||
}
|
||||
|
||||
if (!valid_pin(pin)) {
|
||||
return;
|
||||
}
|
||||
if (pin < 8) {
|
||||
if (!(pin_mode_is_write & (1U<<pin))) {
|
||||
// ignore setting of pull-up resistors
|
||||
|
|
Loading…
Reference in New Issue