AP_HAL_SITL: remove redundant nullptr checks on _sitl member

nullptr is checked for at the top of this function, no need to check it after that
This commit is contained in:
Peter Barker 2025-01-09 16:15:20 +11:00 committed by Peter Barker
parent 7c2d329d75
commit beb3dd1519

View File

@ -327,7 +327,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
// give 5 seconds to calibrate airspeed sensor at 0 wind speed // give 5 seconds to calibrate airspeed sensor at 0 wind speed
if (wind_start_delay_micros == 0) { if (wind_start_delay_micros == 0) {
wind_start_delay_micros = now; wind_start_delay_micros = now;
} else if (_sitl && (now - wind_start_delay_micros) > 5000000 ) { } else if ((now - wind_start_delay_micros) > 5000000 ) {
// The EKF does not like step inputs so this LPF keeps it happy. // The EKF does not like step inputs so this LPF keeps it happy.
uint32_t dt_us = now - last_wind_update_us; uint32_t dt_us = now - last_wind_update_us;
if (dt_us > 1000) { if (dt_us > 1000) {
@ -379,27 +379,22 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
} }
} }
if (_sitl != nullptr) { // FETtec ESC simulation support. Input signals of 1000-2000
// FETtec ESC simulation support. Input signals of 1000-2000 // are positive thrust, 0 to 1000 are negative thrust. Deeper
// are positive thrust, 0 to 1000 are negative thrust. Deeper // changes required to support negative thrust - potentially
// changes required to support negative thrust - potentially // adding a field to input.
// adding a field to input. if (_sitl->fetteconewireesc_sim.enabled()) {
if (_sitl != nullptr) { _sitl->fetteconewireesc_sim.update_sitl_input_pwm(input);
if (_sitl->fetteconewireesc_sim.enabled()) { for (uint8_t i=0; i<ARRAY_SIZE(input.servos); i++) {
_sitl->fetteconewireesc_sim.update_sitl_input_pwm(input); if (input.servos[i] != 0 && input.servos[i] < 1000) {
for (uint8_t i=0; i<ARRAY_SIZE(input.servos); i++) { AP_HAL::panic("Bad input servo value (%u)", input.servos[i]);
if (input.servos[i] != 0 && input.servos[i] < 1000) {
AP_HAL::panic("Bad input servo value (%u)", input.servos[i]);
}
}
} }
} }
} }
float engine_mul = _sitl?_sitl->engine_mul.get():1; const float engine_mul = _sitl->engine_mul.get();
uint32_t engine_fail = _sitl?_sitl->engine_fail.get():0; const uint32_t engine_fail = _sitl->engine_fail.get();
float throttle = 0.0f;
// apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter // apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter
for (uint8_t i=0; i<ARRAY_SIZE(input.servos); i++) { for (uint8_t i=0; i<ARRAY_SIZE(input.servos); i++) {
if (engine_fail & (1<<i)) { if (engine_fail & (1<<i)) {
@ -411,6 +406,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
} }
} }
float throttle = 0.0f;
if (_vehicle == ArduPlane) { if (_vehicle == ArduPlane) {
float forward_throttle = constrain_float((input.servos[2] - 1000) / 1000.0f, 0.0f, 1.0f); float forward_throttle = constrain_float((input.servos[2] - 1000) / 1000.0f, 0.0f, 1.0f);
// do a little quadplane dance // do a little quadplane dance
@ -459,9 +455,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input)
throttle /= running_motors; throttle /= running_motors;
} }
} }
if (_sitl) { _sitl->throttle = throttle;
_sitl->throttle = throttle;
}
update_voltage_current(input, throttle); update_voltage_current(input, throttle);
} }