added trim save

git-svn-id: https://arducopter.googlecode.com/svn/trunk@980 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2010-11-29 01:44:40 +00:00
parent 2ac2faf7a7
commit 4ef6bd673f
2 changed files with 12 additions and 2 deletions

View File

@ -98,6 +98,8 @@ RC_Channel::calc_pwm(void)
radio_out = pwm_out + radio_min;
}
// ------------------------------------------
void
RC_Channel::load_eeprom(void)
{
@ -109,11 +111,18 @@ RC_Channel::load_eeprom(void)
void
RC_Channel::save_eeprom(void)
{
eeprom_write_word((uint16_t *) _address, radio_min);
eeprom_write_word((uint16_t *) _address, radio_min);
eeprom_write_word((uint16_t *) (_address + 2), radio_max);
eeprom_write_word((uint16_t *) (_address + 4), radio_trim);
}
// ------------------------------------------
void
RC_Channel::save_trim(void)
{
eeprom_write_word((uint16_t *) (_address + 4), radio_trim);
}
// ------------------------------------------
void

View File

@ -38,6 +38,7 @@ class RC_Channel{
// startup
void load_eeprom(void);
void save_eeprom(void);
void save_trim(void);
void set_filter(bool filter);
// setup the control preferences
@ -58,7 +59,7 @@ class RC_Channel{
// value generated from PWM
int16_t control_in;
int8_t dead_zone; // used to keep noise down and create a dead zone.
int16_t dead_zone; // used to keep noise down and create a dead zone.
int control_mix(float value);