aboutsummaryrefslogtreecommitdiff
path: root/apps/commander/commander.c
diff options
context:
space:
mode:
authorJulian Oes <joes@student.ethz.ch>2012-09-25 10:51:13 +0200
committerJulian Oes <joes@student.ethz.ch>2012-09-25 10:51:13 +0200
commite217540e013aaa4162c95b361f511c7eb76bc7ad (patch)
treedb9825217868dfe537e81e7715033a32f9cbd6b1 /apps/commander/commander.c
parent268874fdb7d3f5396a0ddf7731681afb42c01ec2 (diff)
downloadpx4-firmware-e217540e013aaa4162c95b361f511c7eb76bc7ad.tar.gz
px4-firmware-e217540e013aaa4162c95b361f511c7eb76bc7ad.tar.bz2
px4-firmware-e217540e013aaa4162c95b361f511c7eb76bc7ad.zip
write all params to EEPROM for now (workaround to prevent standard values being written)
Diffstat (limited to 'apps/commander/commander.c')
-rw-r--r--apps/commander/commander.c12
1 files changed, 9 insertions, 3 deletions
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index 18dd0ceb6..7535b9046 100644
--- a/apps/commander/commander.c
+++ b/apps/commander/commander.c
@@ -516,11 +516,13 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
free(mag_minima[2]);
/* auto-save to EEPROM */
- int save_ret = pm_save_eeprom(true);
+ int save_ret = pm_save_eeprom(false);
if(save_ret != 0) {
warn("WARNING: auto-save of params to EEPROM failed");
}
+ mavlink_log_info(mavlink_fd, "[commander] magnetometer calibration finished");
+
close(sub_sensor_combined);
}
@@ -601,7 +603,7 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
close(fd);
/* auto-save to EEPROM */
- int save_ret = pm_save_eeprom(true);
+ int save_ret = pm_save_eeprom(false);
if(save_ret != 0) {
warn("WARNING: auto-save of params to EEPROM failed");
}
@@ -610,6 +612,8 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
status->flag_preflight_gyro_calibration = false;
state_machine_publish(status_pub, status, mavlink_fd);
+ mavlink_log_info(mavlink_fd, "[commander] gyro calibration finished");
+
// char offset_output[50];
// sprintf(offset_output, "[commander] gyro 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, offset_output);
@@ -716,7 +720,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status)
close(fd);
/* auto-save to EEPROM */
- int save_ret = pm_save_eeprom(true);
+ int save_ret = pm_save_eeprom(false);
if(save_ret != 0) {
warn("WARNING: auto-save of params to EEPROM failed");
}
@@ -725,6 +729,8 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status)
status->flag_preflight_accel_calibration = false;
state_machine_publish(status_pub, status, mavlink_fd);
+ mavlink_log_info(mavlink_fd, "[commander] acceleration calibration finished");
+
// char offset_output[50];
// sprintf(offset_output, "[commander] accel cal: x:%8.4f y:%8.4f z:%8.4f", (double)accel_offset[0],
// (double)accel_offset[1], (double)accel_offset[2]);