AP_InertialSensor: prevent nullptr dereference in SITL
This commit is contained in:
parent
6144136b61
commit
3da156e358
@ -282,6 +282,9 @@ void AP_InertialSensor_SITL::timer_update(void)
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if (sitl == nullptr) {
|
||||
return;
|
||||
}
|
||||
if (now >= next_accel_sample) {
|
||||
if (((1U << accel_instance) & sitl->accel_fail_mask) == 0) {
|
||||
generate_accel();
|
||||
|
Loading…
Reference in New Issue
Block a user