Skip to content

Commit

Permalink
AP_HAL: SIMState: do a single nullptr check in SIMState servo sim
Browse files Browse the repository at this point in the history
mirrors if c1016ae
  • Loading branch information
peterbarker committed Jan 22, 2025
1 parent d64cf3e commit dbaca50
Showing 1 changed file with 8 additions and 4 deletions.
12 changes: 8 additions & 4 deletions libraries/AP_HAL/SIMState.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,6 +274,10 @@ void SIMState::fdm_input_local(void)
*/
void SIMState::_simulator_servos(struct sitl_input &input)
{
if (_sitl == nullptr) {
return;
}

// output at chosen framerate
uint32_t now = AP_HAL::micros();

Expand All @@ -288,7 +292,7 @@ void SIMState::_simulator_servos(struct sitl_input &input)
// give 5 seconds to calibrate airspeed sensor at 0 wind speed
if (wind_start_delay_micros == 0) {
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.
wind_speed = _sitl->wind_speed_active = (0.95f*_sitl->wind_speed_active) + (0.05f*_sitl->wind_speed);
wind_direction = _sitl->wind_direction_active = (0.95f*_sitl->wind_direction_active) + (0.05f*_sitl->wind_direction);
Expand Down Expand Up @@ -328,7 +332,7 @@ void SIMState::_simulator_servos(struct sitl_input &input)
}
}

if (_sitl != nullptr) {
{
// FETtec ESC simulation support. Input signals of 1000-2000
// are positive thrust, 0 to 1000 are negative thrust. Deeper
// changes required to support negative thrust - potentially
Expand Down Expand Up @@ -360,8 +364,8 @@ void SIMState::_simulator_servos(struct sitl_input &input)

float voltage = 0;
_current = 0;
if (_sitl != nullptr) {

{
if (_sitl->state.battery_voltage <= 0) {
} else {
// FDM provides voltage and current
Expand Down

0 comments on commit dbaca50

Please sign in to comment.