From cf55b0f93fb58a600e287fd24f826f65699bd3f5 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Tue, 18 Jan 2011 19:00:07 +0000 Subject: [PATCH] updated the stabilize_dampener variable git-svn-id: https://arducopter.googlecode.com/svn/trunk@1512 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/read_commands.pde | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopterMega/read_commands.pde b/ArduCopterMega/read_commands.pde index 4ccae0251b..1c001e382d 100644 --- a/ArduCopterMega/read_commands.pde +++ b/ArduCopterMega/read_commands.pde @@ -79,30 +79,30 @@ void parseCommand(char *buffer) case 'P': pid_stabilize_roll.kP((float)value / 1000); pid_stabilize_pitch.kP((float)value / 1000); - //save_EEPROM_PID(); + save_EEPROM_PID(); break; case 'I': pid_stabilize_roll.kI((float)value / 1000); pid_stabilize_pitch.kI((float)value / 1000); - //save_EEPROM_PID(); + save_EEPROM_PID(); break; case 'D': pid_stabilize_roll.kD((float)value / 1000); pid_stabilize_pitch.kD((float)value / 1000); - //save_EEPROM_PID(); + save_EEPROM_PID(); break; case 'X': pid_stabilize_roll.imax((int)(value * 100)); pid_stabilize_pitch.imax((int)(value * 100)); - //save_EEPROM_PID(); + save_EEPROM_PID(); break; case 'R': - //stabilize_rate_roll_pitch = (float)value / 1000; - //save_EEPROM_PID(); + stabilize_dampener = (float)value / 1000; + save_EEPROM_PID(); break; } init_pids();