mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: stop setting of pull-up resistors affecting SIM_PIN_MASK
This commit is contained in:
parent
8885aa255d
commit
c40b5490f4
@ -11,7 +11,16 @@ void GPIO::init()
|
|||||||
{}
|
{}
|
||||||
|
|
||||||
void GPIO::pinMode(uint8_t pin, uint8_t output)
|
void GPIO::pinMode(uint8_t pin, uint8_t output)
|
||||||
{}
|
{
|
||||||
|
if (pin > 7) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (output) {
|
||||||
|
pin_mode_is_write |= (1U<<pin);
|
||||||
|
} else {
|
||||||
|
pin_mode_is_write &= ~(1U<<pin);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
uint8_t GPIO::read(uint8_t pin)
|
uint8_t GPIO::read(uint8_t pin)
|
||||||
{
|
{
|
||||||
@ -33,6 +42,13 @@ void GPIO::write(uint8_t pin, uint8_t value)
|
|||||||
if (!_sitlState->_sitl) {
|
if (!_sitlState->_sitl) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (pin < 8) {
|
||||||
|
if (!(pin_mode_is_write & (1U<<pin))) {
|
||||||
|
// ignore setting of pull-up resistors
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
|
uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
|
||||||
uint16_t new_mask = mask;
|
uint16_t new_mask = mask;
|
||||||
|
|
||||||
|
@ -19,6 +19,8 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
SITL_State *_sitlState;
|
SITL_State *_sitlState;
|
||||||
|
|
||||||
|
uint8_t pin_mode_is_write;
|
||||||
};
|
};
|
||||||
|
|
||||||
class HALSITL::DigitalSource : public AP_HAL::DigitalSource {
|
class HALSITL::DigitalSource : public AP_HAL::DigitalSource {
|
||||||
|
Loading…
Reference in New Issue
Block a user