Use table iterator for EEPROM read/write (#620)

* refactor: use a loop for writeAllConfig.

Future proofing: new pages will get automatically
written

* Call existing [read|store]EEPROMVersion functions

* Common function to compute CRC address

* Bulk write calibration tables

* Use EEPROM get/put instead of hand rolled code

* Typedef the EEPROM address

I.e. the EEPROM.read() parameter type

* Encapsulate eepromWritesPending

* Remove C++ namespaces

* Use table iterators for read/write

* Rename storage.ino to .cpp

This fixes a warning
This commit is contained in:
tx_haggis 2021-09-14 01:51:26 -05:00 committed by GitHub
parent b0e311b3e4
commit 5e409445a4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
14 changed files with 530 additions and 673 deletions

View File

@ -15,8 +15,10 @@
#define COUNTER_TYPE uint16_t
#ifdef USE_SPI_EEPROM
#define EEPROM_LIB_H "src/SPIAsEEPROM/SPIAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#else
#define EEPROM_LIB_H <EEPROM.h>
typedef int eeprom_address_t;
#endif
#define RTC_LIB_H "TimeLib.h"
void initBoard();

View File

@ -18,6 +18,7 @@
#define COUNTER_TYPE uint16_t
#ifdef USE_SPI_EEPROM
#define EEPROM_LIB_H "src/SPIAsEEPROM/SPIAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#include EEPROM_LIB_H
//SPIClass SPI_for_flash(1, 2, 3); //SPI1_MOSI, SPI1_MISO, SPI1_SCK
SPIClass SPI_for_flash = SPI; //SPI1_MOSI, SPI1_MISO, SPI1_SCK
@ -29,6 +30,7 @@
#else
//#define EEPROM_LIB_H <EEPROM.h>
#define EEPROM_LIB_H "src/FlashStorage/FlashAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#endif
#define RTC_LIB_H "TimeLib.h"
void initBoard();

View File

@ -16,8 +16,10 @@
#define EEPROM_LIB_H "src/BackupSram/BackupSramAsEEPROM.h"
#elif defined(FRAM_AS_EEPROM) //https://github.com/VitorBoss/FRAM
#define EEPROM_LIB_H <Fram.h>
typedef uint16_t eeprom_address_t;
#else
#define EEPROM_LIB_H "src/SPIAsEEPROM/SPIAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#endif
#ifndef USE_SERIAL3

View File

@ -78,11 +78,13 @@ extern "C" char* sbrk(int incr);
*/
#if defined(SRAM_AS_EEPROM)
#define EEPROM_LIB_H "src/BackupSram/BackupSramAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#include EEPROM_LIB_H
extern BackupSramAsEEPROM EEPROM;
#elif defined(USE_SPI_EEPROM)
#define EEPROM_LIB_H "src/SPIAsEEPROM/SPIAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#include EEPROM_LIB_H
extern SPIClass SPI_for_flash; //SPI1_MOSI, SPI1_MISO, SPI1_SCK
@ -93,6 +95,7 @@ extern "C" char* sbrk(int incr);
#elif defined(FRAM_AS_EEPROM) //https://github.com/VitorBoss/FRAM
#define EEPROM_LIB_H "src/FRAM/Fram.h"
typedef uint16_t eeprom_address_t;
#include EEPROM_LIB_H
#if defined(STM32F407xx)
extern FramClass EEPROM; /*(mosi, miso, sclk, ssel, clockspeed) 31/01/2020*/
@ -102,6 +105,7 @@ extern "C" char* sbrk(int incr);
#else //default case, internal flash as EEPROM
#define EEPROM_LIB_H "src/SPIAsEEPROM/SPIAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#include EEPROM_LIB_H
extern InternalSTM32F4_EEPROM_Class EEPROM;
#if defined(STM32F401xC)
@ -110,7 +114,6 @@ extern "C" char* sbrk(int incr);
#endif
#define RTC_LIB_H "STM32RTC.h"
/*

View File

@ -18,8 +18,10 @@
#define BOARD_MAX_IO_PINS 34 //digital pins + analog channels + 1
#ifdef USE_SPI_EEPROM
#define EEPROM_LIB_H "src/SPIAsEEPROM/SPIAsEEPROM.h"
typedef uint16_t eeprom_address_t;
#else
#define EEPROM_LIB_H <EEPROM.h>
typedef int eeprom_address_t;
#endif
#define RTC_ENABLED
#define RTC_LIB_H "TimeLib.h"

View File

@ -17,6 +17,7 @@
#define BOARD_MAX_DIGITAL_PINS 34
#define BOARD_MAX_IO_PINS 34 //digital pins + analog channels + 1
#define EEPROM_LIB_H <EEPROM.h>
typedef int eeprom_address_t;
#define RTC_ENABLED
#define RTC_LIB_H "TimeLib.h"

View File

@ -11,6 +11,7 @@
#define BOARD_MAX_IO_PINS 52 //digital pins + analog channels + 1
#define BOARD_MAX_DIGITAL_PINS 52 //Pretty sure this isn't right
#define EEPROM_LIB_H <EEPROM.h> //The name of the file that provides the EEPROM class
typedef int eeprom_address_t;
#define micros_safe() micros() //timer5 method is not used on anything but AVR, the micros_safe() macro is simply an alias for the normal micros()
void initBoard();
uint16_t freeRam();

View File

@ -326,7 +326,6 @@ void initialiseAll()
if ( configPage6.useExtBaro != 0 )
{
readBaro();
//EEPROM.update(EEPROM_LAST_BARO, currentStatus.baro);
storeLastBaro(currentStatus.baro);
}
else
@ -339,7 +338,6 @@ void initialiseAll()
if ((currentStatus.MAP >= BARO_MIN) && (currentStatus.MAP <= BARO_MAX)) //Check if engine isn't running
{
currentStatus.baro = currentStatus.MAP;
//EEPROM.update(EEPROM_LAST_BARO, currentStatus.baro);
storeLastBaro(currentStatus.baro);
}
else

View File

@ -286,7 +286,7 @@ void loop()
readTPS();
#endif
if(eepromWritesPending == true) { writeAllConfig(); } //Check for any outstanding EEPROM writes.
if(isEepromWritePending() == true) { writeAllConfig(); } //Check for any outstanding EEPROM writes.
}
if (BIT_CHECK(LOOP_TIMER, BIT_TIMER_4HZ))
{

472
speeduino/storage.cpp Normal file
View File

@ -0,0 +1,472 @@
/*
Speeduino - Simple engine management for the Arduino Mega 2560 platform
Copyright (C) Josh Stewart
A full copy of the license may be found in the projects root directory
*/
/** @file
* Lower level ConfigPage*, Table2D, Table3D and EEPROM storage operations.
*/
#include "globals.h"
#include "table.h"
#include EEPROM_LIB_H //This is defined in the board .h files
#include "storage.h"
#include "table_iterator.h"
#include "pages.h"
//The maximum number of write operations that will be performed in one go. If we try to write to the EEPROM too fast (Each write takes ~3ms) then the rest of the system can hang)
#if defined(CORE_STM32) || defined(CORE_TEENSY) & !defined(USE_SPI_EEPROM)
#define EEPROM_MAX_WRITE_BLOCK 64
#else
#define EEPROM_MAX_WRITE_BLOCK 30
#endif
#define EEPROM_DATA_VERSION 0
// Calibration data is stored at the end of the EEPROM (This is in case any further calibration tables are needed as they are large blocks)
#define STORAGE_END 0xFFF // Should be E2END?
#define EEPROM_CALIBRATION_CLT_VALUES (STORAGE_END-sizeof(cltCalibration_values))
#define EEPROM_CALIBRATION_CLT_BINS (EEPROM_CALIBRATION_CLT_VALUES-sizeof(cltCalibration_bins))
#define EEPROM_CALIBRATION_IAT_VALUES (EEPROM_CALIBRATION_CLT_BINS-sizeof(iatCalibration_values))
#define EEPROM_CALIBRATION_IAT_BINS (EEPROM_CALIBRATION_IAT_VALUES-sizeof(iatCalibration_bins))
#define EEPROM_CALIBRATION_O2_VALUES (EEPROM_CALIBRATION_IAT_BINS-sizeof(o2Calibration_values))
#define EEPROM_CALIBRATION_O2_BINS (EEPROM_CALIBRATION_O2_VALUES-sizeof(o2Calibration_bins))
#define EEPROM_LAST_BARO (EEPROM_CALIBRATION_O2_BINS-1)
static bool eepromWritesPending = false;
bool isEepromWritePending()
{
return eepromWritesPending;
}
/** Write all config pages to EEPROM.
*/
void writeAllConfig()
{
uint8_t pageCount = getPageCount();
uint8_t page = 1U;
writeConfig(page++);
while (page<pageCount && !eepromWritesPending)
{
writeConfig(page++);
}
}
// ================================= Internal write support ===============================
typedef struct write_location {
eeprom_address_t address;
uint8_t counter;
} write_location;
/** Update byte to EEPROM by first comparing content and the need to write it.
We only ever write to the EEPROM where the new value is different from the currently stored byte
This is due to the limited write life of the EEPROM (Approximately 100,000 writes)
*/
static inline write_location update(uint8_t value, write_location location)
{
if (EEPROM.read(location.address)!=value)
{
EEPROM.write(location.address, value);
++location.counter;
}
return location;
}
static inline write_location write_range(const byte *pStart, const byte *pEnd, write_location location)
{
while (location.counter<=EEPROM_MAX_WRITE_BLOCK && pStart!=pEnd)
{
location = update(*pStart, location);
++pStart; ++location.address;
}
return location;
}
static inline write_location write(const table_row_t &row, write_location location)
{
return write_range(row.pValue, row.pEnd, location);
}
static inline write_location write(table_row_iterator_t it, write_location location)
{
while ((location.counter<=EEPROM_MAX_WRITE_BLOCK) && !at_end(it))
{
location = write(get_row(it), location);
it = advance_row(it);
}
return location;
}
static inline write_location write(table_axis_iterator_t it, write_location location)
{
while ((location.counter<=EEPROM_MAX_WRITE_BLOCK) && !at_end(it))
{
location = update(get_value(it), location);
++location.address;
it = advance_axis(it);
}
return location;
}
static inline write_location writeTable(const table3D *pTable, write_location location)
{
return write(y_rbegin(pTable),
write(x_begin(pTable),
write(rows_begin(pTable), location)));
}
// ================================= End write support ===============================
/** Write a table or map to EEPROM storage.
Takes the current configuration (config pages and maps)
and writes them to EEPROM as per the layout defined in storage.h.
*/
void writeConfig(uint8_t pageNum)
{
write_location result = { 0, 0 };
switch(pageNum)
{
case veMapPage:
/*---------------------------------------------------
| Fuel table (See storage.h for data layout) - Page 1
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&fuelTable, { EEPROM_CONFIG1_MAP, 0 } );
break;
case veSetPage:
/*---------------------------------------------------
| Config page 2 (See storage.h for data layout)
| 64 byte long config table
-----------------------------------------------------*/
result = write_range((byte *)&configPage2, (byte *)&configPage2+sizeof(configPage2), { EEPROM_CONFIG2_START, 0 });
break;
case ignMapPage:
/*---------------------------------------------------
| Ignition table (See storage.h for data layout) - Page 1
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&ignitionTable, { EEPROM_CONFIG3_MAP, 0 });
break;
case ignSetPage:
/*---------------------------------------------------
| Config page 2 (See storage.h for data layout)
| 64 byte long config table
-----------------------------------------------------*/
result = write_range((byte *)&configPage4, (byte *)&configPage4+sizeof(configPage4), { EEPROM_CONFIG4_START, 0 });
break;
case afrMapPage:
/*---------------------------------------------------
| AFR table (See storage.h for data layout) - Page 5
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&afrTable, {EEPROM_CONFIG5_MAP, 0} );
break;
case afrSetPage:
/*---------------------------------------------------
| Config page 3 (See storage.h for data layout)
| 64 byte long config table
-----------------------------------------------------*/
result = write_range((byte *)&configPage6, (byte *)&configPage6+sizeof(configPage6), { EEPROM_CONFIG6_START, 0 });
break;
case boostvvtPage:
/*---------------------------------------------------
| Boost and vvt tables (See storage.h for data layout) - Page 8
| 8x8 table itself + the 8 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&boostTable, { EEPROM_CONFIG7_MAP1, 0 });
result = writeTable(&vvtTable, { EEPROM_CONFIG7_MAP2, result.counter });
result = writeTable(&stagingTable, { EEPROM_CONFIG7_MAP3, result.counter });
break;
case seqFuelPage:
/*---------------------------------------------------
| Fuel trim tables (See storage.h for data layout) - Page 9
| 6x6 tables itself + the 6 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&trim1Table, { EEPROM_CONFIG8_MAP1, 0} );
result = writeTable(&trim2Table, { EEPROM_CONFIG8_MAP2, result.counter});
result = writeTable(&trim3Table, { EEPROM_CONFIG8_MAP3, result.counter});
result = writeTable(&trim4Table, { EEPROM_CONFIG8_MAP4, result.counter});
result = writeTable(&trim5Table, { EEPROM_CONFIG8_MAP5, result.counter});
result = writeTable(&trim6Table, { EEPROM_CONFIG8_MAP6, result.counter});
result = writeTable(&trim7Table, { EEPROM_CONFIG8_MAP7, result.counter});
result = writeTable(&trim8Table, { EEPROM_CONFIG8_MAP8, result.counter});
break;
case canbusPage:
/*---------------------------------------------------
| Config page 10 (See storage.h for data layout)
| 192 byte long config table
-----------------------------------------------------*/
result = write_range((byte *)&configPage9, (byte *)&configPage9+sizeof(configPage9), { EEPROM_CONFIG9_START, 0 });
break;
case warmupPage:
/*---------------------------------------------------
| Config page 11 (See storage.h for data layout)
| 192 byte long config table
-----------------------------------------------------*/
result = write_range((byte *)&configPage10, (byte *)&configPage10+sizeof(configPage10), { EEPROM_CONFIG10_START, 0});
break;
case fuelMap2Page:
/*---------------------------------------------------
| Fuel table 2 (See storage.h for data layout)
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&fuelTable2, { EEPROM_CONFIG11_MAP, 0 });
break;
case wmiMapPage:
/*---------------------------------------------------
| WMI and Dwell tables (See storage.h for data layout) - Page 12
| 8x8 WMI table itself + the 8 values along each of the axis
| 8x8 VVT2 table + the 8 values along each of the axis
| 4x4 Dwell table itself + the 4 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&wmiTable, { EEPROM_CONFIG12_MAP, 0 });
result = writeTable(&vvt2Table, { EEPROM_CONFIG12_MAP2, result.counter});
result = writeTable(&dwellTable, { EEPROM_CONFIG12_MAP3, result.counter});
break;
case progOutsPage:
/*---------------------------------------------------
| Config page 13 (See storage.h for data layout)
-----------------------------------------------------*/
result = write_range((byte *)&configPage13, (byte *)&configPage13+sizeof(configPage13), { EEPROM_CONFIG13_START, 0});
break;
case ignMap2Page:
/*---------------------------------------------------
| Ignition table (See storage.h for data layout) - Page 1
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
result = writeTable(&ignitionTable2, { EEPROM_CONFIG14_MAP, 0});
break;
default:
break;
}
eepromWritesPending = result.counter > EEPROM_MAX_WRITE_BLOCK;
}
/** Reset all configPage* structs (2,4,6,9,10,13) and write them full of null-bytes.
*/
void resetConfigPages()
{
for (uint8_t page=1; page<getPageCount(); ++page)
{
page_iterator_t entity = page_begin(page);
while (entity.type!=End)
{
if (entity.type==Raw)
{
memset(entity.pData, 0, entity.size);
}
entity = advance(entity);
}
}
}
// ================================= Internal read support ===============================
/** Load range of bytes form EEPROM offset to memory.
* @param address - start offset in EEPROM
* @param pFirst - Start memory address
* @param pLast - End memory address
*/
static inline eeprom_address_t load_range(eeprom_address_t address, byte *pFirst, const byte *pLast)
{
for (; pFirst != pLast; ++address, (void)++pFirst)
{
*pFirst = EEPROM.read(address);
}
return address;
}
static inline eeprom_address_t load(table_row_t row, eeprom_address_t address)
{
return load_range(address, row.pValue, row.pEnd);
}
static inline eeprom_address_t load(table_row_iterator_t it, eeprom_address_t address)
{
while (!at_end(it))
{
address = load(get_row(it), address);
it = advance_row(it);
}
return address;
}
static inline eeprom_address_t load(table_axis_iterator_t it, eeprom_address_t address)
{
while (!at_end(it))
{
set_value(it, EEPROM.read(address));
++address;
it = advance_axis(it);
}
return address;
}
static inline eeprom_address_t loadTable(table3D *pTable, eeprom_address_t address)
{
return load(y_rbegin(pTable),
load(x_begin(pTable),
load(rows_begin(pTable), address)));
}
// ================================= End internal read support ===============================
/** Load all config tables from storage.
*/
void loadConfig()
{
loadTable(&fuelTable, EEPROM_CONFIG1_MAP);
load_range(EEPROM_CONFIG2_START, (byte *)&configPage2, (byte *)&configPage2+sizeof(configPage2));
//*********************************************************************************************************************************************************************************
//IGNITION CONFIG PAGE (2)
loadTable(&ignitionTable, EEPROM_CONFIG3_MAP);
load_range(EEPROM_CONFIG4_START, (byte *)&configPage4, (byte *)&configPage4+sizeof(configPage4));
//*********************************************************************************************************************************************************************************
//AFR TARGET CONFIG PAGE (3)
loadTable(&afrTable, EEPROM_CONFIG5_MAP);
load_range(EEPROM_CONFIG6_START, (byte *)&configPage6, (byte *)&configPage6+sizeof(configPage6));
//*********************************************************************************************************************************************************************************
// Boost and vvt tables load
loadTable(&boostTable, EEPROM_CONFIG7_MAP1);
loadTable(&vvtTable, EEPROM_CONFIG7_MAP2);
loadTable(&stagingTable, EEPROM_CONFIG7_MAP3);
//*********************************************************************************************************************************************************************************
// Fuel trim tables load
loadTable(&trim1Table, EEPROM_CONFIG8_MAP1);
loadTable(&trim2Table, EEPROM_CONFIG8_MAP2);
loadTable(&trim3Table, EEPROM_CONFIG8_MAP3);
loadTable(&trim4Table, EEPROM_CONFIG8_MAP4);
loadTable(&trim5Table, EEPROM_CONFIG8_MAP5);
loadTable(&trim6Table, EEPROM_CONFIG8_MAP6);
loadTable(&trim7Table, EEPROM_CONFIG8_MAP7);
loadTable(&trim8Table, EEPROM_CONFIG8_MAP8);
//*********************************************************************************************************************************************************************************
//canbus control page load
load_range(EEPROM_CONFIG9_START, (byte *)&configPage9, (byte *)&configPage9+sizeof(configPage9));
//*********************************************************************************************************************************************************************************
//CONFIG PAGE (10)
load_range(EEPROM_CONFIG10_START, (byte *)&configPage10, (byte *)&configPage10+sizeof(configPage10));
//*********************************************************************************************************************************************************************************
//Fuel table 2 (See storage.h for data layout)
loadTable(&fuelTable2, EEPROM_CONFIG11_MAP);
//*********************************************************************************************************************************************************************************
// WMI, VVT2 and Dwell table load
loadTable(&wmiTable, EEPROM_CONFIG12_MAP);
loadTable(&vvt2Table, EEPROM_CONFIG12_MAP2);
loadTable(&dwellTable, EEPROM_CONFIG12_MAP3);
//*********************************************************************************************************************************************************************************
//CONFIG PAGE (13)
load_range(EEPROM_CONFIG13_START, (byte *)&configPage13, (byte *)&configPage13+sizeof(configPage13));
//*********************************************************************************************************************************************************************************
//SECOND IGNITION CONFIG PAGE (14)
loadTable(&ignitionTable2, EEPROM_CONFIG14_MAP);
//*********************************************************************************************************************************************************************************
}
/** Read the calibration information from EEPROM.
This is separate from the config load as the calibrations do not exist as pages within the ini file for Tuner Studio.
*/
void loadCalibration()
{
// If you modify this function be sure to also modify writeCalibration();
// it should be a mirror image of this function.
EEPROM.get(EEPROM_CALIBRATION_O2_BINS, o2Calibration_bins);
EEPROM.get(EEPROM_CALIBRATION_O2_VALUES, o2Calibration_values);
EEPROM.get(EEPROM_CALIBRATION_IAT_BINS, iatCalibration_bins);
EEPROM.get(EEPROM_CALIBRATION_IAT_VALUES, iatCalibration_values);
EEPROM.get(EEPROM_CALIBRATION_CLT_BINS, cltCalibration_bins);
EEPROM.get(EEPROM_CALIBRATION_CLT_VALUES, cltCalibration_values);
}
/** Write calibration tables to EEPROM.
This takes the values in the 3 calibration tables (Coolant, Inlet temp and O2)
and saves them to the EEPROM.
*/
void writeCalibration()
{
// If you modify this function be sure to also modify loadCalibration();
// it should be a mirror image of this function.
EEPROM.put(EEPROM_CALIBRATION_O2_BINS, o2Calibration_bins);
EEPROM.put(EEPROM_CALIBRATION_O2_VALUES, o2Calibration_values);
EEPROM.put(EEPROM_CALIBRATION_IAT_BINS, iatCalibration_bins);
EEPROM.put(EEPROM_CALIBRATION_IAT_VALUES, iatCalibration_values);
EEPROM.put(EEPROM_CALIBRATION_CLT_BINS, cltCalibration_bins);
EEPROM.put(EEPROM_CALIBRATION_CLT_VALUES, cltCalibration_values);
}
static eeprom_address_t compute_crc_address(uint8_t pageNum)
{
return EEPROM_LAST_BARO-((getPageCount() - pageNum)*sizeof(uint32_t));
}
/** Write CRC32 checksum to EEPROM.
Takes a page number and CRC32 value then stores it in the relevant place in EEPROM
@param pageNo - Config page number
@param crc32_val - CRC32 checksum
*/
void storePageCRC32(uint8_t pageNum, uint32_t crcValue)
{
EEPROM.put(compute_crc_address(pageNum), crcValue);
}
/** Retrieves and returns the 4 byte CRC32 checksum for a given page from EEPROM.
@param pageNo - Config page number
*/
uint32_t readPageCRC32(uint8_t pageNum)
{
uint32_t crc32_val;
return EEPROM.get(compute_crc_address(pageNum), crc32_val);
}
// Utility functions.
// By having these in this file, it prevents other files from calling EEPROM functions directly. This is useful due to differences in the EEPROM libraries on different devces
/// Read last stored barometer reading from EEPROM.
byte readLastBaro() { return EEPROM.read(EEPROM_LAST_BARO); }
/// Write last acquired arometer reading to EEPROM.
void storeLastBaro(byte newValue) { EEPROM.update(EEPROM_LAST_BARO, newValue); }
/// Read EEPROM current data format version (from offset EEPROM_DATA_VERSION).
byte readEEPROMVersion() { return EEPROM.read(EEPROM_DATA_VERSION); }
/// Store EEPROM current data format version (to offset EEPROM_DATA_VERSION).
void storeEEPROMVersion(byte newVersion) { EEPROM.update(EEPROM_DATA_VERSION, newVersion); }

View File

@ -1,32 +1,22 @@
#ifndef STORAGE_H
#define STORAGE_H
#include "globals.h"
void writeAllConfig();
void writeConfig(byte);
void writeConfig(uint8_t pageNum);
void loadConfig();
void loadCalibration();
void writeCalibration();
void loadCalibration_new();
void writeCalibration_new();
void resetConfigPages();
//These are utility functions that prevent other files from having to use EEPROM.h directly
byte readLastBaro();
void storeLastBaro(byte);
void storeCalibrationValue(uint16_t, byte);
byte readEEPROMVersion();
void storeEEPROMVersion(byte);
void storePageCRC32(byte, uint32_t);
uint32_t readPageCRC32(byte);
uint8_t readEEPROMVersion();
void storeEEPROMVersion(uint8_t);
void storePageCRC32(uint8_t pageNum, uint32_t crcValue);
uint32_t readPageCRC32(uint8_t pageNum);
#if defined(CORE_STM32) || defined(CORE_TEENSY) & !defined(USE_SPI_EEPROM)
#define EEPROM_MAX_WRITE_BLOCK 64 //The maximum number of write operations that will be performed in one go. If we try to write to the EEPROM too fast (Each write takes ~3ms) then the rest of the system can hang)
#else
#define EEPROM_MAX_WRITE_BLOCK 30 //The maximum number of write operations that will be performed in one go. If we try to write to the EEPROM too fast (Each write takes ~3ms) then the rest of the system can hang)
#endif
extern bool eepromWritesPending;
bool isEepromWritePending();
/*
Current layout of EEPROM data (Version 3) is as follows (All sizes are in bytes):
@ -85,129 +75,43 @@ Current layout of EEPROM data (Version 3) is as follows (All sizes are in bytes)
-----------------------------------------------------
*/
#define EEPROM_DATA_VERSION 0
#define EEPROM_CONFIG1_XSIZE 1
#define EEPROM_CONFIG1_YSIZE 2
#define EEPROM_CONFIG1_MAP 3
#define EEPROM_CONFIG1_XBINS 259
#define EEPROM_CONFIG1_YBINS 275
#define EEPROM_CONFIG2_START 291
#define EEPROM_CONFIG2_END 419
#define EEPROM_CONFIG3_XSIZE 419
#define EEPROM_CONFIG3_YSIZE 420
#define EEPROM_CONFIG3_MAP 421
#define EEPROM_CONFIG3_XBINS 677
#define EEPROM_CONFIG3_YBINS 693
#define EEPROM_CONFIG4_START 709
#define EEPROM_CONFIG4_END 837
#define EEPROM_CONFIG5_XSIZE 837
#define EEPROM_CONFIG5_YSIZE 838
#define EEPROM_CONFIG5_MAP 839
#define EEPROM_CONFIG5_XBINS 1095
#define EEPROM_CONFIG5_YBINS 1111
#define EEPROM_CONFIG6_START 1127
#define EEPROM_CONFIG6_END 1255
#define EEPROM_CONFIG7_XSIZE1 1255
#define EEPROM_CONFIG7_YSIZE1 1256
#define EEPROM_CONFIG7_MAP1 1257
#define EEPROM_CONFIG7_XBINS1 1321
#define EEPROM_CONFIG7_YBINS1 1329
#define EEPROM_CONFIG7_XSIZE2 1337
#define EEPROM_CONFIG7_YSIZE2 1338
#define EEPROM_CONFIG7_MAP2 1339
#define EEPROM_CONFIG7_XBINS2 1403
#define EEPROM_CONFIG7_YBINS2 1411
#define EEPROM_CONFIG7_XSIZE3 1419
#define EEPROM_CONFIG7_YSIZE3 1420
#define EEPROM_CONFIG7_MAP3 1421
#define EEPROM_CONFIG7_XBINS3 1485
#define EEPROM_CONFIG7_YBINS3 1493
#define EEPROM_CONFIG7_END 1501
#define EEPROM_CONFIG8_XSIZE1 1501
#define EEPROM_CONFIG8_YSIZE1 1502
#define EEPROM_CONFIG8_MAP1 1503
#define EEPROM_CONFIG8_XBINS1 1539
#define EEPROM_CONFIG8_YBINS1 1545
#define EEPROM_CONFIG8_XSIZE2 1551
#define EEPROM_CONFIG8_YSIZE2 1552
#define EEPROM_CONFIG8_MAP2 1553
#define EEPROM_CONFIG8_XBINS2 1589
#define EEPROM_CONFIG8_YBINS2 1595
#define EEPROM_CONFIG8_XSIZE3 1601
#define EEPROM_CONFIG8_YSIZE3 1602
#define EEPROM_CONFIG8_MAP3 1603
#define EEPROM_CONFIG8_XBINS3 1639
#define EEPROM_CONFIG8_YBINS3 1645
#define EEPROM_CONFIG8_XSIZE4 1651
#define EEPROM_CONFIG8_YSIZE4 1652
#define EEPROM_CONFIG8_MAP4 1653
#define EEPROM_CONFIG8_XBINS4 1689
#define EEPROM_CONFIG8_YBINS4 1695
#define EEPROM_CONFIG9_START 1710
#define EEPROM_CONFIG9_END 1902
#define EEPROM_CONFIG10_START 1902
#define EEPROM_CONFIG10_END 2094
#define EEPROM_CONFIG11_XSIZE 2094
#define EEPROM_CONFIG11_YSIZE 2095
#define EEPROM_CONFIG11_MAP 2096
#define EEPROM_CONFIG11_XBINS 2352
#define EEPROM_CONFIG11_YBINS 2369
#define EEPROM_CONFIG11_END 2385
#define EEPROM_CONFIG12_XSIZE 2385
#define EEPROM_CONFIG12_YSIZE 2386
#define EEPROM_CONFIG12_MAP 2387
#define EEPROM_CONFIG12_XBINS 2451
#define EEPROM_CONFIG12_YBINS 2459
#define EEPROM_CONFIG12_XSIZE2 2467
#define EEPROM_CONFIG12_YSIZE2 2468
#define EEPROM_CONFIG12_MAP2 2469
#define EEPROM_CONFIG12_XBINS2 2533
#define EEPROM_CONFIG12_YBINS2 2541
#define EEPROM_CONFIG12_XSIZE3 2549
#define EEPROM_CONFIG12_YSIZE3 2550
#define EEPROM_CONFIG12_MAP3 2551
#define EEPROM_CONFIG12_XBINS3 2567
#define EEPROM_CONFIG12_YBINS3 2571
#define EEPROM_CONFIG12_END 2575
#define EEPROM_CONFIG13_START 2580
#define EEPROM_CONFIG13_END 2708
#define EEPROM_CONFIG14_XSIZE 2708
#define EEPROM_CONFIG14_YSIZE 2709
#define EEPROM_CONFIG14_MAP 2710
#define EEPROM_CONFIG14_XBINS 2966
#define EEPROM_CONFIG14_YBINS 2982
#define EEPROM_CONFIG14_END 2998
//This is OUT OF ORDER as Table 8 was expanded to add fuel trim 5-8. The EEPROM for them is simply added here so as not to impact existing tunes
#define EEPROM_CONFIG8_XSIZE5 2999
#define EEPROM_CONFIG8_YSIZE5 3000
#define EEPROM_CONFIG8_MAP5 3001
#define EEPROM_CONFIG8_XBINS5 3037
#define EEPROM_CONFIG8_YBINS5 3043
#define EEPROM_CONFIG8_XSIZE6 3049
#define EEPROM_CONFIG8_YSIZE6 3050
#define EEPROM_CONFIG8_MAP6 3051
#define EEPROM_CONFIG8_XBINS6 3087
#define EEPROM_CONFIG8_YBINS6 3093
#define EEPROM_CONFIG8_XSIZE7 3099
#define EEPROM_CONFIG8_YSIZE7 3100
#define EEPROM_CONFIG8_MAP7 3101
#define EEPROM_CONFIG8_XBINS7 3137
#define EEPROM_CONFIG8_YBINS7 3143
#define EEPROM_CONFIG8_XSIZE8 3149
#define EEPROM_CONFIG8_YSIZE8 3150
#define EEPROM_CONFIG8_MAP8 3151
#define EEPROM_CONFIG8_XBINS8 3187
#define EEPROM_CONFIG8_YBINS8 3193
//Calibration data is stored at the end of the EEPROM (This is in case any further calibration tables are needed as they are large blocks)
#define EEPROM_PAGE_CRC32 3686 //Size of this is 4 * <number of pages> (CRC32 = 32 bits): 3742 - (14 * 4) = 3686
#define EEPROM_LAST_BARO 3742 // 3743 - 1
//New values using 2D tables
#define EEPROM_CALIBRATION_O2 3743 //3839-96 +64
#define EEPROM_CALIBRATION_IAT 3839 //3967-128
#define EEPROM_CALIBRATION_CLT 3967 //4095-128
//These were the values used previously when all calibration tables were 512 long. They need to be retained for the update process (202005 -> 202008) can work.
#define EEPROM_CALIBRATION_O2_OLD 2559
#define EEPROM_CALIBRATION_IAT_OLD 3071

View File

@ -1,532 +0,0 @@
/*
Speeduino - Simple engine management for the Arduino Mega 2560 platform
Copyright (C) Josh Stewart
A full copy of the license may be found in the projects root directory
*/
/** @file
* Lower level ConfigPage*, Table2D, Table3D and EEPROM storage operations.
*/
#include "globals.h"
#include "table.h"
#include "comms.h" // Is this needed at all ?
#include EEPROM_LIB_H //This is defined in the board .h files
#include "storage.h"
#include "table_iterator.h"
bool eepromWritesPending = false;
/** Write all config pages to EEPROM.
*/
void writeAllConfig()
{
writeConfig(veSetPage);
if (eepromWritesPending == false) { writeConfig(veMapPage); }
if (eepromWritesPending == false) { writeConfig(ignMapPage); }
if (eepromWritesPending == false) { writeConfig(ignSetPage); }
if (eepromWritesPending == false) { writeConfig(afrMapPage); }
if (eepromWritesPending == false) { writeConfig(afrSetPage); }
if (eepromWritesPending == false) { writeConfig(boostvvtPage); }
if (eepromWritesPending == false) { writeConfig(seqFuelPage); }
if (eepromWritesPending == false) { writeConfig(canbusPage); }
if (eepromWritesPending == false) { writeConfig(warmupPage); }
if (eepromWritesPending == false) { writeConfig(fuelMap2Page); }
if (eepromWritesPending == false) { writeConfig(wmiMapPage); }
if (eepromWritesPending == false) { writeConfig(progOutsPage); }
if (eepromWritesPending == false) { writeConfig(ignMap2Page); }
}
namespace {
/** Update byte to EEPROM by first comparing content and the need to write it.
We only ever write to the EEPROM where the new value is different from the currently stored byte
This is due to the limited write life of the EEPROM (Approximately 100,000 writes)
*/
inline int16_t update(int index, uint8_t value, int16_t counter)
{
if (EEPROM.read(index)!=value)
{
EEPROM.write(index, value);
return counter+1;
}
return counter;
}
inline int16_t write_range_divisor(int &index, int8_t divisor, int16_t *pStart, const int16_t *pEnd, int16_t counter)
{
while (counter<=EEPROM_MAX_WRITE_BLOCK && pStart!=pEnd)
{
counter = update(index, (*pStart)/divisor, counter);
++pStart; ++index;
}
return counter;
}
inline int16_t write_range(int &index, byte *pStart, const byte *pEnd, int16_t counter)
{
while (counter<=EEPROM_MAX_WRITE_BLOCK && pStart!=pEnd)
{
counter = update(index, *pStart, counter);
++pStart; ++index;
}
return counter;
}
inline int16_t writeTableValues(const table3D *pTable, int &index, int16_t counter)
{
byte **pRow = pTable->values + (pTable->xSize-1);
byte **pRowEnd = pTable->values - 1;
int rowSize = pTable->xSize;
while (counter<=EEPROM_MAX_WRITE_BLOCK && pRow!=pRowEnd)
{
counter = write_range(index, *pRow, *pRow+rowSize, counter);
--pRow;
}
return counter;
}
inline int16_t writeTable(const table3D *pTable, int &index, int16_t counter)
{
counter = update(index, pTable->xSize, counter); ++index;
counter = update(index, pTable->ySize, counter); ++index;
counter = writeTableValues(pTable, index, counter);
counter = write_range_divisor(index, getTableXAxisFactor(pTable), pTable->axisX, pTable->axisX+pTable->xSize, counter);
return write_range_divisor(index, getTableYAxisFactor(pTable), pTable->axisY, pTable->axisY+pTable->ySize, counter);
}
}
/** Write a table or map to EEPROM storage.
Takes the current configuration (config pages and maps)
and writes them to EEPROM as per the layout defined in storage.h.
*/
void writeConfig(byte tableNum)
{
/*
We only ever write to the EEPROM where the new value is different from the currently stored byte
This is due to the limited write life of the EEPROM (Approximately 100,000 writes)
*/
int writeCounter = 0;
int index;
switch(tableNum)
{
case veMapPage:
/*---------------------------------------------------
| Fuel table (See storage.h for data layout) - Page 1
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
index = EEPROM_CONFIG1_XSIZE;
writeCounter = writeTable(&fuelTable, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
//That concludes the writing of the VE table
case veSetPage:
/*---------------------------------------------------
| Config page 2 (See storage.h for data layout)
| 64 byte long config table
-----------------------------------------------------*/
index = EEPROM_CONFIG2_START;
writeCounter = write_range(index, (byte *)&configPage2, (byte *)&configPage2+sizeof(configPage2), writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case ignMapPage:
/*---------------------------------------------------
| Ignition table (See storage.h for data layout) - Page 1
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
//Begin writing the Ignition table, basically the same thing as above
index = EEPROM_CONFIG3_XSIZE;
writeCounter = writeTable(&ignitionTable, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case ignSetPage:
/*---------------------------------------------------
| Config page 2 (See storage.h for data layout)
| 64 byte long config table
-----------------------------------------------------*/
index = EEPROM_CONFIG4_START;
writeCounter = write_range(index, (byte *)&configPage4, (byte *)&configPage4+sizeof(configPage4), writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case afrMapPage:
/*---------------------------------------------------
| AFR table (See storage.h for data layout) - Page 5
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
//Begin writing the Ignition table, basically the same thing as above
index = EEPROM_CONFIG5_XSIZE;
writeCounter = writeTable(&afrTable, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case afrSetPage:
/*---------------------------------------------------
| Config page 3 (See storage.h for data layout)
| 64 byte long config table
-----------------------------------------------------*/
index = EEPROM_CONFIG6_START;
writeCounter = write_range(index, (byte *)&configPage6, (byte *)&configPage6+sizeof(configPage6), writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case boostvvtPage:
/*---------------------------------------------------
| Boost and vvt tables (See storage.h for data layout) - Page 8
| 8x8 table itself + the 8 values along each of the axis
-----------------------------------------------------*/
//Begin writing the 2 tables, basically the same thing as above but we're doing these 2 together (2 tables per page instead of 1)
index = EEPROM_CONFIG7_XSIZE1;
writeCounter = writeTable(&boostTable, index, writeCounter);
index = EEPROM_CONFIG7_XSIZE2;
writeCounter = writeTable(&vvtTable, index, writeCounter);
index = EEPROM_CONFIG7_XSIZE3;
writeCounter = writeTable(&stagingTable, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case seqFuelPage:
/*---------------------------------------------------
| Fuel trim tables (See storage.h for data layout) - Page 9
| 6x6 tables itself + the 6 values along each of the axis
-----------------------------------------------------*/
//Begin writing the 2 tables, basically the same thing as above but we're doing these 2 together (2 tables per page instead of 1)
index = EEPROM_CONFIG8_XSIZE1;
writeCounter = writeTable(&trim1Table, index, writeCounter);
index = EEPROM_CONFIG8_XSIZE2;
writeCounter = writeTable(&trim2Table, index, writeCounter);
index = EEPROM_CONFIG8_XSIZE3;
writeCounter = writeTable(&trim3Table, index, writeCounter);
index = EEPROM_CONFIG8_XSIZE4;
writeCounter = writeTable(&trim4Table, index, writeCounter);
index = EEPROM_CONFIG8_XSIZE5;
writeCounter = writeTable(&trim5Table, index, writeCounter);
index = EEPROM_CONFIG8_XSIZE6;
writeCounter = writeTable(&trim6Table, index, writeCounter);
index = EEPROM_CONFIG8_XSIZE7;
writeCounter = writeTable(&trim7Table, index, writeCounter);
index = EEPROM_CONFIG8_XSIZE8;
writeCounter = writeTable(&trim8Table, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case canbusPage:
/*---------------------------------------------------
| Config page 10 (See storage.h for data layout)
| 192 byte long config table
-----------------------------------------------------*/
index = EEPROM_CONFIG9_START;
writeCounter = write_range(index, (byte *)&configPage9, (byte *)&configPage9+sizeof(configPage9), writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case warmupPage:
/*---------------------------------------------------
| Config page 11 (See storage.h for data layout)
| 192 byte long config table
-----------------------------------------------------*/
index = EEPROM_CONFIG10_START;
writeCounter = write_range(index, (byte *)&configPage10, (byte *)&configPage10+sizeof(configPage10), writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case fuelMap2Page:
/*---------------------------------------------------
| Fuel table 2 (See storage.h for data layout)
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
index = EEPROM_CONFIG11_XSIZE;
writeCounter = writeTable(&fuelTable2, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
//That concludes the writing of the 2nd fuel table
case wmiMapPage:
/*---------------------------------------------------
| WMI and Dwell tables (See storage.h for data layout) - Page 12
| 8x8 WMI table itself + the 8 values along each of the axis
| 8x8 VVT2 table + the 8 values along each of the axis
| 4x4 Dwell table itself + the 4 values along each of the axis
-----------------------------------------------------*/
index = EEPROM_CONFIG12_XSIZE;
writeCounter = writeTable(&wmiTable, index, writeCounter);
index = EEPROM_CONFIG12_XSIZE2;
writeCounter = writeTable(&vvt2Table, index, writeCounter);
index = EEPROM_CONFIG12_XSIZE3;
writeCounter = writeTable(&dwellTable, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case progOutsPage:
/*---------------------------------------------------
| Config page 13 (See storage.h for data layout)
-----------------------------------------------------*/
index = EEPROM_CONFIG13_START;
writeCounter = write_range(index, (byte *)&configPage13, (byte *)&configPage13+sizeof(configPage13), writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
case ignMap2Page:
/*---------------------------------------------------
| Ignition table (See storage.h for data layout) - Page 1
| 16x16 table itself + the 16 values along each of the axis
-----------------------------------------------------*/
//Begin writing the Ignition table, basically the same thing as above
index = EEPROM_CONFIG14_XSIZE;
writeCounter = writeTable(&ignitionTable2, index, writeCounter);
eepromWritesPending = writeCounter > EEPROM_MAX_WRITE_BLOCK;
break;
default:
break;
}
}
/** Reset all configPage* structs (2,4,6,9,10,13) and write them full of null-bytes.
*/
void resetConfigPages()
{
memset(&configPage2, 0, sizeof(config2));
memset(&configPage4, 0, sizeof(config4));
memset(&configPage6, 0, sizeof(config6));
memset(&configPage9, 0, sizeof(config9));
memset(&configPage10, 0, sizeof(config10));
memset(&configPage13, 0, sizeof(config13));
}
namespace
{
/** Load range of bytes form EEPROM offset to memory.
* @param index - start offset in EEPROM
* @param pFirst - Start memory address
* @param pLast - End memory address
*/
inline int load_range(int index, byte *pFirst, byte *pLast)
{
for (; pFirst != pLast; ++index, (void)++pFirst)
{
*pFirst = EEPROM.read(index);
}
return index;
}
inline int load_range_multiplier(int index, int16_t *pFirst, int16_t *pLast, int16_t multiplier)
{
for (; pFirst != pLast; ++index, (void)++pFirst)
{
*pFirst = EEPROM.read(index) * multiplier;
}
return index;
}
inline int loadTableValues(table3D *pTable, int index)
{
byte **pRow = pTable->values + (pTable->xSize-1);
byte **pRowEnd = pTable->values - 1;
int rowSize = pTable->xSize;
for(; pRow!=pRowEnd; --pRow)
{
index = load_range(index, *pRow, *pRow+rowSize);
}
return index;
}
inline int loadTableAxisX(table3D *pTable, int index)
{
return load_range_multiplier(index, pTable->axisX, pTable->axisX+pTable->xSize, getTableXAxisFactor(pTable));
}
inline int loadTableAxisY(table3D *pTable, int index)
{
return load_range_multiplier(index, pTable->axisY, pTable->axisY+pTable->ySize, getTableYAxisFactor(pTable));
}
inline int loadTable(table3D *pTable, int index)
{
return loadTableAxisY(pTable,
loadTableAxisX(pTable,
loadTableValues(pTable, index)));
}
}
/** Load all config tables from storage.
*/
void loadConfig()
{
loadTable(&fuelTable, EEPROM_CONFIG1_MAP);
load_range(EEPROM_CONFIG2_START, (byte *)&configPage2, (byte *)&configPage2+sizeof(configPage2));
//That concludes the reading of the VE table
//*********************************************************************************************************************************************************************************
//IGNITION CONFIG PAGE (2)
//Begin writing the Ignition table, basically the same thing as above
loadTable(&ignitionTable, EEPROM_CONFIG3_MAP);
load_range(EEPROM_CONFIG4_START, (byte *)&configPage4, (byte *)&configPage4+sizeof(configPage4));
//*********************************************************************************************************************************************************************************
//AFR TARGET CONFIG PAGE (3)
//Begin writing the Ignition table, basically the same thing as above
loadTable(&afrTable, EEPROM_CONFIG5_MAP);
load_range(EEPROM_CONFIG6_START, (byte *)&configPage6, (byte *)&configPage6+sizeof(configPage6));
//*********************************************************************************************************************************************************************************
// Boost and vvt tables load
loadTable(&boostTable, EEPROM_CONFIG7_MAP1);
loadTable(&vvtTable, EEPROM_CONFIG7_MAP2);
loadTable(&stagingTable, EEPROM_CONFIG7_MAP3);
//*********************************************************************************************************************************************************************************
// Fuel trim tables load
loadTable(&trim1Table, EEPROM_CONFIG8_MAP1);
loadTable(&trim2Table, EEPROM_CONFIG8_MAP2);
loadTable(&trim3Table, EEPROM_CONFIG8_MAP3);
loadTable(&trim4Table, EEPROM_CONFIG8_MAP4);
loadTable(&trim5Table, EEPROM_CONFIG8_MAP5);
loadTable(&trim6Table, EEPROM_CONFIG8_MAP6);
loadTable(&trim7Table, EEPROM_CONFIG8_MAP7);
loadTable(&trim8Table, EEPROM_CONFIG8_MAP8);
//*********************************************************************************************************************************************************************************
//canbus control page load
load_range(EEPROM_CONFIG9_START, (byte *)&configPage9, (byte *)&configPage9+sizeof(configPage9));
//*********************************************************************************************************************************************************************************
//CONFIG PAGE (10)
load_range(EEPROM_CONFIG10_START, (byte *)&configPage10, (byte *)&configPage10+sizeof(configPage10));
//*********************************************************************************************************************************************************************************
//Fuel table 2 (See storage.h for data layout)
loadTable(&fuelTable2, EEPROM_CONFIG11_MAP);
//*********************************************************************************************************************************************************************************
// WMI, VVT2 and Dwell table load
loadTable(&wmiTable, EEPROM_CONFIG12_MAP);
loadTable(&vvt2Table, EEPROM_CONFIG12_MAP2);
loadTable(&dwellTable, EEPROM_CONFIG12_MAP3);
//*********************************************************************************************************************************************************************************
//CONFIG PAGE (13)
load_range(EEPROM_CONFIG13_START, (byte *)&configPage13, (byte *)&configPage13+sizeof(configPage13));
//*********************************************************************************************************************************************************************************
//SECOND IGNITION CONFIG PAGE (14)
//Begin writing the Ignition table, basically the same thing as above
loadTable(&ignitionTable2, EEPROM_CONFIG14_MAP);
//*********************************************************************************************************************************************************************************
}
/** Read the calibration information from EEPROM.
This is separate from the config load as the calibrations do not exist as pages within the ini file for Tuner Studio.
*/
void loadCalibration()
{
for(int x=0; x<32; x++) //Each calibration table is 32 bytes long
{
int y = EEPROM_CALIBRATION_CLT + (x * 2);
EEPROM.get(y, cltCalibration_bins[x]);
y += 64;
EEPROM.get(y, cltCalibration_values[x]);
y = EEPROM_CALIBRATION_IAT + (x * 2);
EEPROM.get(y, iatCalibration_bins[x]);
y += 64;
EEPROM.get(y, iatCalibration_values[x]);
y = EEPROM_CALIBRATION_O2 + (x * 2);
EEPROM.get(y, o2Calibration_bins[x]);
y = EEPROM_CALIBRATION_O2 + 64 + x;
o2Calibration_values[x] = EEPROM.read(y); //Byte values
}
}
/** Write calibration tables to EEPROM.
This takes the values in the 3 calibration tables (Coolant, Inlet temp and O2)
and saves them to the EEPROM.
*/
void writeCalibration()
{
for(int x=0; x<32; x++) //Each calibration table is 32 bytes long
{
int y = EEPROM_CALIBRATION_CLT + (x * 2);
EEPROM.put(y, cltCalibration_bins[x]);
y += 64;
EEPROM.put(y, cltCalibration_values[x]);
y = EEPROM_CALIBRATION_IAT + (x * 2);
EEPROM.put(y, iatCalibration_bins[x]);
y += 64;
EEPROM.put(y, iatCalibration_values[x]);
y = EEPROM_CALIBRATION_O2 + (x * 2);
EEPROM.put(y, o2Calibration_bins[x]);
y = EEPROM_CALIBRATION_O2 + 64 + x;
EEPROM.update(y, o2Calibration_values[x]);
}
}
/** Write CRC32 checksum to EEPROM.
Takes a page number and CRC32 value then stores it in the relevant place in EEPROM
Note: Each pages requires 4 bytes for its CRC32. These are stored in reverse page order (ie the last page is store first in EEPROM).
@param pageNo - Config page number
@param crc32_val - CRC32 checksum
*/
void storePageCRC32(byte pageNo, uint32_t crc32_val)
{
uint16_t address; //Start address for the relevant page
address = EEPROM_PAGE_CRC32 + ((getPageCount() - pageNo) * 4);
//One = Most significant -> Four = Least significant byte
byte four = (crc32_val & 0xFF);
byte three = ((crc32_val >> 8) & 0xFF);
byte two = ((crc32_val >> 16) & 0xFF);
byte one = ((crc32_val >> 24) & 0xFF);
//Write the 4 bytes into the eeprom memory.
EEPROM.update(address, four);
EEPROM.update(address + 1, three);
EEPROM.update(address + 2, two);
EEPROM.update(address + 3, one);
}
/** Retrieves and returns the 4 byte CRC32 checksum for a given page from EEPROM.
@param pageNo - Config page number
*/
uint32_t readPageCRC32(byte pageNo)
{
uint16_t address; //Start address for the relevant page
address = EEPROM_PAGE_CRC32 + ((getPageCount() - pageNo) * 4);
//Read the 4 bytes from the eeprom memory.
uint32_t four = EEPROM.read(address);
uint32_t three = EEPROM.read(address + 1);
uint32_t two = EEPROM.read(address + 2);
uint32_t one = EEPROM.read(address + 3);
//Return the recomposed long by using bitshift.
return ((four << 0) & 0xFF) + ((three << 8) & 0xFFFF) + ((two << 16) & 0xFFFFFF) + ((one << 24) & 0xFFFFFFFF);
}
// Utility functions.
// By having these in this file, it prevents other files from calling EEPROM functions directly. This is useful due to differences in the EEPROM libraries on different devces
/// Read last stored barometer reading from EEPROM.
byte readLastBaro() { return EEPROM.read(EEPROM_LAST_BARO); }
/// Write last acquired arometer reading to EEPROM.
void storeLastBaro(byte newValue) { EEPROM.update(EEPROM_LAST_BARO, newValue); }
/// Store calibration value byte into EEPROM (offset "location").
void storeCalibrationValue(uint16_t location, byte value) { EEPROM.update(location, value); } //This is essentially just an abstraction for EEPROM.update()
/// Read EEPROM current data format version (from offset EEPROM_DATA_VERSION).
byte readEEPROMVersion() { return EEPROM.read(EEPROM_DATA_VERSION); }
/// Store EEPROM current data format version (to offset EEPROM_DATA_VERSION).
void storeEEPROMVersion(byte newVersion) { EEPROM.update(EEPROM_DATA_VERSION, newVersion); }

View File

@ -50,6 +50,11 @@ inline table_axis_iterator_t y_begin(const table3D *pTable)
-1 };
}
inline table_axis_iterator_t y_rbegin(const table3D *pTable)
{
return { pTable->axisY, pTable->axisY + pTable->ySize, getTableYAxisFactor(pTable), 1 };
}
inline table_axis_iterator_t x_begin(const table3D *pTable)
{
return { pTable->axisX, pTable->axisX+pTable->xSize, getTableXAxisFactor(pTable), 1 };

View File

@ -19,7 +19,7 @@ void doUpdates()
#ifndef SMALL_FLASH_MODE
//May 2017 firmware introduced a -40 offset on the ignition table. Update that table to +40
if(EEPROM.read(EEPROM_DATA_VERSION) == 2)
if(readEEPROMVersion() == 2)
{
for(int x=0; x<16; x++)
{
@ -29,11 +29,10 @@ void doUpdates()
}
}
writeAllConfig();
//EEPROM.write(EEPROM_DATA_VERSION, 3);
storeEEPROMVersion(3);
}
//June 2017 required the forced addition of some CAN values to avoid weird errors
if(EEPROM.read(EEPROM_DATA_VERSION) == 3)
if(readEEPROMVersion() == 3)
{
configPage9.speeduino_tsCanId = 0;
configPage9.true_address = 256;
@ -43,11 +42,10 @@ void doUpdates()
if(configPage4.sparkDur == 255) { configPage4.sparkDur = 10; }
writeAllConfig();
//EEPROM.write(EEPROM_DATA_VERSION, 4);
storeEEPROMVersion(4);
}
//July 2017 adds a cranking enrichment curve in place of the single value. This converts that single value to the curve
if(EEPROM.read(EEPROM_DATA_VERSION) == 4)
if(readEEPROMVersion() == 4)
{
//Some default values for the bins (Doesn't matter too much here as the values against them will all be identical)
configPage10.crankingEnrichBins[0] = 0;
@ -61,11 +59,10 @@ void doUpdates()
configPage10.crankingEnrichValues[3] = 100 + configPage2.crankingPct;
writeAllConfig();
//EEPROM.write(EEPROM_DATA_VERSION, 5);
storeEEPROMVersion(5);
}
//September 2017 had a major change to increase the minimum table size to 128. This required multiple pieces of data being moved around
if(EEPROM.read(EEPROM_DATA_VERSION) == 5)
if(readEEPROMVersion() == 5)
{
//Data after page 4 has to move back 128 bytes
for(int x=0; x < 1152; x++)
@ -84,11 +81,11 @@ void doUpdates()
EEPROM.update(endMem, currentVal);
}
EEPROM.write(EEPROM_DATA_VERSION, 6);
storeEEPROMVersion(6);
loadConfig(); //Reload the config after changing everything in EEPROM
}
//November 2017 added the staging table that comes after boost and vvt in the EEPROM. This required multiple pieces of data being moved around
if(EEPROM.read(EEPROM_DATA_VERSION) == 6)
if(readEEPROMVersion() == 6)
{
//Data after page 8 has to move back 82 bytes
for(int x=0; x < 529; x++)
@ -99,11 +96,11 @@ void doUpdates()
EEPROM.update(endMem, currentVal);
}
EEPROM.write(EEPROM_DATA_VERSION, 7);
storeEEPROMVersion(7);
loadConfig(); //Reload the config after changing everything in EEPROM
}
if (EEPROM.read(EEPROM_DATA_VERSION) == 7) {
if (readEEPROMVersion() == 7) {
//Convert whatever flex fuel settings are there into the new tables
configPage10.flexBoostBins[0] = 0;
@ -133,10 +130,10 @@ void doUpdates()
}
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 8);
storeEEPROMVersion(8);
}
if (EEPROM.read(EEPROM_DATA_VERSION) == 8)
if (readEEPROMVersion() == 8)
{
//May 2018 adds separate load sources for fuel and ignition. Copy the existing load alogirthm into Both
configPage2.fuelAlgorithm = configPage2.legacyMAP; //Was configPage2.unused2_38c
@ -146,10 +143,10 @@ void doUpdates()
configPage4.boostType = 1;
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 9);
storeEEPROMVersion(9);
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 9)
if(readEEPROMVersion() == 9)
{
//October 2018 set default values for all the aux in variables (These were introduced in Aug, but no defaults were set then)
//All aux channels set to Off
@ -168,10 +165,10 @@ void doUpdates()
configPage4.ADCFILTER_BARO= 64;
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 10);
storeEEPROMVersion(10);
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 10)
if(readEEPROMVersion() == 10)
{
//May 2019 version adds the use of a 2D table for the priming pulse rather than a single value.
//This sets all the values in the 2D table to be the same as the previous single value
@ -238,10 +235,10 @@ void doUpdates()
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 11);
storeEEPROMVersion(11);
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 11)
if(readEEPROMVersion() == 11)
{
//Sep 2019
//A battery calibration offset value was introduced. Set default value to 0
@ -256,10 +253,10 @@ void doUpdates()
configPage10.fuel2SwitchValue = 7000; //7000 RPM switch point is safe
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 12);
storeEEPROMVersion(12);
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 12)
if(readEEPROMVersion() == 12)
{
//Nov 2019
//New option to only apply voltage correction to dead time. Set existing tunes to use old method
@ -302,10 +299,10 @@ void doUpdates()
configPage4.idleAdvValues[5] = 15;
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 13);
storeEEPROMVersion(13);
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 13)
if(readEEPROMVersion() == 13)
{
//202005
//Cranking enrichment range 0..1275% instead of older 0.255, so need to divide old values by 5
@ -369,12 +366,12 @@ void doUpdates()
configPage2.vssMode = 0;
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 14);
storeEEPROMVersion(14);
//
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 14)
if(readEEPROMVersion() == 14)
{
//202008
@ -435,21 +432,21 @@ void doUpdates()
configPage2.aseTaperTime = 10; //1 second taper
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 15);
storeEEPROMVersion(15);
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 15)
if(readEEPROMVersion() == 15)
{
//202012
configPage10.spark2Mode = 0; //Disable 2nd spark table
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 16);
storeEEPROMVersion(16);
}
//Move this #endif to only do latest updates to safe ROM space on small devices.
#endif
if(EEPROM.read(EEPROM_DATA_VERSION) == 16)
if(readEEPROMVersion() == 16)
{
//Fix for wrong placed page 13
for(int x=EEPROM_CONFIG14_END; x>=EEPROM_CONFIG13_START; x--)
@ -461,10 +458,10 @@ void doUpdates()
configPage2.useDwellMap = 0; //Dwell map added, use old fixed value as default
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 17);
storeEEPROMVersion(17);
}
if(EEPROM.read(EEPROM_DATA_VERSION) == 17)
if(readEEPROMVersion() == 17)
{
//VVT stuff has now 0.5 accurasy, so shift values in vvt table by one.
for(int x=0; x<8; x++)
@ -509,11 +506,11 @@ void doUpdates()
configPage13.outputTimeLimit[7] = 0;
writeAllConfig();
EEPROM.write(EEPROM_DATA_VERSION, 18);
storeEEPROMVersion(18);
}
//Final check is always for 255 and 0 (Brand new arduino)
if( (EEPROM.read(EEPROM_DATA_VERSION) == 0) || (EEPROM.read(EEPROM_DATA_VERSION) == 255) )
if( (readEEPROMVersion() == 0) || (readEEPROMVersion() == 255) )
{
configPage9.true_address = 0x200;
@ -529,9 +526,9 @@ void doUpdates()
configPage4.FILTER_FLEX = 75;
EEPROM.write(EEPROM_DATA_VERSION, CURRENT_DATA_VERSION);
storeEEPROMVersion(CURRENT_DATA_VERSION);
}
//Check to see if someone has downgraded versions:
if( EEPROM.read(EEPROM_DATA_VERSION) > CURRENT_DATA_VERSION ) { EEPROM.write(EEPROM_DATA_VERSION, CURRENT_DATA_VERSION); }
if( readEEPROMVersion() > CURRENT_DATA_VERSION ) { storeEEPROMVersion(CURRENT_DATA_VERSION); }
}