mirror of https://github.com/ArduPilot/ardupilot
removed EEPROMB references
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1314 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
ef160226cc
commit
7dd1b3cbe7
|
@ -118,32 +118,32 @@ RC_Channel::calc_pwm(void)
|
|||
void
|
||||
RC_Channel::load_eeprom(void)
|
||||
{
|
||||
//radio_min = eeprom_read_word((uint16_t *) _address);
|
||||
//radio_max = eeprom_read_word((uint16_t *) (_address + 2));
|
||||
//radio_trim = eeprom_read_word((uint16_t *) (_address + 4));
|
||||
radio_min = _ee.read_int(_address);
|
||||
radio_max = _ee.read_int(_address + 2);
|
||||
radio_trim = _ee.read_int(_address + 4);
|
||||
radio_min = eeprom_read_word((uint16_t *) _address);
|
||||
radio_max = eeprom_read_word((uint16_t *) (_address + 2));
|
||||
radio_trim = eeprom_read_word((uint16_t *) (_address + 4));
|
||||
//radio_min = _ee.read_int(_address);
|
||||
//radio_max = _ee.read_int(_address + 2);
|
||||
//radio_trim = _ee.read_int(_address + 4);
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::save_eeprom(void)
|
||||
{
|
||||
//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);
|
||||
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);
|
||||
|
||||
_ee.write_int(_address, radio_min);
|
||||
_ee.write_int((_address + 2), radio_max);
|
||||
_ee.write_int((_address + 4), radio_trim);
|
||||
//_ee.write_int(_address, radio_min);
|
||||
//_ee.write_int((_address + 2), radio_max);
|
||||
//_ee.write_int((_address + 4), radio_trim);
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
void
|
||||
RC_Channel::save_trim(void)
|
||||
{
|
||||
//eeprom_write_word((uint16_t *) (_address + 4), radio_trim);
|
||||
_ee.write_int((_address + 4), radio_trim);
|
||||
eeprom_write_word((uint16_t *) (_address + 4), radio_trim);
|
||||
//_ee.write_int((_address + 4), radio_trim);
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
|
|
@ -7,7 +7,6 @@
|
|||
#define RC_Channel_h
|
||||
|
||||
#include <stdint.h>
|
||||
#include <AP_EEPROMB.h>
|
||||
|
||||
/// @class RC_Channel
|
||||
/// @brief Object managing one RC channel
|
||||
|
@ -101,7 +100,6 @@ class RC_Channel{
|
|||
bool _type;
|
||||
int16_t _high;
|
||||
int16_t _low;
|
||||
AP_EEPROMB _ee;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue