removed EEPROMB references

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1315 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2010-12-28 18:42:56 +00:00
parent 857046eea4
commit 09b02a06fd
2 changed files with 11 additions and 13 deletions

View File

@ -73,15 +73,15 @@ PID::load_gains()
// load is a NOP if the gain array is managed externally // load is a NOP if the gain array is managed externally
break; break;
case STORE_EEPROM_UINT16: case STORE_EEPROM_UINT16:
// _kp = (float)(eeprom_read_word((uint16_t *) _address)) / 1000.0; _kp = (float)(eeprom_read_word((uint16_t *) _address)) / 1000.0;
// _ki = (float)(eeprom_read_word((uint16_t *) (_address + 2))) / 1000.0; _ki = (float)(eeprom_read_word((uint16_t *) (_address + 2))) / 1000.0;
//_kd = (float)(eeprom_read_word((uint16_t *) (_address + 4))) / 1000.0; _kd = (float)(eeprom_read_word((uint16_t *) (_address + 4))) / 1000.0;
//_imax = eeprom_read_word((uint16_t *) (_address + 6)) * 100; _imax = eeprom_read_word((uint16_t *) (_address + 6)) * 100;
_kp = (float)_ee.read_int(_address) / 1000.0; //_kp = (float)_ee.read_int(_address) / 1000.0;
_ki = (float)_ee.read_int(_address + 2) / 1000.0; //_ki = (float)_ee.read_int(_address + 2) / 1000.0;
_kd = (float)_ee.read_int(_address + 4) / 1000.0; //_kd = (float)_ee.read_int(_address + 4) / 1000.0;
_imax = (float)_ee.read_int(_address + 6) * 100; //_imax = (float)_ee.read_int(_address + 6) * 100;
break; break;
@ -103,16 +103,16 @@ PID::save_gains()
// save is a NOP if the gain array is managed externally // save is a NOP if the gain array is managed externally
break; break;
case STORE_EEPROM_UINT16: case STORE_EEPROM_UINT16:
/*
eeprom_write_word((uint16_t *) _address, (int)(_kp * 1000)); eeprom_write_word((uint16_t *) _address, (int)(_kp * 1000));
eeprom_write_word((uint16_t *) (_address + 2), (int)(_ki * 1000)); eeprom_write_word((uint16_t *) (_address + 2), (int)(_ki * 1000));
eeprom_write_word((uint16_t *) (_address + 4), (int)(_kd * 1000)); eeprom_write_word((uint16_t *) (_address + 4), (int)(_kd * 1000));
eeprom_write_word((uint16_t *) (_address + 6), (int)_imax/100); eeprom_write_word((uint16_t *) (_address + 6), (int)_imax/100);
*/
_ee.write_int(_address, (int)(_kp * 1000)); /*_ee.write_int(_address, (int)(_kp * 1000));
_ee.write_int(_address + 2, (int)(_ki * 1000)); _ee.write_int(_address + 2, (int)(_ki * 1000));
_ee.write_int(_address + 4, (int)(_kd * 1000)); _ee.write_int(_address + 4, (int)(_kd * 1000));
_ee.write_int(_address + 6, (int)(_imax /100)); _ee.write_int(_address + 6, (int)(_imax /100));
*/
break; break;
case STORE_EEPROM_FLOAT: case STORE_EEPROM_FLOAT:
//eeprom_write_block((const void *)&_kp,(void *)(_address),sizeof(_kp)); //eeprom_write_block((const void *)&_kp,(void *)(_address),sizeof(_kp));

View File

@ -7,7 +7,6 @@
#define PID_h #define PID_h
#include <stdint.h> #include <stdint.h>
#include <AP_EEPROMB.h>
/// @class PID /// @class PID
/// @brief Object managing one PID control /// @brief Object managing one PID control
@ -118,7 +117,6 @@ public:
float get_integrator() { return _integrator; } float get_integrator() { return _integrator; }
private: private:
AP_EEPROMB _ee;
uint16_t _address; ///< EEPROM address for save/restore of P/I/D uint16_t _address; ///< EEPROM address for save/restore of P/I/D
float *_gain_array; ///< pointer to the gains for this pid float *_gain_array; ///< pointer to the gains for this pid