aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/airspeed_calibration.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander/airspeed_calibration.cpp')
-rw-r--r--src/modules/commander/airspeed_calibration.cpp39
1 files changed, 25 insertions, 14 deletions
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index 0e58c68b6..cae1d7684 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -61,6 +61,15 @@ static const int ERROR = -1;
static const char *sensor_name = "dpress";
+#define HUMAN_ASPD_CAL_FAILED_MSG "Calibration failed, see http://px4.io/help/aspd"
+
+static void feedback_calibration_failed(int mavlink_fd)
+{
+ sleep(5);
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ mavlink_log_critical(mavlink_fd, HUMAN_ASPD_CAL_FAILED_MSG);
+}
+
int do_airspeed_calibration(int mavlink_fd)
{
/* give directions */
@@ -99,7 +108,7 @@ int do_airspeed_calibration(int mavlink_fd)
float analog_scaling = 0.0f;
param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling));
if (fabsf(analog_scaling) < 0.1f) {
- mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]");
+ mavlink_log_critical(mavlink_fd, "No airspeed sensor, see http://px4.io/help/aspd");
close(diff_pres_sub);
return ERROR;
}
@@ -138,7 +147,7 @@ int do_airspeed_calibration(int mavlink_fd)
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
- mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
return ERROR;
}
@@ -175,16 +184,18 @@ int do_airspeed_calibration(int mavlink_fd)
}
} else {
- mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
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 */
usleep(500 * 1000);
+ mavlink_log_critical(mavlink_fd, "Create airflow now");
+
calibration_counter = 0;
const unsigned maxcount = 3000;
@@ -204,18 +215,18 @@ int do_airspeed_calibration(int mavlink_fd)
calibration_counter++;
if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) {
- if (calibration_counter % 100 == 0) {
- mavlink_log_critical(mavlink_fd, "Missing airflow! (%d, wanted: 50 Pa, #h101)",
- (int)diff_pres.differential_pressure_raw_pa);
+ if (calibration_counter % 500 == 0) {
+ mavlink_log_info(mavlink_fd, "Create air pressure! (got %d, wanted: 50 Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
}
continue;
}
/* do not allow negative values */
if (diff_pres.differential_pressure_raw_pa < 0.0f) {
- mavlink_log_info(mavlink_fd, "negative pressure: ERROR (%d Pa)",
- (int)diff_pres.differential_pressure_raw_pa);
- mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)diff_pres.differential_pressure_raw_pa);
+ mavlink_log_info(mavlink_fd, "ERROR: Negative pressure difference detected! (%d Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ mavlink_log_critical(mavlink_fd, "Swap static and dynamic ports!");
close(diff_pres_sub);
/* the user setup is wrong, wipe the calibration to force a proper re-calibration */
@@ -233,24 +244,24 @@ int do_airspeed_calibration(int mavlink_fd)
close(diff_pres_sub);
- mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
return ERROR;
} 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);
break;
}
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
- mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
return ERROR;
}
}
if (calibration_counter == maxcount) {
- mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
return ERROR;
}