diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-18 08:43:38 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-18 08:43:38 +0200 |
commit | ac00100cb800423347ad81967a7731ab766be629 (patch) | |
tree | 050ad45539eaad8c389eaf4c6ae7f03e1b931e09 /src/modules/commander | |
parent | a4ecdc95828484370e0e399d2f3c8b0e28f5c585 (diff) | |
download | px4-firmware-ac00100cb800423347ad81967a7731ab766be629.tar.gz px4-firmware-ac00100cb800423347ad81967a7731ab766be629.tar.bz2 px4-firmware-ac00100cb800423347ad81967a7731ab766be629.zip |
Hotfix: Disable gyro scale calibration to prevent people from wrongly using it
Diffstat (limited to 'src/modules/commander')
-rw-r--r-- | src/modules/commander/gyro_calibration.cpp | 12 |
1 files changed, 8 insertions, 4 deletions
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index 82a0349c9..369e6da62 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -163,7 +163,9 @@ int do_gyro_calibration(int mavlink_fd) return ERROR; } + mavlink_log_info(mavlink_fd, "offset calibration done."); +#if 0 /*** --- SCALING --- ***/ mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip."); @@ -241,9 +243,14 @@ int do_gyro_calibration(int mavlink_fd) } float gyro_scale = baseline_integral / gyro_integral; - float gyro_scales[] = { gyro_scale, gyro_scale, gyro_scale }; + warnx("gyro scale: yaw (z): %6.4f", (double)gyro_scale); mavlink_log_info(mavlink_fd, "gyro scale: yaw (z): %6.4f", (double)gyro_scale); +#else + float gyro_scales[] = { 1.0f, 1.0f, 1.0f }; +#endif + + if (isfinite(gyro_scales[0]) && isfinite(gyro_scales[1]) && isfinite(gyro_scales[2])) { @@ -277,9 +284,6 @@ int do_gyro_calibration(int mavlink_fd) warn("WARNING: auto-save of params to storage failed"); } - // char buf[50]; - // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]); - // mavlink_log_info(mavlink_fd, buf); mavlink_log_info(mavlink_fd, "gyro calibration done"); /* third beep by cal end routine */ |