From f7f48ebb2051f5eb45fdf8ed8875c567e3b5a296 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Sun, 6 Mar 2011 09:35:57 +0000 Subject: [PATCH] mavlink: fixed store of parameter values to eeprom setting parameters via mavlink only saves them in memory. We need to use AP_Var::save_all() to save them permanently git-svn-id: https://arducopter.googlecode.com/svn/trunk@1748 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/GCS_Mavlink.pde | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/ArduCopterMega/GCS_Mavlink.pde b/ArduCopterMega/GCS_Mavlink.pde index a1c02ec647..021ad4d8e3 100644 --- a/ArduCopterMega/GCS_Mavlink.pde +++ b/ArduCopterMega/GCS_Mavlink.pde @@ -239,21 +239,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; case MAV_ACTION_STORAGE_READ: - //read_EEPROM_startup(); - //read_EEPROM_airstart_critical(); - //read_command_index(); - //read_EEPROM_flight_modes(); + AP_Var::load_all(); break; case MAV_ACTION_STORAGE_WRITE: - //save_EEPROM_trims(); - //save_EEPROM_waypoint_info(); - //save_EEPROM_gains(); - //save_command_index(); - //save_pressure_data(); - //save_EEPROM_radio_minmax(); - //save_user_configs(); - //save_EEPROM_flight_modes(); + AP_Var::save_all(); break; case MAV_ACTION_CALIBRATE_RC: break;