From 09b02a06fd8d78f1ee1fbd9086f3dc35c30e9c65 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Tue, 28 Dec 2010 18:42:56 +0000 Subject: [PATCH] removed EEPROMB references git-svn-id: https://arducopter.googlecode.com/svn/trunk@1315 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/PID/PID.cpp | 22 +++++++++++----------- libraries/PID/PID.h | 2 -- 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 22f36f3989..a451175689 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -73,15 +73,15 @@ PID::load_gains() // load is a NOP if the gain array is managed externally break; case STORE_EEPROM_UINT16: - // _kp = (float)(eeprom_read_word((uint16_t *) _address)) / 1000.0; - // _ki = (float)(eeprom_read_word((uint16_t *) (_address + 2))) / 1000.0; - //_kd = (float)(eeprom_read_word((uint16_t *) (_address + 4))) / 1000.0; - //_imax = eeprom_read_word((uint16_t *) (_address + 6)) * 100; + _kp = (float)(eeprom_read_word((uint16_t *) _address)) / 1000.0; + _ki = (float)(eeprom_read_word((uint16_t *) (_address + 2))) / 1000.0; + _kd = (float)(eeprom_read_word((uint16_t *) (_address + 4))) / 1000.0; + _imax = eeprom_read_word((uint16_t *) (_address + 6)) * 100; - _kp = (float)_ee.read_int(_address) / 1000.0; - _ki = (float)_ee.read_int(_address + 2) / 1000.0; - _kd = (float)_ee.read_int(_address + 4) / 1000.0; - _imax = (float)_ee.read_int(_address + 6) * 100; + //_kp = (float)_ee.read_int(_address) / 1000.0; + //_ki = (float)_ee.read_int(_address + 2) / 1000.0; + //_kd = (float)_ee.read_int(_address + 4) / 1000.0; + //_imax = (float)_ee.read_int(_address + 6) * 100; break; @@ -103,16 +103,16 @@ PID::save_gains() // save is a NOP if the gain array is managed externally break; case STORE_EEPROM_UINT16: - /* 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 + 4), (int)(_kd * 1000)); 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 + 4, (int)(_kd * 1000)); _ee.write_int(_address + 6, (int)(_imax /100)); + */ break; case STORE_EEPROM_FLOAT: //eeprom_write_block((const void *)&_kp,(void *)(_address),sizeof(_kp)); diff --git a/libraries/PID/PID.h b/libraries/PID/PID.h index fefaa92486..2e8edbe126 100644 --- a/libraries/PID/PID.h +++ b/libraries/PID/PID.h @@ -7,7 +7,6 @@ #define PID_h #include -#include /// @class PID /// @brief Object managing one PID control @@ -118,7 +117,6 @@ public: float get_integrator() { return _integrator; } private: - AP_EEPROMB _ee; uint16_t _address; ///< EEPROM address for save/restore of P/I/D float *_gain_array; ///< pointer to the gains for this pid