diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2015-02-01 18:26:00 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2015-02-03 08:55:16 +0100 |
commit | 9d0c74e8ec67ffa4847ee88c0385b088ce73b0ed (patch) | |
tree | afd63ea0a47ef6d49ddfdedc64b0c9d4a8049693 /src/systemcmds/preflight_check/preflight_check.c | |
parent | ed98dc1fdfad3f4ec501c5a9a8cfdaaf9b377614 (diff) | |
download | px4-firmware-9d0c74e8ec67ffa4847ee88c0385b088ce73b0ed.tar.gz px4-firmware-9d0c74e8ec67ffa4847ee88c0385b088ce73b0ed.tar.bz2 px4-firmware-9d0c74e8ec67ffa4847ee88c0385b088ce73b0ed.zip |
Preflight check: Use indexed sensor params
Diffstat (limited to 'src/systemcmds/preflight_check/preflight_check.c')
-rw-r--r-- | src/systemcmds/preflight_check/preflight_check.c | 6 |
1 files changed, 3 insertions, 3 deletions
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c index 3e1f76714..c5c959cf3 100644 --- a/src/systemcmds/preflight_check/preflight_check.c +++ b/src/systemcmds/preflight_check/preflight_check.c @@ -99,7 +99,7 @@ int preflight_check_main(int argc, char *argv[]) } devid = ioctl(fd, DEVIOCGDEVICEID,0); - param_get(param_find("SENS_MAG_ID"), &(calibration_devid)); + param_get(param_find("CAL_MAG0_ID"), &(calibration_devid)); if (devid != calibration_devid){ warnx("magnetometer calibration is for a different device - calibrate magnetometer first"); mavlink_log_critical(mavlink_fd, "SENSOR FAIL: MAG CAL ID"); @@ -122,7 +122,7 @@ int preflight_check_main(int argc, char *argv[]) fd = open(ACCEL_DEVICE_PATH, O_RDONLY); devid = ioctl(fd, DEVIOCGDEVICEID,0); - param_get(param_find("SENS_ACC_ID"), &(calibration_devid)); + param_get(param_find("CAL_ACC0_ID"), &(calibration_devid)); if (devid != calibration_devid){ warnx("accelerometer calibration is for a different device - calibrate accelerometer first"); mavlink_log_critical(mavlink_fd, "SENSOR FAIL: ACC CAL ID"); @@ -168,7 +168,7 @@ int preflight_check_main(int argc, char *argv[]) fd = open(GYRO_DEVICE_PATH, 0); devid = ioctl(fd, DEVIOCGDEVICEID,0); - param_get(param_find("SENS_GYRO_ID"), &(calibration_devid)); + param_get(param_find("CAL_GYRO0_ID"), &(calibration_devid)); if (devid != calibration_devid){ warnx("gyro calibration is for a different device - calibrate gyro first"); mavlink_log_critical(mavlink_fd, "SENSOR FAIL: GYRO CAL ID"); |