forked from Archive/PX4-Autopilot
airspeed_calibration: stop talking about Pa and and hashtags
This commit is contained in:
parent
40fe9ab969
commit
c6fb75f66f
|
@ -232,6 +232,8 @@ MEASAirspeed::collect()
|
||||||
* tubes are connected backwards */
|
* tubes are connected backwards */
|
||||||
float diff_press_pa = diff_press_pa_raw;
|
float diff_press_pa = diff_press_pa_raw;
|
||||||
|
|
||||||
|
warnx("diff preasure: %.4f", (double)diff_press_pa);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
note that we return both the absolute value with offset
|
note that we return both the absolute value with offset
|
||||||
applied and a raw value without the offset applied. This
|
applied and a raw value without the offset applied. This
|
||||||
|
@ -259,9 +261,9 @@ MEASAirspeed::collect()
|
||||||
report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa);
|
report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa);
|
||||||
|
|
||||||
/* the dynamics of the filter can make it overshoot into the negative range */
|
/* the dynamics of the filter can make it overshoot into the negative range */
|
||||||
if (report.differential_pressure_filtered_pa < 0.0f) {
|
//if (report.differential_pressure_filtered_pa < 0.0f) {
|
||||||
report.differential_pressure_filtered_pa = _filter.reset(diff_press_pa);
|
// report.differential_pressure_filtered_pa = _filter.reset(diff_press_pa);
|
||||||
}
|
//}
|
||||||
|
|
||||||
report.differential_pressure_raw_pa = diff_press_pa_raw;
|
report.differential_pressure_raw_pa = diff_press_pa_raw;
|
||||||
report.max_differential_pressure_pa = _max_differential_pressure_pa;
|
report.max_differential_pressure_pa = _max_differential_pressure_pa;
|
||||||
|
|
|
@ -180,11 +180,13 @@ int do_airspeed_calibration(int mavlink_fd)
|
||||||
return ERROR;
|
return ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
mavlink_log_critical(mavlink_fd, "Offset of %d Pa, create airflow now!", (int)diff_pres_offset);
|
mavlink_log_critical(mavlink_fd, "Offset of %d Pascal", (int)diff_pres_offset);
|
||||||
|
|
||||||
/* wait 500 ms to ensure parameter propagated through the system */
|
/* wait 500 ms to ensure parameter propagated through the system */
|
||||||
usleep(500 * 1000);
|
usleep(500 * 1000);
|
||||||
|
|
||||||
|
mavlink_log_critical(mavlink_fd, "Create airflow now");
|
||||||
|
|
||||||
calibration_counter = 0;
|
calibration_counter = 0;
|
||||||
const unsigned maxcount = 3000;
|
const unsigned maxcount = 3000;
|
||||||
|
|
||||||
|
@ -204,18 +206,18 @@ int do_airspeed_calibration(int mavlink_fd)
|
||||||
calibration_counter++;
|
calibration_counter++;
|
||||||
|
|
||||||
if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) {
|
if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) {
|
||||||
if (calibration_counter % 100 == 0) {
|
if (calibration_counter % 500 == 0) {
|
||||||
mavlink_log_critical(mavlink_fd, "Missing airflow! (%d, wanted: 50 Pa, #h101)",
|
mavlink_log_info(mavlink_fd, "Create airflow! (%d, wanted: 50 Pa)",
|
||||||
(int)diff_pres.differential_pressure_raw_pa);
|
(int)diff_pres.differential_pressure_raw_pa);
|
||||||
}
|
}
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* do not allow negative values */
|
/* do not allow negative values */
|
||||||
if (diff_pres.differential_pressure_raw_pa < 0.0f) {
|
if (diff_pres.differential_pressure_raw_pa < 0.0f) {
|
||||||
mavlink_log_info(mavlink_fd, "negative pressure: ERROR (%d Pa)",
|
mavlink_log_critical(mavlink_fd, "Swap static and dynamic ports!");
|
||||||
(int)diff_pres.differential_pressure_raw_pa);
|
mavlink_log_info(mavlink_fd, "ERROR: Negative pressure difference detected! (%d Pa)",
|
||||||
mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)diff_pres.differential_pressure_raw_pa);
|
(int)diff_pres.differential_pressure_raw_pa);
|
||||||
close(diff_pres_sub);
|
close(diff_pres_sub);
|
||||||
|
|
||||||
/* the user setup is wrong, wipe the calibration to force a proper re-calibration */
|
/* the user setup is wrong, wipe the calibration to force a proper re-calibration */
|
||||||
|
@ -236,7 +238,7 @@ int do_airspeed_calibration(int mavlink_fd)
|
||||||
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
|
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
|
||||||
return ERROR;
|
return ERROR;
|
||||||
} else {
|
} else {
|
||||||
mavlink_log_info(mavlink_fd, "positive pressure: OK (%d Pa)",
|
mavlink_log_info(mavlink_fd, "Positive pressure: OK (%d Pa)",
|
||||||
(int)diff_pres.differential_pressure_raw_pa);
|
(int)diff_pres.differential_pressure_raw_pa);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue