mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
airspeed calibration: save offset only when full procedure succeed (#25412)
* feat: save offset only when full procedure succeed * feat: zero dpres off on all failures * feat: remove unnecessary param_save_default calls
This commit is contained in:
parent
8c4d998931
commit
6934bc908e
@ -178,10 +178,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
/* save */
|
||||
calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, 0);
|
||||
param_save_default(true);
|
||||
|
||||
feedback_calibration_failed(mavlink_log_pub);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
@ -201,6 +198,14 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
|
||||
}
|
||||
|
||||
if (hrt_elapsed_time(&calibration_started) > 90_s) {
|
||||
diff_pres_offset = 0.0f;
|
||||
|
||||
if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
|
||||
calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, 0);
|
||||
feedback_calibration_failed(mavlink_log_pub);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
@ -209,6 +214,14 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
|
||||
}
|
||||
|
||||
if (calibration_counter == maxcount) {
|
||||
diff_pres_offset = 0.0f;
|
||||
|
||||
if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
|
||||
calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, 0);
|
||||
feedback_calibration_failed(mavlink_log_pub);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user