mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 16:37:34 +08:00
Airspeed calibration: Ensure that the calibration state is stored correctly
This is necessary due to sensors that are so accurate that they have no offset at all.
This commit is contained in:
@@ -175,6 +175,14 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
|
||||
px4_close(fd_scale);
|
||||
}
|
||||
|
||||
// Prevent a completely zero param
|
||||
// since this is used to detect a missing calibration
|
||||
// This value is numerically down in the noise and has
|
||||
// no effect on the sensor performance.
|
||||
if (fabsf(diff_pres_offset) < 0.00000001f) {
|
||||
diff_pres_offset = 0.00000001f;
|
||||
}
|
||||
|
||||
if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
|
||||
calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG, 1);
|
||||
goto error_return;
|
||||
|
||||
Reference in New Issue
Block a user