diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-18 11:49:32 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-18 11:49:32 +0200 |
commit | 626f433630697a630e5063f4f53cfa570bb4a9df (patch) | |
tree | 62fa0bf8afd0de0eff15a68a249c42f5358f8e16 /src | |
parent | 6624c8f1c40d08d594fd2f180bff1088eaff82d4 (diff) | |
parent | 210e7f92454e2b99a448c1563e22fed6f0220ea7 (diff) | |
download | px4-firmware-626f433630697a630e5063f4f53cfa570bb4a9df.tar.gz px4-firmware-626f433630697a630e5063f4f53cfa570bb4a9df.tar.bz2 px4-firmware-626f433630697a630e5063f4f53cfa570bb4a9df.zip |
Merge branch 'master' of github.com:PX4/Firmware
Diffstat (limited to 'src')
-rw-r--r-- | src/modules/commander/gyro_calibration.cpp | 12 | ||||
-rw-r--r-- | src/modules/systemlib/param/param.c | 6 |
2 files changed, 13 insertions, 5 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 */ diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c index c69de52b7..e7c96fe54 100644 --- a/src/modules/systemlib/param/param.c +++ b/src/modules/systemlib/param/param.c @@ -519,6 +519,10 @@ param_save_default(void) int fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL); if (fd < 0) { + /* do another attempt in case the unlink call is not synced yet */ + usleep(5000); + fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL); + warn("opening '%s' for writing failed", param_get_default_file()); return fd; } @@ -528,7 +532,7 @@ param_save_default(void) if (result != 0) { warn("error exporting parameters to '%s'", param_get_default_file()); - unlink(param_get_default_file()); + (void)unlink(param_get_default_file()); return result; } |