mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_InertialSensor: fix segfault
This commit is contained in:
parent
83d5a6664a
commit
bae16a61e2
@ -132,7 +132,7 @@ void AP_InertialSensor_Backend::_publish_accel(uint8_t instance, const Vector3f
|
||||
_imu._delta_velocity_valid[instance] = true;
|
||||
|
||||
|
||||
if (_imu._accel_calibrator[instance].get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
|
||||
if (_imu._accel_calibrator != NULL && _imu._accel_calibrator[instance].get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
|
||||
Vector3f cal_sample = _imu._delta_velocity[instance];
|
||||
|
||||
//remove rotation
|
||||
|
Loading…
Reference in New Issue
Block a user