diff options
author | hauptmech <hauptmech@gmail.com> | 2015-01-28 15:45:00 +1300 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2015-01-31 15:53:34 +0100 |
commit | 0b784c20c8bf69cee281f6717f055b0309d331b1 (patch) | |
tree | 9de9bf48368b35e213569ee1f26fe9083790cc73 /src/modules/commander/accelerometer_calibration.cpp | |
parent | e9bcc0a2624c77c6f71bb926347e85b8c7592e34 (diff) | |
download | px4-firmware-0b784c20c8bf69cee281f6717f055b0309d331b1.tar.gz px4-firmware-0b784c20c8bf69cee281f6717f055b0309d331b1.tar.bz2 px4-firmware-0b784c20c8bf69cee281f6717f055b0309d331b1.zip |
Save and check device id for acc and gyro calibration parameters.config_all_devices
Fix config utility to work with all devices of each type.
Accel, gyro and mag devices correctly set their device_id devtype.
Combo devices (mpu6000 lsm303d) now correctly return their devtype.
config util shows device id for all sensor types.
Add, save during calibration and check during preflight ID parameters for accelerometer and gyro
Diffstat (limited to 'src/modules/commander/accelerometer_calibration.cpp')
-rw-r--r-- | src/modules/commander/accelerometer_calibration.cpp | 8 |
1 files changed, 8 insertions, 0 deletions
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index d4cd97be6..13ab966ab 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -159,6 +159,7 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo int do_accel_calibration(int mavlink_fd) { int fd; + int32_t device_id; mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name); @@ -180,6 +181,9 @@ int do_accel_calibration(int mavlink_fd) /* reset all offsets to zero and all scales to one */ fd = open(ACCEL_DEVICE_PATH, 0); + + device_id = ioctl(fd, DEVIOCGDEVICEID, 0); + res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale); close(fd); @@ -226,6 +230,10 @@ int do_accel_calibration(int mavlink_fd) mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG); res = ERROR; } + + if (param_set(param_find("SENS_ACC_ID"), &(device_id))) { + res = ERROR; + } } if (res == OK) { |