mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed:add option to report cal offset to GCS
This commit is contained in:
parent
44891ce570
commit
06efeb20cd
|
@ -125,9 +125,9 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
|
||||||
#ifndef HAL_BUILD_AP_PERIPH
|
#ifndef HAL_BUILD_AP_PERIPH
|
||||||
// @Param: _OPTIONS
|
// @Param: _OPTIONS
|
||||||
// @DisplayName: Airspeed options bitmask
|
// @DisplayName: Airspeed options bitmask
|
||||||
// @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction, 3:Check that the airspeed is statistically consistent with the navigation EKF vehicle and wind velocity estimates using EKF3 (requires AHRS_EKF_TYPE = 3)
|
// @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction, 3:Check that the airspeed is statistically consistent with the navigation EKF vehicle and wind velocity estimates using EKF3 (requires AHRS_EKF_TYPE = 3), 4:Report cal offset to GCS
|
||||||
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
|
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
|
||||||
// @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection, 3:UseEkf3Consistency
|
// @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection, 3:UseEkf3Consistency, 4:ReportOffset
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT),
|
AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT),
|
||||||
|
|
||||||
|
@ -557,7 +557,6 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %u unhealthy", i + 1);
|
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %u unhealthy", i + 1);
|
||||||
calibration_state[i] = CalibrationState::FAILED;
|
calibration_state[i] = CalibrationState::FAILED;
|
||||||
} else {
|
} else {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1);
|
|
||||||
float calibrated_offset = state[i].cal.sum / state[i].cal.count;
|
float calibrated_offset = state[i].cal.sum / state[i].cal.count;
|
||||||
// check if new offset differs too greatly from last calibration, indicating pitot uncovered in wind
|
// check if new offset differs too greatly from last calibration, indicating pitot uncovered in wind
|
||||||
if (fixed_wing_parameters != nullptr) {
|
if (fixed_wing_parameters != nullptr) {
|
||||||
|
@ -570,6 +569,11 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
|
||||||
}
|
}
|
||||||
param[i].offset.set_and_save(calibrated_offset);
|
param[i].offset.set_and_save(calibrated_offset);
|
||||||
calibration_state[i] = CalibrationState::SUCCESS;
|
calibration_state[i] = CalibrationState::SUCCESS;
|
||||||
|
if (_options & AP_Airspeed::OptionsMask::REPORT_OFFSET ){
|
||||||
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated, offset = %4.0f", i + 1, calibrated_offset);
|
||||||
|
} else {
|
||||||
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
state[i].cal.start_ms = 0;
|
state[i].cal.start_ms = 0;
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -171,6 +171,7 @@ public:
|
||||||
ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE = (1<<1), // If set then automatically enable the airspeed sensor use when healthy again.
|
ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE = (1<<1), // If set then automatically enable the airspeed sensor use when healthy again.
|
||||||
DISABLE_VOLTAGE_CORRECTION = (1<<2),
|
DISABLE_VOLTAGE_CORRECTION = (1<<2),
|
||||||
USE_EKF_CONSISTENCY = (1<<3),
|
USE_EKF_CONSISTENCY = (1<<3),
|
||||||
|
REPORT_OFFSET = (1<<4), // report offset cal to GCS
|
||||||
};
|
};
|
||||||
|
|
||||||
enum airspeed_type {
|
enum airspeed_type {
|
||||||
|
|
Loading…
Reference in New Issue