aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds/preflight_check/preflight_check.c
diff options
context:
space:
mode:
Diffstat (limited to 'src/systemcmds/preflight_check/preflight_check.c')
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c148
1 files changed, 46 insertions, 102 deletions
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index 7752ffe67..982b03782 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -57,6 +57,7 @@
#include <drivers/drv_baro.h>
#include <mavlink/mavlink_log.h>
+#include <systemlib/rc_check.h>
__EXPORT int preflight_check_main(int argc, char *argv[]);
static int led_toggle(int leds, int led);
@@ -108,7 +109,7 @@ int preflight_check_main(int argc, char *argv[])
/* ---- ACCEL ---- */
close(fd);
- fd = open(ACCEL_DEVICE_PATH, 0);
+ fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
ret = ioctl(fd, ACCELIOCSELFTEST, 0);
if (ret != OK) {
@@ -118,6 +119,29 @@ int preflight_check_main(int argc, char *argv[])
goto system_eval;
}
+ /* check measurement result range */
+ struct accel_report acc;
+ ret = read(fd, &acc, sizeof(acc));
+
+ if (ret == sizeof(acc)) {
+ /* evaluate values */
+ if (sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z) > 30.0f /* m/s^2 */) {
+ warnx("accel with spurious values");
+ mavlink_log_critical(mavlink_fd, "SENSOR FAIL: |ACCEL| > 30 m/s^2");
+ /* this is frickin' fatal */
+ fail_on_error = true;
+ system_ok = false;
+ goto system_eval;
+ }
+ } else {
+ warnx("accel read failed");
+ mavlink_log_critical(mavlink_fd, "SENSOR FAIL: ACCEL READ");
+ /* this is frickin' fatal */
+ fail_on_error = true;
+ system_ok = false;
+ goto system_eval;
+ }
+
/* ---- GYRO ---- */
close(fd);
@@ -135,104 +159,15 @@ int preflight_check_main(int argc, char *argv[])
close(fd);
fd = open(BARO_DEVICE_PATH, 0);
+ close(fd);
/* ---- RC CALIBRATION ---- */
- param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
- _parameter_handles_rev, _parameter_handles_dz;
-
- float param_min, param_max, param_trim, param_rev, param_dz;
-
- bool rc_ok = true;
- char nbuf[20];
-
- /* first check channel mappings */
- /* check which map param applies */
- // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
- // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
- // /* give system time to flush error message in case there are more */
- // usleep(100000);
- // count++;
- // }
-
- for (int i = 0; i < 12; i++) {
- /* should the channel be enabled? */
- uint8_t count = 0;
-
- /* min values */
- sprintf(nbuf, "RC%d_MIN", i + 1);
- _parameter_handles_min = param_find(nbuf);
- param_get(_parameter_handles_min, &param_min);
-
- /* trim values */
- sprintf(nbuf, "RC%d_TRIM", i + 1);
- _parameter_handles_trim = param_find(nbuf);
- param_get(_parameter_handles_trim, &param_trim);
-
- /* max values */
- sprintf(nbuf, "RC%d_MAX", i + 1);
- _parameter_handles_max = param_find(nbuf);
- param_get(_parameter_handles_max, &param_max);
-
- /* channel reverse */
- sprintf(nbuf, "RC%d_REV", i + 1);
- _parameter_handles_rev = param_find(nbuf);
- param_get(_parameter_handles_rev, &param_rev);
-
- /* channel deadzone */
- sprintf(nbuf, "RC%d_DZ", i + 1);
- _parameter_handles_dz = param_find(nbuf);
- param_get(_parameter_handles_dz, &param_dz);
-
- /* assert min..center..max ordering */
- if (param_min < 500) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MIN < 500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_max > 2500) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAX > 2500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_trim < param_min) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM < MIN", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_trim > param_max) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM > MAX", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
-
- /* assert deadzone is sane */
- if (param_dz > 500) {
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_DZ > 500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- count++;
- }
+ bool rc_ok = (OK == rc_calibration_check(mavlink_fd));
- /* check which map param applies */
- // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
- // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
- // /* give system time to flush error message in case there are more */
- // usleep(100000);
- // count++;
- // }
-
- /* sanity checks pass, enable channel */
- if (count) {
- mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
- usleep(100000);
- rc_ok = false;
- }
- }
+ /* warn */
+ if (!rc_ok)
+ warnx("rc calibration test failed");
/* require RC ok to keep system_ok */
system_ok &= rc_ok;
@@ -248,34 +183,43 @@ system_eval:
} else {
fflush(stdout);
- int buzzer = open("/dev/tone_alarm", O_WRONLY);
+ warnx("PREFLIGHT CHECK ERROR! TRIGGERING ALARM");
+ fflush(stderr);
+
+ int buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY);
int leds = open(LED_DEVICE_PATH, 0);
+ if (leds < 0) {
+ close(buzzer);
+ errx(1, "failed to open leds, aborting");
+ }
+
/* flip blue led into alternating amber */
led_off(leds, LED_BLUE);
led_off(leds, LED_AMBER);
led_toggle(leds, LED_BLUE);
/* display and sound error */
- for (int i = 0; i < 150; i++)
+ for (int i = 0; i < 14; i++)
{
led_toggle(leds, LED_BLUE);
led_toggle(leds, LED_AMBER);
if (i % 10 == 0) {
- ioctl(buzzer, TONE_SET_ALARM, 4);
+ ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEUTRAL_TUNE);
} else if (i % 5 == 0) {
- ioctl(buzzer, TONE_SET_ALARM, 2);
+ ioctl(buzzer, TONE_SET_ALARM, TONE_ERROR_TUNE);
}
usleep(100000);
}
/* stop alarm */
- ioctl(buzzer, TONE_SET_ALARM, 0);
+ ioctl(buzzer, TONE_SET_ALARM, TONE_STOP_TUNE);
- /* switch on leds */
+ /* switch off leds */
led_on(leds, LED_BLUE);
led_on(leds, LED_AMBER);
+ close(leds);
if (fail_on_error) {
/* exit with error message */
@@ -307,4 +251,4 @@ static int led_off(int leds, int led)
static int led_on(int leds, int led)
{
return ioctl(leds, LED_ON, led);
-} \ No newline at end of file
+}