mirror of
https://github.com/peterantypas/maiana.git
synced 2025-05-29 05:40:15 -07:00
Flash persistence
This commit is contained in:
parent
7737a46685
commit
10f525b317
File diff suppressed because it is too large
Load Diff
@ -1,54 +1,6 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<project>
|
||||
|
||||
<configuration id="ilg.gnuarmeclipse.managedbuild.cross.toolchain.base.224719691" name="STM32L432-Debug">
|
||||
|
||||
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
||||
|
||||
<provider class="org.eclipse.cdt.managedbuilder.language.settings.providers.GCCBuiltinSpecsDetector" console="false" env-hash="-1825228665693299080" id="ilg.gnuarmeclipse.managedbuild.cross.GCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT ARM Cross GCC Built-in Compiler Settings " parameter="${COMMAND} ${FLAGS} ${cross_toolchain_flags} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||
|
||||
</provider>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
</extension>
|
||||
|
||||
</configuration>
|
||||
|
||||
<configuration id="ilg.gnuarmeclipse.managedbuild.cross.toolchain.base.224719691.1415184230" name="STM32L432-Release">
|
||||
|
||||
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
||||
|
||||
<provider class="org.eclipse.cdt.managedbuilder.language.settings.providers.GCCBuiltinSpecsDetector" console="false" env-hash="-1784426948057827467" id="ilg.gnuarmeclipse.managedbuild.cross.GCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT ARM Cross GCC Built-in Compiler Settings " parameter="${COMMAND} ${FLAGS} ${cross_toolchain_flags} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||
|
||||
</provider>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
</extension>
|
||||
|
||||
</configuration>
|
||||
|
||||
<configuration id="ilg.gnuarmeclipse.managedbuild.cross.toolchain.base.224719691.1736396711" name="STM32L412-Debug">
|
||||
|
||||
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
|
||||
@ -97,4 +49,52 @@
|
||||
|
||||
</configuration>
|
||||
|
||||
<configuration id="ilg.gnuarmeclipse.managedbuild.cross.toolchain.base.224719691.1736396711.702231882" name="STM32L432-Debug">
|
||||
|
||||
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
||||
|
||||
<provider class="org.eclipse.cdt.managedbuilder.language.settings.providers.GCCBuiltinSpecsDetector" console="false" env-hash="-1845368326497085580" id="ilg.gnuarmeclipse.managedbuild.cross.GCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT ARM Cross GCC Built-in Compiler Settings " parameter="${COMMAND} ${FLAGS} ${cross_toolchain_flags} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||
|
||||
</provider>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
</extension>
|
||||
|
||||
</configuration>
|
||||
|
||||
<configuration id="ilg.gnuarmeclipse.managedbuild.cross.toolchain.base.224719691.1415184230.175393012.1960282527" name="STM32L432-Release">
|
||||
|
||||
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
||||
|
||||
<provider class="org.eclipse.cdt.managedbuilder.language.settings.providers.GCCBuiltinSpecsDetector" console="false" env-hash="-1804972565764657307" id="ilg.gnuarmeclipse.managedbuild.cross.GCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT ARM Cross GCC Built-in Compiler Settings " parameter="${COMMAND} ${FLAGS} ${cross_toolchain_flags} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||
|
||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||
|
||||
</provider>
|
||||
|
||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||
|
||||
</extension>
|
||||
|
||||
</configuration>
|
||||
|
||||
</project>
|
||||
|
@ -17,19 +17,18 @@
|
||||
along with this program. If not, see <https://www.gnu.org/licenses/>
|
||||
*/
|
||||
|
||||
|
||||
#ifndef CONFIGURATION_HPP_
|
||||
#define CONFIGURATION_HPP_
|
||||
|
||||
// This singleton manages user-definable configuration data stored in Flash (or EEPROM).
|
||||
// This singleton manages user-definable configuration data stored in Flash.
|
||||
|
||||
#include "StationData.h"
|
||||
|
||||
// Defining this as a union of data fields or 32 double words, as the L4 expects flash writes to be 8 bytes long
|
||||
// This should be plenty big (no need to be a whole flash page)
|
||||
typedef union
|
||||
{
|
||||
StationData station;
|
||||
uint64_t dw[32];
|
||||
uint64_t dw[64];
|
||||
} ConfigPage;
|
||||
|
||||
class Configuration
|
||||
|
@ -105,6 +105,8 @@
|
||||
#define DFU_FLAG_MAGIC 0xa191feed
|
||||
#define CLI_FLAG_MAGIC 0x209a388d
|
||||
|
||||
#define CONFIGURATION_ADDRESS 0x0800F800
|
||||
|
||||
|
||||
|
||||
#endif /* CONFIG_H_ */
|
||||
|
@ -62,7 +62,7 @@ _Min_Stack_Size = 0x400; /* required amount of stack */
|
||||
MEMORY
|
||||
{
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 39K
|
||||
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 62K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
|
@ -62,7 +62,7 @@ MEMORY
|
||||
{
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 39K
|
||||
RAM2 (xrw) : ORIGIN = 0x10000000, LENGTH = 16K
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 100K
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 62K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
|
@ -17,21 +17,13 @@
|
||||
along with this program. If not, see <https://www.gnu.org/licenses/>
|
||||
*/
|
||||
|
||||
|
||||
#include <stm32l4xx_hal.h>
|
||||
#include <cstring>
|
||||
#include "Configuration.hpp"
|
||||
#include "Utils.hpp"
|
||||
#include "config.h"
|
||||
#include "EventQueue.hpp"
|
||||
#include "bsp.hpp"
|
||||
#include <stdio.h>
|
||||
|
||||
|
||||
#if 0
|
||||
|
||||
// This has no effect anymore, just left here for reference
|
||||
|
||||
static StationData __THIS_STATION__ = {
|
||||
STATION_DATA_MAGIC,
|
||||
987654321, // MMSI
|
||||
@ -45,6 +37,7 @@ static StationData __THIS_STATION__ = {
|
||||
};
|
||||
#endif
|
||||
|
||||
static ConfigPage __page;
|
||||
|
||||
Configuration &Configuration::instance()
|
||||
{
|
||||
@ -71,9 +64,6 @@ void Configuration::reportStationData()
|
||||
memset(&d, 0, sizeof d);
|
||||
|
||||
Event *e = EventPool::instance().newEvent(PROPR_NMEA_SENTENCE);
|
||||
if ( !e )
|
||||
return;
|
||||
|
||||
sprintf(e->nmeaBuffer.sentence,
|
||||
"$PAISTN,%lu,%s,%s,%d,%d,%d,%d,%d*",
|
||||
d.mmsi,
|
||||
@ -84,30 +74,82 @@ void Configuration::reportStationData()
|
||||
d.beam,
|
||||
d.portOffset,
|
||||
d.bowOffset);
|
||||
|
||||
Utils::completeNMEA(e->nmeaBuffer.sentence);
|
||||
EventQueue::instance().push(e);
|
||||
}
|
||||
|
||||
bool Configuration::erasePage()
|
||||
{
|
||||
uint32_t page = (CONFIGURATION_ADDRESS - FLASH_BASE) / FLASH_PAGE_SIZE;
|
||||
|
||||
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS);
|
||||
HAL_FLASH_Unlock();
|
||||
|
||||
FLASH_EraseInitTypeDef erase;
|
||||
erase.TypeErase = FLASH_TYPEERASE_PAGES;
|
||||
erase.Banks = FLASH_BANK_1;
|
||||
erase.Page = page;
|
||||
erase.NbPages = 1;
|
||||
|
||||
uint32_t errPage;
|
||||
HAL_StatusTypeDef status = HAL_FLASHEx_Erase(&erase, &errPage);
|
||||
if ( status != HAL_OK )
|
||||
{
|
||||
HAL_FLASH_Lock();
|
||||
return false;
|
||||
}
|
||||
|
||||
HAL_FLASH_Lock();
|
||||
return true;
|
||||
}
|
||||
|
||||
void Configuration::resetToDefaults()
|
||||
{
|
||||
if ( bsp_erase_station_data() )
|
||||
if ( erasePage() )
|
||||
reportStationData();
|
||||
}
|
||||
|
||||
bool Configuration::writeStationData(const StationData &data)
|
||||
{
|
||||
if ( bsp_save_station_data(data) )
|
||||
if ( !erasePage() )
|
||||
return false;
|
||||
|
||||
memcpy(&__page.station, &data, sizeof data);
|
||||
if ( erasePage() )
|
||||
{
|
||||
bool success = writePage();
|
||||
reportStationData();
|
||||
return true;
|
||||
return success;
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
bool Configuration::writePage()
|
||||
{
|
||||
uint32_t pageAddress = CONFIGURATION_ADDRESS;
|
||||
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS);
|
||||
HAL_FLASH_Unlock();
|
||||
HAL_StatusTypeDef status = HAL_OK;
|
||||
for ( uint32_t dw = 0; dw < sizeof __page/8; ++dw )
|
||||
{
|
||||
status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD, pageAddress + dw*8, __page.dw[dw]);
|
||||
if ( status != HAL_OK )
|
||||
break;
|
||||
}
|
||||
HAL_FLASH_Lock();
|
||||
|
||||
return status == HAL_OK;
|
||||
}
|
||||
|
||||
bool Configuration::readStationData(StationData &data)
|
||||
{
|
||||
return bsp_read_station_data(data) && data.magic == STATION_DATA_MAGIC;
|
||||
memcpy(&__page, (const void*)CONFIGURATION_ADDRESS, sizeof __page);
|
||||
memcpy(&data, &__page.station, sizeof data);
|
||||
return data.magic == STATION_DATA_MAGIC;
|
||||
}
|
||||
|
||||
|
||||
|
@ -19,14 +19,9 @@
|
||||
|
||||
|
||||
#include "EventQueue.hpp"
|
||||
//#include <stm32l4xx.h>
|
||||
|
||||
#include "printf_serial.h"
|
||||
#include "printf_serial.h"
|
||||
#include "Utils.hpp"
|
||||
#include "FreeRTOS.h"
|
||||
#include "queue.h"
|
||||
#include "task.h"
|
||||
#include "bsp.hpp"
|
||||
|
||||
|
||||
|
@ -27,7 +27,7 @@
|
||||
|
||||
#if BOARD_REV==100
|
||||
|
||||
I2C_HandleTypeDef hi2c1;
|
||||
//I2C_HandleTypeDef hi2c1;
|
||||
SPI_HandleTypeDef hspi1;
|
||||
IWDG_HandleTypeDef hiwdg;
|
||||
UART_HandleTypeDef huart2;
|
||||
@ -74,8 +74,10 @@ static const GPIO __gpios[] = {
|
||||
{RX_IC_CLK_PORT, {RX_IC_CLK_PIN, GPIO_MODE_IT_RISING, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{RX_IC_DATA_PORT, {RX_IC_DATA_PIN, GPIO_MODE_INPUT, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{TX_CTRL_PORT, {TX_CTRL_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
#if 0
|
||||
{I2C_SCL_PORT, {I2C_SCL_PIN, GPIO_MODE_AF_OD, GPIO_PULLUP, GPIO_SPEED_HIGH, GPIO_AF4_I2C1}, GPIO_PIN_SET},
|
||||
{I2C_SDA_PORT, {I2C_SDA_PIN, GPIO_MODE_AF_OD, GPIO_PULLUP, GPIO_SPEED_HIGH, GPIO_AF4_I2C1}, GPIO_PIN_SET},
|
||||
#endif
|
||||
};
|
||||
|
||||
extern "C"
|
||||
@ -184,6 +186,7 @@ void bsp_hw_init()
|
||||
|
||||
HAL_TIM_Base_Init(&htim2);
|
||||
|
||||
#if 0
|
||||
// I2C
|
||||
hi2c1.Instance = I2C1;
|
||||
hi2c1.Init.Timing = 0x00702991;
|
||||
@ -210,6 +213,7 @@ void bsp_hw_init()
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
#endif
|
||||
|
||||
// 1PPS signal
|
||||
HAL_NVIC_SetPriority(EXTI2_IRQn, 6, 0);
|
||||
@ -488,6 +492,7 @@ uint8_t bsp_tx_spi_byte(uint8_t data)
|
||||
|
||||
bool bsp_erase_station_data()
|
||||
{
|
||||
#if 0
|
||||
uint8_t b = 0xff;
|
||||
HAL_Delay(1);
|
||||
|
||||
@ -496,12 +501,14 @@ bool bsp_erase_station_data()
|
||||
HAL_I2C_Mem_Write(&hi2c1, EEPROM_ADDRESS, i, 1, &b, 1, 100);
|
||||
HAL_Delay(6);
|
||||
}
|
||||
#endif
|
||||
|
||||
return true;
|
||||
return false;
|
||||
}
|
||||
|
||||
bool bsp_save_station_data(const StationData &data)
|
||||
{
|
||||
#if 0
|
||||
HAL_Delay(1);
|
||||
|
||||
uint8_t *b = (uint8_t*)&data;
|
||||
@ -510,8 +517,9 @@ bool bsp_save_station_data(const StationData &data)
|
||||
HAL_I2C_Mem_Write(&hi2c1, EEPROM_ADDRESS, i, 1, b, 1, 100);
|
||||
HAL_Delay(6);
|
||||
}
|
||||
#endif
|
||||
|
||||
return true;
|
||||
return false;
|
||||
}
|
||||
|
||||
void bsp_reboot()
|
||||
@ -521,13 +529,14 @@ void bsp_reboot()
|
||||
|
||||
bool bsp_read_station_data(StationData &data)
|
||||
{
|
||||
#if 0
|
||||
uint8_t *b = (uint8_t*)&data;
|
||||
for ( unsigned i = 0; i < sizeof(StationData); ++i, ++b )
|
||||
{
|
||||
HAL_I2C_Mem_Read(&hi2c1, EEPROM_ADDRESS, i, 1, b, 1, 100);
|
||||
}
|
||||
|
||||
return true;
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
bool bsp_is_tx_disabled()
|
||||
|
Loading…
x
Reference in New Issue
Block a user