From e217540e013aaa4162c95b361f511c7eb76bc7ad Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 25 Sep 2012 10:51:13 +0200 Subject: write all params to EEPROM for now (workaround to prevent standard values being written) --- apps/commander/commander.c | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) (limited to 'apps/commander') 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]); -- cgit v1.2.3