Fixed EEProm for new vector style.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1252 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-12-24 23:59:52 +00:00
parent 98624b3de7
commit c63973e313
3 changed files with 10 additions and 10 deletions

View File

@ -1,5 +1,5 @@
/* /*
* AP_EEProm.h * AP_EEProm.cpp
* Copyright (C) James Goppert 2010 <james.goppert@gmail.com> * Copyright (C) James Goppert 2010 <james.goppert@gmail.com>
* *
* This file is free software: you can redistribute it and/or modify it * This file is free software: you can redistribute it and/or modify it

View File

@ -85,7 +85,7 @@ protected:
/** /**
* The main EEProm Registry class. * The main EEProm Registry class.
*/ */
class AP_EEPromRegistry : public AP_Vector<AP_EEPromEntry *> class AP_EEPromRegistry : public Vector<AP_EEPromEntry *>
{ {
public: public:

View File

@ -38,15 +38,15 @@ void loop()
Serial.printf_P(PSTR("\nvar.getId(): %d\n"), id); Serial.printf_P(PSTR("\nvar.getId(): %d\n"), id);
delay(2000); delay(2000);
Serial.printf_P(PSTR("\neepromRegistry(id)->getEntry(): %f\n"), eepromRegistry(id)->getEntry()); Serial.printf_P(PSTR("\neepromRegistry(id)->getEntry(): %f\n"), eepromRegistry[id]->getEntry());
delay(2000); delay(2000);
eepromRegistry(id)->setEntry(456); eepromRegistry[id]->setEntry(456);
Serial.printf_P(PSTR("\neepromRegistry(id)->setEntry(456): %d\n"), var.get()); Serial.printf_P(PSTR("\neepromRegistry(id)->setEntry(456): %d\n"), var.get());
delay(2000); delay(2000);
Serial.printf_P(PSTR("\nprint the parameters name by id: %s\n"), eepromRegistry(id)->getName()); Serial.printf_P(PSTR("\nprint the parameters name by id: %s\n"), eepromRegistry[id]->getName());
Serial.printf_P(PSTR("\nprint the parameters address by id: %d\n"), int(eepromRegistry(id)->getAddress())); Serial.printf_P(PSTR("\nprint the parameters address by id: %d\n"), int(eepromRegistry[id]->getAddress()));
Serial.print("\n\nSynced variable demo\n"); Serial.print("\n\nSynced variable demo\n");
@ -69,15 +69,15 @@ void loop()
Serial.printf_P(PSTR("\nvar2.getId(): %d\n"), id); Serial.printf_P(PSTR("\nvar2.getId(): %d\n"), id);
delay(2000); delay(2000);
Serial.printf_P(PSTR("\neepromRegistry(id)->getEntry(): %f\n"), eepromRegistry(id)->getEntry()); Serial.printf_P(PSTR("\neepromRegistry(id)->getEntry(): %f\n"), eepromRegistry[id]->getEntry());
delay(2000); delay(2000);
eepromRegistry(id)->setEntry(4.56); eepromRegistry[id]->setEntry(4.56);
Serial.printf_P(PSTR("\neepromRegistry(id)->setEntry(4.56): %f\n"), var2.get()); Serial.printf_P(PSTR("\neepromRegistry(id)->setEntry(4.56): %f\n"), var2.get());
delay(2000); delay(2000);
Serial.printf_P(PSTR("\nprint the parameters name by id: %s\n"), eepromRegistry(id)->getName()); Serial.printf_P(PSTR("\nprint the parameters name by id: %s\n"), eepromRegistry[id]->getName());
Serial.printf_P(PSTR("\nprint the parameters address by id: %d\n"), int(eepromRegistry(id)->getAddress())); Serial.printf_P(PSTR("\nprint the parameters address by id: %d\n"), int(eepromRegistry[id]->getAddress()));
delay(5000); delay(5000);
} }