diff --git a/.cproject b/.cproject
new file mode 100644
index 00000000..70887b05
--- /dev/null
+++ b/.cproject
@@ -0,0 +1,120 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/.gitignore b/.gitignore
index eb48f105..2d6277fd 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,2 +1,6 @@
build/*
!build/hover.hex
+/.settings/language.settings.xml
+/.settings/org.eclipse.cdt.codan.core.prefs
+/build/hover.hex
+/openocd.txt
diff --git a/.project b/.project
new file mode 100644
index 00000000..11080760
--- /dev/null
+++ b/.project
@@ -0,0 +1,29 @@
+
+
+ hoverboard_sw
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ fr.ac6.mcu.ide.core.MCUProjectNature
+ fr.ac6.mcu.ide.core.MCUSingleCoreProjectNature
+
+
diff --git a/Drivers/eeprom/eeprom.c b/Drivers/eeprom/eeprom.c
new file mode 100644
index 00000000..abd60fff
--- /dev/null
+++ b/Drivers/eeprom/eeprom.c
@@ -0,0 +1,665 @@
+#include "eeprom.h"
+#include "stm32f1xx_hal.h"
+// See http://www.st.com/web/en/resource/technical/document/application_note/CD00165693.pdf
+
+//add defines for your MCU family
+#ifndef EEPROM_PAGE_SIZE
+ #if defined (STM32F103xE)
+ #define EEPROM_PAGE_SIZE (uint16_t)0x800 /* Page size = 2KByte */
+ #else
+ #error "No known MCU type specified to determine EEPROM page size."
+ #endif
+#endif
+
+//add defines for your MCU
+#ifndef EEPROM_START_ADDRESS
+ #if defined (STM32F103xE)
+ #define EEPROM_START_ADDRESS ((uint32_t)(0x8000000 + 512 * 1024 - 2 * EEPROM_PAGE_SIZE))
+ #else
+ #error "No known MCU type specified to determine EEPROM start address."
+ #endif
+#endif
+
+/* Pages 0 and 1 base and end addresses */
+#define EEPROM_PAGE0_BASE ((uint32_t)(EEPROM_START_ADDRESS + 0x000))
+#define EEPROM_PAGE1_BASE ((uint32_t)(EEPROM_START_ADDRESS + EEPROM_PAGE_SIZE))
+
+/* Page status definitions */
+#define EEPROM_ERASED ((uint16_t)0xFFFF) /* PAGE is empty */
+#define EEPROM_RECEIVE_DATA ((uint16_t)0xEEEE) /* PAGE is marked to receive data */
+#define EEPROM_VALID_PAGE ((uint16_t)0x0000) /* PAGE containing valid data */
+
+/* Page full define */
+enum
+{
+ EEPROM_OK = 0x0000, //0
+ EEPROM_OUT_SIZE = 0x0081, //129
+ EEPROM_BAD_ADDRESS = 0x0082, //130
+ EEPROM_BAD_FLASH = 0x0083, //131
+ EEPROM_NOT_INIT = 0x0084, //132
+ EEPROM_SAME_VALUE = 0x0085, //133
+ EEPROM_NO_VALID_PAGE = 0x00AB //171
+};
+
+#define EEPROM_DEFAULT_DATA 0xFFFF
+
+//private helper functions
+FLASH_Status EE_ErasePage(uint32_t);
+uint16_t EE_CheckPage(uint32_t, uint16_t);
+uint16_t EE_CheckErasePage(uint32_t, uint16_t);
+uint32_t EE_FindValidPage(void);
+uint16_t EE_GetVariablesCount(uint32_t, uint16_t);
+uint16_t EE_PageTransfer(uint32_t, uint32_t, uint16_t);
+uint16_t EE_VerifyPageFullWriteVariable(uint16_t, uint16_t);
+
+//member variables (this file was CPP)
+uint32_t PageBase0 = EEPROM_PAGE0_BASE;
+uint32_t PageBase1 = EEPROM_PAGE1_BASE;
+uint32_t PageSize = EEPROM_PAGE_SIZE;
+uint16_t Status = EEPROM_NOT_INIT;
+
+/**
+ * @brief Check page for blank
+ * @param page base address
+ * @retval Success or error
+ * EEPROM_BAD_FLASH: page not empty after erase
+ * EEPROM_OK: page blank
+ */
+uint16_t EE_CheckPage(uint32_t pageBase, uint16_t status)
+{
+ uint32_t pageEnd = pageBase + (uint32_t)PageSize;
+
+ // Page Status not EEPROM_ERASED and not a "state"
+ if ((*(__IO uint16_t*)pageBase) != EEPROM_ERASED && (*(__IO uint16_t*)pageBase) != status)
+ return EEPROM_BAD_FLASH;
+ for(pageBase += 4; pageBase < pageEnd; pageBase += 4)
+ if ((*(__IO uint32_t*)pageBase) != 0xFFFFFFFF) // Verify if slot is empty
+ return EEPROM_BAD_FLASH;
+ return EEPROM_OK;
+}
+
+/**
+ * @brief Erase page with increment erase counter (page + 2)
+ * @param page base address
+ * @retval Success or error
+ * FLASH_COMPLETE: success erase
+ * - Flash error code: on write Flash error
+ */
+FLASH_Status EE_ErasePage(uint32_t pageBase)
+{
+ FLASH_Status FlashStatus;
+ uint16_t data = (*(__IO uint16_t*)(pageBase));
+ if ((data == EEPROM_ERASED) || (data == EEPROM_VALID_PAGE) || (data == EEPROM_RECEIVE_DATA))
+ data = (*(__IO uint16_t*)(pageBase + 2)) + 1;
+ else
+ data = 0;
+
+ FlashStatus = FLASH_ErasePage(pageBase);
+ if (FlashStatus == FLASH_COMPLETE)
+ FlashStatus = FLASH_ProgramHalfWord(pageBase + 2, data);
+
+ return FlashStatus;
+}
+
+/**
+ * @brief Check page for blank and erase it
+ * @param page base address
+ * @retval Success or error
+ * - Flash error code: on write Flash error
+ * - EEPROM_BAD_FLASH: page not empty after erase
+ * - EEPROM_OK: page blank
+ */
+uint16_t EE_CheckErasePage(uint32_t pageBase, uint16_t status)
+{
+ uint16_t FlashStatus;
+ if (EE_CheckPage(pageBase, status) != EEPROM_OK)
+ {
+ FlashStatus = EE_ErasePage(pageBase);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+ return EE_CheckPage(pageBase, status);
+ }
+ return EEPROM_OK;
+}
+
+/**
+ * @brief Find valid Page for write or read operation
+ * @param Page0: Page0 base address
+ * Page1: Page1 base address
+ * @retval Valid page address (PAGE0 or PAGE1) or NULL in case of no valid page was found
+ */
+uint32_t EE_FindValidPage(void)
+{
+ uint16_t status0 = (*(__IO uint16_t*)PageBase0); // Get Page0 actual status
+ uint16_t status1 = (*(__IO uint16_t*)PageBase1); // Get Page1 actual status
+
+ if (status0 == EEPROM_VALID_PAGE && status1 == EEPROM_ERASED)
+ return PageBase0;
+ if (status1 == EEPROM_VALID_PAGE && status0 == EEPROM_ERASED)
+ return PageBase1;
+
+ return 0;
+}
+
+/**
+ * @brief Calculate unique variables in EEPROM
+ * @param start: address of first slot to check (page + 4)
+ * @param end: page end address
+ * @param address: 16 bit virtual address of the variable to excluse (or 0XFFFF)
+ * @retval count of variables
+ */
+uint16_t EE_GetVariablesCount(uint32_t pageBase, uint16_t skipAddress)
+{
+ uint16_t varAddress, nextAddress;
+ uint32_t idx;
+ uint32_t pageEnd = pageBase + (uint32_t)PageSize;
+ uint16_t count = 0;
+
+ for (pageBase += 6; pageBase < pageEnd; pageBase += 4)
+ {
+ varAddress = (*(__IO uint16_t*)pageBase);
+ if (varAddress == 0xFFFF || varAddress == skipAddress)
+ continue;
+
+ count++;
+ for(idx = pageBase + 4; idx < pageEnd; idx += 4)
+ {
+ nextAddress = (*(__IO uint16_t*)idx);
+ if (nextAddress == varAddress)
+ {
+ count--;
+ break;
+ }
+ }
+ }
+ return count;
+}
+
+/**
+ * @brief Transfers last updated variables data from the full Page to an empty one.
+ * @param newPage: new page base address
+ * @param oldPage: old page base address
+ * @param SkipAddress: 16 bit virtual address of the variable (or 0xFFFF)
+ * @retval Success or error status:
+ * - FLASH_COMPLETE: on success
+ * - EEPROM_OUT_SIZE: if valid new page is full
+ * - Flash error code: on write Flash error
+ */
+uint16_t EE_PageTransfer(uint32_t newPage, uint32_t oldPage, uint16_t SkipAddress)
+{
+ uint32_t oldEnd, newEnd;
+ uint32_t oldIdx, newIdx, idx;
+ uint16_t address, data, found;
+ FLASH_Status FlashStatus;
+
+ // Transfer process: transfer variables from old to the new active page
+ newEnd = newPage + ((uint32_t)PageSize);
+
+ // Find first free element in new page
+ for (newIdx = newPage + 4; newIdx < newEnd; newIdx += 4)
+ if ((*(__IO uint32_t*)newIdx) == 0xFFFFFFFF) // Verify if element
+ break; // contents are 0xFFFFFFFF
+ if (newIdx >= newEnd)
+ return EEPROM_OUT_SIZE;
+
+ oldEnd = oldPage + 4;
+ oldIdx = oldPage + (uint32_t)(PageSize - 2);
+
+ for (; oldIdx > oldEnd; oldIdx -= 4)
+ {
+ address = *(__IO uint16_t*)oldIdx;
+ if (address == 0xFFFF || address == SkipAddress)
+ continue; // it's means that power off after write data
+
+ found = 0;
+ for (idx = newPage + 6; idx < newIdx; idx += 4)
+ if ((*(__IO uint16_t*)(idx)) == address)
+ {
+ found = 1;
+ break;
+ }
+
+ if (found)
+ continue;
+
+ if (newIdx < newEnd)
+ {
+ data = (*(__IO uint16_t*)(oldIdx - 2));
+
+ FlashStatus = FLASH_ProgramHalfWord(newIdx, data);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+
+ FlashStatus = FLASH_ProgramHalfWord(newIdx + 2, address);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+
+ newIdx += 4;
+ }
+ else
+ return EEPROM_OUT_SIZE;
+ }
+
+ // Erase the old Page: Set old Page status to EEPROM_EEPROM_ERASED status
+ data = EE_CheckErasePage(oldPage, EEPROM_ERASED);
+ if (data != EEPROM_OK)
+ return data;
+
+ // Set new Page status
+ FlashStatus = FLASH_ProgramHalfWord(newPage, EEPROM_VALID_PAGE);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+
+ return EEPROM_OK;
+}
+
+/**
+ * @brief Verify if active page is full and Writes variable in EEPROM.
+ * @param Address: 16 bit virtual address of the variable
+ * @param Data: 16 bit data to be written as variable value
+ * @retval Success or error status:
+ * - FLASH_COMPLETE: on success
+ * - EEPROM_PAGE_FULL: if valid page is full (need page transfer)
+ * - EEPROM_NO_VALID_PAGE: if no valid page was found
+ * - EEPROM_OUT_SIZE: if EEPROM size exceeded
+ * - Flash error code: on write Flash error
+ */
+uint16_t EE_VerifyPageFullWriteVariable(uint16_t Address, uint16_t Data)
+{
+ FLASH_Status FlashStatus;
+ uint32_t idx, pageBase, pageEnd, newPage;
+ uint16_t count;
+
+ // Get valid Page for write operation
+ pageBase = EE_FindValidPage();
+ if (pageBase == 0)
+ return EEPROM_NO_VALID_PAGE;
+
+ // Get the valid Page end Address
+ pageEnd = pageBase + PageSize; // Set end of page
+
+ for (idx = pageEnd - 2; idx > pageBase; idx -= 4)
+ {
+ if ((*(__IO uint16_t*)idx) == Address) // Find last value for address
+ {
+ count = (*(__IO uint16_t*)(idx - 2)); // Read last data
+ if (count == Data)
+ return EEPROM_OK;
+ if (count == 0xFFFF)
+ {
+ FlashStatus = FLASH_ProgramHalfWord(idx - 2, Data); // Set variable data
+ if (FlashStatus == FLASH_COMPLETE)
+ return EEPROM_OK;
+ }
+ break;
+ }
+ }
+
+ // Check each active page address starting from begining
+ for (idx = pageBase + 4; idx < pageEnd; idx += 4)
+ if ((*(__IO uint32_t*)idx) == 0xFFFFFFFF) // Verify if element
+ { // contents are 0xFFFFFFFF
+ FlashStatus = FLASH_ProgramHalfWord(idx, Data); // Set variable data
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+ FlashStatus = FLASH_ProgramHalfWord(idx + 2, Address); // Set variable virtual address
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+ return EEPROM_OK;
+ }
+
+ // Empty slot not found, need page transfer
+ // Calculate unique variables in page
+ count = EE_GetVariablesCount(pageBase, Address) + 1;
+ if (count >= (PageSize / 4 - 1))
+ return EEPROM_OUT_SIZE;
+
+ if (pageBase == PageBase1)
+ newPage = PageBase0; // New page address where variable will be moved to
+ else
+ newPage = PageBase1;
+
+ // Set the new Page status to RECEIVE_DATA status
+ FlashStatus = FLASH_ProgramHalfWord(newPage, EEPROM_RECEIVE_DATA);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+
+ // Write the variable passed as parameter in the new active page
+ FlashStatus = FLASH_ProgramHalfWord(newPage + 4, Data);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+
+ FlashStatus = FLASH_ProgramHalfWord(newPage + 6, Address);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+
+ return EE_PageTransfer(newPage, pageBase, Address);
+}
+
+
+uint16_t ee_init(void)
+{
+ uint16_t status0, status1;
+ FLASH_Status FlashStatus;
+
+ FLASH_Unlock();
+ Status = EEPROM_NO_VALID_PAGE;
+
+ status0 = (*(__IO uint16_t *)PageBase0);
+ status1 = (*(__IO uint16_t *)PageBase1);
+
+ switch (status0)
+ {
+/*
+ Page0 Page1
+ ----- -----
+ EEPROM_ERASED EEPROM_VALID_PAGE Page1 valid, Page0 erased
+ EEPROM_RECEIVE_DATA Page1 need set to valid, Page0 erased
+ EEPROM_ERASED make EE_Format
+ any Error: EEPROM_NO_VALID_PAGE
+*/
+ case EEPROM_ERASED:
+ if (status1 == EEPROM_VALID_PAGE) // Page0 erased, Page1 valid
+ Status = EE_CheckErasePage(PageBase0, EEPROM_ERASED);
+ else if (status1 == EEPROM_RECEIVE_DATA) // Page0 erased, Page1 receive
+ {
+ FlashStatus = FLASH_ProgramHalfWord(PageBase1, EEPROM_VALID_PAGE);
+ if (FlashStatus != FLASH_COMPLETE)
+ Status = FlashStatus;
+ else
+ Status = EE_CheckErasePage(PageBase0, EEPROM_ERASED);
+ }
+ else if (status1 == EEPROM_ERASED) // Both in erased state so format EEPROM
+ Status = ee_format();
+ break;
+/*
+ Page0 Page1
+ ----- -----
+ EEPROM_RECEIVE_DATA EEPROM_VALID_PAGE Transfer Page1 to Page0
+ EEPROM_ERASED Page0 need set to valid, Page1 erased
+ any EEPROM_NO_VALID_PAGE
+*/
+ case EEPROM_RECEIVE_DATA:
+ if (status1 == EEPROM_VALID_PAGE) // Page0 receive, Page1 valid
+ Status = EE_PageTransfer(PageBase0, PageBase1, 0xFFFF);
+ else if (status1 == EEPROM_ERASED) // Page0 receive, Page1 erased
+ {
+ Status = EE_CheckErasePage(PageBase1, EEPROM_ERASED);
+ if (Status == EEPROM_OK)
+ {
+ FlashStatus = FLASH_ProgramHalfWord(PageBase0, EEPROM_VALID_PAGE);
+ if (FlashStatus != FLASH_COMPLETE)
+ Status = FlashStatus;
+ else
+ Status = EEPROM_OK;
+ }
+ }
+ break;
+/*
+ Page0 Page1
+ ----- -----
+ EEPROM_VALID_PAGE EEPROM_VALID_PAGE Error: EEPROM_NO_VALID_PAGE
+ EEPROM_RECEIVE_DATA Transfer Page0 to Page1
+ any Page0 valid, Page1 erased
+*/
+ case EEPROM_VALID_PAGE:
+ if (status1 == EEPROM_VALID_PAGE) // Both pages valid
+ Status = EEPROM_NO_VALID_PAGE;
+ else if (status1 == EEPROM_RECEIVE_DATA)
+ Status = EE_PageTransfer(PageBase1, PageBase0, 0xFFFF);
+ else
+ Status = EE_CheckErasePage(PageBase1, EEPROM_ERASED);
+ break;
+/*
+ Page0 Page1
+ ----- -----
+ any EEPROM_VALID_PAGE Page1 valid, Page0 erased
+ EEPROM_RECEIVE_DATA Page1 valid, Page0 erased
+ any EEPROM_NO_VALID_PAGE
+*/
+ default:
+ if (status1 == EEPROM_VALID_PAGE)
+ Status = EE_CheckErasePage(PageBase0, EEPROM_ERASED); // Check/Erase Page0
+ else if (status1 == EEPROM_RECEIVE_DATA)
+ {
+ FlashStatus = FLASH_ProgramHalfWord(PageBase1, EEPROM_VALID_PAGE);
+ if (FlashStatus != FLASH_COMPLETE)
+ Status = FlashStatus;
+ else
+ Status = EE_CheckErasePage(PageBase0, EEPROM_ERASED);
+ }
+ break;
+ }
+ return Status;
+}
+
+/**
+ * @brief Erases PAGE0 and PAGE1 and writes EEPROM_VALID_PAGE / 0 header to PAGE0
+ * @param PAGE0 and PAGE1 base addresses
+ * @retval Status of the last operation (Flash write or erase) done during EEPROM formating
+ */
+uint16_t ee_format(void)
+{
+ uint16_t status;
+ FLASH_Status FlashStatus;
+
+ FLASH_Unlock();
+
+ // Erase Page0
+ status = EE_CheckErasePage(PageBase0, EEPROM_VALID_PAGE);
+ if (status != EEPROM_OK)
+ return status;
+ if ((*(__IO uint16_t*)PageBase0) == EEPROM_ERASED)
+ {
+ // Set Page0 as valid page: Write VALID_PAGE at Page0 base address
+ FlashStatus = FLASH_ProgramHalfWord(PageBase0, EEPROM_VALID_PAGE);
+ if (FlashStatus != FLASH_COMPLETE)
+ return FlashStatus;
+ }
+ // Erase Page1
+ return EE_CheckErasePage(PageBase1, EEPROM_ERASED);
+}
+
+/**
+ * @brief Returns the erase counter for current page
+ * @param Data: Global variable contains the read variable value
+ * @retval Success or error status:
+ * - EEPROM_OK: if erases counter return.
+ * - EEPROM_NO_VALID_PAGE: if no valid page was found.
+ */
+uint16_t ee_erases(uint16_t *Erases)
+{
+ uint32_t pageBase;
+ if (Status != EEPROM_OK)
+ if (ee_init() != EEPROM_OK)
+ return Status;
+
+ // Get active Page for read operation
+ pageBase = EE_FindValidPage();
+ if (pageBase == 0)
+ return EEPROM_NO_VALID_PAGE;
+
+ *Erases = (*(__IO uint16_t*)pageBase+2);
+ return EEPROM_OK;
+}
+
+/**
+ * @brief Returns the last stored variable data, if found,
+ * which correspond to the passed virtual address
+ * @param Address: Variable virtual address
+ * @param Data: Pointer to data variable
+ * @retval Success or error status:
+ * - EEPROM_OK: if variable was found
+ * - EEPROM_BAD_ADDRESS: if the variable was not found
+ * - EEPROM_NO_VALID_PAGE: if no valid page was found.
+ */
+uint16_t ee_read(uint16_t Address, uint16_t *Data)
+{
+ uint32_t pageBase, pageEnd;
+
+ // Set default data (empty EEPROM)
+ *Data = EEPROM_DEFAULT_DATA;
+
+ if (Status == EEPROM_NOT_INIT)
+ if (ee_init() != EEPROM_OK)
+ return Status;
+
+ // Get active Page for read operation
+ pageBase = EE_FindValidPage();
+ if (pageBase == 0)
+ return EEPROM_NO_VALID_PAGE;
+
+ // Get the valid Page end Address
+ pageEnd = pageBase + ((uint32_t)(PageSize - 2));
+
+ // Check each active page address starting from end
+ for (pageBase += 6; pageEnd >= pageBase; pageEnd -= 4)
+ if ((*(__IO uint16_t*)pageEnd) == Address) // Compare the read address with the virtual address
+ {
+ *Data = (*(__IO uint16_t*)(pageEnd - 2)); // Get content of Address-2 which is variable value
+ return EEPROM_OK;
+ }
+
+ // Return ReadStatus value: (0: variable exist, 1: variable doesn't exist)
+ return EEPROM_BAD_ADDRESS;
+}
+
+/**
+ * @brief Writes/updates variable data in EEPROM.
+ * @param VirtAddress: Variable virtual address
+ * @param Data: 16 bit data to be written
+ * @retval Success or error status:
+ * - FLASH_COMPLETE: on success
+ * - EEPROM_BAD_ADDRESS: if address = 0xFFFF
+ * - EEPROM_PAGE_FULL: if valid page is full
+ * - EEPROM_NO_VALID_PAGE: if no valid page was found
+ * - EEPROM_OUT_SIZE: if no empty EEPROM variables
+ * - Flash error code: on write Flash error
+ */
+uint16_t ee_write(uint16_t Address, uint16_t Data)
+{
+ if (Status == EEPROM_NOT_INIT)
+ if (ee_init() != EEPROM_OK)
+ return Status;
+
+ if (Address == 0xFFFF)
+ return EEPROM_BAD_ADDRESS;
+
+ // Write the variable virtual address and value in the EEPROM
+ uint16_t status = EE_VerifyPageFullWriteVariable(Address, Data);
+ return status;
+}
+
+
+/**
+ * @brief Stores an array of 16-bit values into eeprom address 0
+ * @param data: array of data to store
+ * @param len: number of 16-bit values to store
+ * @retval number of data elements succesfully stored
+ */
+uint16_t ee_store(volatile uint16_t *data, uint16_t len)
+{
+ return ee_write_multiple(0,data,len);
+}
+
+/**
+ * @brief Reads an array of 16-bit values from eeprom address 0
+ * @param data: array to store data
+ * @param len: number of 16-bit values to load
+ * @retval number of data elements succesfully loaded
+ */
+uint16_t ee_load(volatile uint16_t *data, uint16_t len)
+{
+ return ee_read_multiple(0,data,len);
+}
+
+
+/**
+ * @brief Reads multiple variables from EEPROM.
+ * @param addr: data start address
+ * @param data: data buffer to be read into
+ * @param len : number of variables to be read
+ * @retval number of variables succesfully read
+ */
+uint16_t ee_read_multiple(uint16_t addr, volatile uint16_t *data, uint16_t len)
+{
+ uint16_t cnt;
+ for(cnt=0; cntSR & FLASH_SR_BSY) == FLASH_SR_BSY)
+ return FLASH_BUSY;
+
+ if ((FLASH->SR & FLASH_SR_PGERR) != 0)
+ return FLASH_ERROR_PG;
+
+ if ((FLASH->SR & FLASH_SR_WRPRTERR) != 0 )
+ return FLASH_ERROR_WRP;
+
+ if ((FLASH->SR & FLASH_OBR_OPTERR) != 0 )
+ return FLASH_ERROR_OPT;
+
+ return FLASH_COMPLETE;
+}
+
+/**
+ * @brief Waits for a Flash operation to complete or a TIMEOUT to occur.
+ * @param Timeout: FLASH progamming Timeout
+ * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+ * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+ */
+FLASH_Status FLASH_WaitForLastOp(uint32_t Timeout)
+{
+ FLASH_Status status;
+
+ /* Check for the Flash Status */
+ status = FLASH_GetStatus();
+ /* Wait for a Flash operation to complete or a TIMEOUT to occur */
+ while ((status == FLASH_BUSY) && (Timeout != 0x00))
+ {
+ delay();
+ status = FLASH_GetStatus();
+ Timeout--;
+ }
+ if (Timeout == 0)
+ status = FLASH_TIMEOUT;
+ /* Return the operation status */
+ return status;
+}
+
+/**
+ * @brief Erases a specified FLASH page.
+ * @param Page_Address: The page address to be erased.
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG,
+ * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+ */
+FLASH_Status FLASH_ErasePage(uint32_t Page_Address)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+ /* Check the parameters */
+ if(!IS_FLASH_ADDRESS(Page_Address))
+ return FLASH_BAD_ADDRESS;
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOp(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to erase the page */
+ FLASH->CR |= FLASH_CR_PER;
+ FLASH->AR = Page_Address;
+ FLASH->CR |= FLASH_CR_STRT;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOp(EraseTimeout);
+ if(status != FLASH_TIMEOUT)
+ {
+ /* if the erase operation is completed, disable the PER Bit */
+ FLASH->CR &= ~FLASH_CR_PER;
+ }
+ FLASH->SR = (FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPRTERR);
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/**
+ * @brief Programs a half word at a specified address.
+ * @param Address: specifies the address to be programmed.
+ * @param Data: specifies the data to be programmed.
+ * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+ * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+ */
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data)
+{
+ FLASH_Status status = FLASH_BAD_ADDRESS;
+
+ if (IS_FLASH_ADDRESS(Address))
+ {
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOp(ProgramTimeout);
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to program the new data */
+ FLASH->CR |= FLASH_CR_PG;
+ *(__IO uint16_t*)Address = Data;
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOp(ProgramTimeout);
+ if(status != FLASH_TIMEOUT)
+ {
+ /* if the program operation is completed, disable the PG Bit */
+ FLASH->CR &= ~FLASH_CR_PG;
+ }
+ FLASH->SR = (FLASH_SR_EOP | FLASH_SR_PGERR | FLASH_SR_WRPRTERR);
+ }
+ }
+ return status;
+}
+
+/**
+ * @brief Unlocks the FLASH Program Erase Controller.
+ * @param None
+ * @retval None
+ */
+void FLASH_Unlock(void)
+{
+ /* Authorize the FPEC Access */
+ FLASH->KEYR = FLASH_KEY1;
+ FLASH->KEYR = FLASH_KEY2;
+}
+
+/**
+ * @brief Locks the FLASH Program Erase Controller.
+ * @param None
+ * @retval None
+ */
+void FLASH_Lock(void)
+{
+ /* Set the Lock Bit to lock the FPEC and the FCR */
+ FLASH->CR |= FLASH_CR_LOCK;
+}
diff --git a/Drivers/eeprom/flash_stm32.h b/Drivers/eeprom/flash_stm32.h
new file mode 100644
index 00000000..d60d363c
--- /dev/null
+++ b/Drivers/eeprom/flash_stm32.h
@@ -0,0 +1,34 @@
+#ifndef __FLASH_STM32_H
+#define __FLASH_STM32_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+#include "stdint.h"
+
+typedef enum
+ {
+ FLASH_BUSY = 1,
+ FLASH_ERROR_PG = 2,
+ FLASH_ERROR_WRP = 3,
+ FLASH_ERROR_OPT = 4,
+ FLASH_COMPLETE = 5,
+ FLASH_TIMEOUT = 6,
+ FLASH_BAD_ADDRESS = 7
+ } FLASH_Status;
+
+#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x0807FFFF))
+
+FLASH_Status FLASH_WaitForLastOp(uint32_t Timeout);
+FLASH_Status FLASH_ErasePage(uint32_t Page_Address);
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data);
+
+void FLASH_Unlock(void);
+void FLASH_Lock(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __FLASH_STM32_H */
diff --git a/Inc/cfgbus.h b/Inc/cfgbus.h
new file mode 100644
index 00000000..36843008
--- /dev/null
+++ b/Inc/cfgbus.h
@@ -0,0 +1,117 @@
+#ifndef CFGBUS_H
+#define CFGBUS_H
+
+#include
+#include
+#include "modbus.h"
+
+//address at which the cfgbus list can be requested
+#define CFG_LIST_REG_INDEX (5000) //excl 40001 range offset
+#define CFG_DEVICE_NAME "Hover" //10 chars max
+#define CFG_LIST_NAME_CHARS (16) //max characters in entry name string (excl. terminating \0)
+
+//I am not a big fan of complicated macro structures, but this was the only way I could think
+//of that allows an easy definition of entries, that can be easily accessed (cfg.vars._varname),
+//and that leaves no room for error by multiple definitions of the same thing (like nr. entries)
+
+//assign initial values in CfgInit()
+
+//USE _STRxx FOR STRING ENTRIES of size xx!!!
+//--------------------------------------------------------------------------------------------------
+//FORMAT | entry type | var name | cfg_type | writeable | name string |
+//--------------------------------------------------------------------------------------------------
+#define CFG_ENTRIES(_ENTRY) \
+ _ENTRY( magic , uint16_t , _U16 , false , "Magic Value" ) \
+ _ENTRY( nr_entries , uint16_t , _U16 , false , "Nr Entries" ) \
+ _ENTRY( dev_name[12] , char , _STR12 , false , "Device Name" ) \
+ _ENTRY( err_code , uint16_t , _U16 , true , "Error Code" ) \
+ _ENTRY( err_cnt , uint16_t , _U16 , true , "Error Count" ) \
+ _ENTRY( rate_limit , uint16_t , _U16 , true , "Rate Limit (p/ms)" ) \
+ _ENTRY( setpoint_l , int16_t , _I16 , true , "PWM Setpoint-L" ) \
+ _ENTRY( setpoint_r , int16_t , _I16 , true , "PWM Setpoint-R" ) \
+ _ENTRY( max_pwm_l , uint16_t , _U16 , true , "Max PWM Left" ) \
+ _ENTRY( max_pwm_r , uint16_t , _U16 , true , "Max PWM Right" ) \
+ _ENTRY( buzzer , uint16_t , _U16 , true , "Buzzer" ) \
+ _ENTRY( speed_l , int16_t , _I16 , false , "Speed Left" ) \
+ _ENTRY( speed_r , int16_t , _I16 , false , "Speed Right" ) \
+ _ENTRY( tacho_l , uint16_t , _U16 , false , "Tacho Left" ) \
+ _ENTRY( tacho_r , uint16_t , _U16 , false , "Tacho Right" ) \
+ _ENTRY( pwm_l , int32_t , _I32 , false , "PWM-Left" ) \
+ _ENTRY( pwm_r , int32_t , _I32 , false , "PWM-Right" ) \
+ _ENTRY( pos_l , uint16_t , _U16 , false , "HALLPos-Left" ) \
+ _ENTRY( pos_r , uint16_t , _U16 , false , "HALLPos-Right" ) \
+ _ENTRY( vbat , float , _FLT , false , "Battery Voltage" )
+
+//-------------------------------------------------------------------------------------------------------------
+// DO NOT EDIT BELOW THIS LINE UNLESS YOU KNOW WHAT YOU ARE DOING
+//-------------------------------------------------------------------------------------------------------------
+
+uint32_t CfgAvailable();
+int CfgRead(uint8_t * data, uint32_t len);
+int CfgWrite(uint8_t * data, uint32_t len);
+void CfgFlushRx();
+void CfgFlushTx();
+uint32_t CfgTick();
+void CfgInit();
+void CfgSetError(int error);
+void CfgRegRead(uint16_t start, uint16_t nr_regs, uint8_t* data);
+mb_exception_t CfgRegWrite(uint16_t start, uint16_t nr_regs, uint8_t* data);
+bool CfgValidRange(uint16_t first, uint16_t cnt);
+
+typedef enum
+{
+ cfg_ok = 0,
+ cfg_invalid_data = 1,
+ cfg_rx_timeout = 2,
+ cfg_rx_error = 3,
+ cfg_tx_timeout = 4,
+ cfg_tx_error = 5,
+ cfg_invalid_entry = 6,
+ cfg_invalid_cmd = 7,
+ cfg_len_mismatch = 8,
+ cfg_crc_err = 9,
+ cfg_illegal_write = 10,
+ cfg_unknown = 11 //should be last
+} cfg_err_t;
+
+typedef enum
+{
+ t_u16 = 0,
+ t_u32 = 1,
+ t_u64 = 2,
+ t_i16 = 3,
+ t_i32 = 4,
+ t_i64 = 5,
+ t_flt = 6,
+ t_dbl = 7,
+ t_bool = 8,
+ t_str = 9,
+ t_err = 10,
+ t_unknown = 11//should be last
+} cfg_type_t;
+
+
+//DONT TOUCH! required for CFGbus operation
+#define _STRUCT(_var,_sys,_3,_4,_5) _sys _var;
+#define _COUNT(_1,_2,_3,_4,_5) +1
+#define CFG_NR_ENTRIES (0+CFG_ENTRIES(_COUNT))
+#define CFG_NR_REGISTERS (cfg_entries[CFG_NR_ENTRIES-1].address + cfg_entries[CFG_NR_ENTRIES-1].size)
+
+
+typedef struct
+{
+ CFG_ENTRIES(_STRUCT)
+} cfg_t;
+
+//defined as union so that struct members will be placed in same memory
+//as configbus registers, only multiple of 2-byte types allowed to ensure
+//allignment with registers
+typedef union{
+ cfg_t vars;
+ uint16_t regs[(sizeof(cfg_t)+1)/2];
+} cfg_mem_t;
+
+extern volatile cfg_mem_t cfg;
+
+#endif //CFGBUS_H
+
diff --git a/Inc/config.h b/Inc/config.h
index 27e0ffc3..440d457a 100644
--- a/Inc/config.h
+++ b/Inc/config.h
@@ -1,25 +1,14 @@
#pragma once
#include "stm32f1xx_hal.h"
-#define R 0.27
-#define P 15
-#define PSI 0.02
-#define V 23
-
-#define MILLI_R (R * 1000)
-#define MILLI_PSI (PSI * 1000)
-#define MILLI_V (V * 1000)
-
#define PWM_FREQ 16000 // PWM frequency in Hz
#define DEAD_TIME 32 // PWM deadtime
+#define DC_CUR_LIMIT 1 // Motor DC current limit in amps
+#define PPM_NUM_CHANNELS 6 // number of PPM channels to receive
+#define VBAT_ADC_TO_UV (25532) //25532 uV per ADC count
+#define ADC_BATTERY_VOLT 0.026474
-//#define DC_CUR_LIMIT 34 // Motor DC current limit in amps
-#define DC_CUR_LIMIT 24 // Motor DC current limit in amps
+//do not change, deducted from other settings
+#define DC_CUR_THRESHOLD (DC_CUR_LIMIT*50) // x50 = /0.02 (old MOTOR_AMP_CONV_DC_AMP)
-//#define DEBUG_SERIAL_SERVOTERM
-// #define DEBUG_SERIAL_ASCII
-#define DEBUG_BAUD 115200 // UART baud rate
-//#define DEBUG_I2C_LCD
-// #define CONTROL_PPM // use PPM CONTROL_PPM
-#define PPM_NUM_CHANNELS 6 // number of PPM channels to receive
diff --git a/Inc/control.h b/Inc/control.h
new file mode 100644
index 00000000..96f0af37
--- /dev/null
+++ b/Inc/control.h
@@ -0,0 +1,17 @@
+/*
+ * control.h
+ *
+ * Created on: May 6, 2018
+ * Author: tomvoc
+ */
+
+#ifndef INC_CONTROL_H_
+#define INC_CONTROL_H_
+
+#include "stm32f1xx_hal.h"
+
+void led_update(void);
+void update_controls(void);
+void init_controls(void);
+
+#endif /* INC_CONTROL_H_ */
diff --git a/Inc/defines.h b/Inc/defines.h
index b2b94e51..e10c63f3 100644
--- a/Inc/defines.h
+++ b/Inc/defines.h
@@ -21,21 +21,19 @@
#pragma once
#include "stm32f1xx_hal.h"
+#define LEFT_HALL_PORT GPIOB
+#define LEFT_HALL_LSB_PIN 5
#define LEFT_HALL_U_PIN GPIO_PIN_5
#define LEFT_HALL_V_PIN GPIO_PIN_6
#define LEFT_HALL_W_PIN GPIO_PIN_7
-#define LEFT_HALL_U_PORT GPIOB
-#define LEFT_HALL_V_PORT GPIOB
-#define LEFT_HALL_W_PORT GPIOB
-
+#define RIGHT_HALL_PORT GPIOC
+#define RIGHT_HALL_LSB_PIN 10
#define RIGHT_HALL_U_PIN GPIO_PIN_10
#define RIGHT_HALL_V_PIN GPIO_PIN_11
#define RIGHT_HALL_W_PIN GPIO_PIN_12
-#define RIGHT_HALL_U_PORT GPIOC
-#define RIGHT_HALL_V_PORT GPIOC
-#define RIGHT_HALL_W_PORT GPIOC
+#define CTRL_TIM TIM3
#define LEFT_TIM TIM8
#define LEFT_TIM_U CCR1
@@ -71,10 +69,6 @@
#define RIGHT_TIM_WL_PIN GPIO_PIN_15
#define RIGHT_TIM_WL_PORT GPIOB
-// #define LEFT_DC_CUR_ADC ADC1
-// #define LEFT_U_CUR_ADC ADC1
-// #define LEFT_V_CUR_ADC ADC1
-
#define LEFT_DC_CUR_PIN GPIO_PIN_0
#define LEFT_U_CUR_PIN GPIO_PIN_0
#define LEFT_V_CUR_PIN GPIO_PIN_3
@@ -83,10 +77,6 @@
#define LEFT_U_CUR_PORT GPIOA
#define LEFT_V_CUR_PORT GPIOC
-// #define RIGHT_DC_CUR_ADC ADC2
-// #define RIGHT_U_CUR_ADC ADC2
-// #define RIGHT_V_CUR_ADC ADC2
-
#define RIGHT_DC_CUR_PIN GPIO_PIN_1
#define RIGHT_U_CUR_PIN GPIO_PIN_4
#define RIGHT_V_CUR_PIN GPIO_PIN_5
@@ -95,12 +85,8 @@
#define RIGHT_U_CUR_PORT GPIOC
#define RIGHT_V_CUR_PORT GPIOC
-// #define DCLINK_ADC ADC3
-// #define DCLINK_CHANNEL
#define DCLINK_PIN GPIO_PIN_2
#define DCLINK_PORT GPIOC
-// #define DCLINK_PULLUP 30000
-// #define DCLINK_PULLDOWN 1000
#define LED_PIN GPIO_PIN_2
#define LED_PORT GPIOB
@@ -120,17 +106,6 @@
#define CHARGER_PIN GPIO_PIN_12
#define CHARGER_PORT GPIOA
-#define DELAY_TIM_FREQUENCY_US 1000000
-
-#define MOTOR_AMP_CONV_DC_AMP 0.02
-#define ADC_BATTERY_VOLT 0.02647435897435897435897435897436
-
-#define MILLI_R (R * 1000)
-#define MILLI_PSI (PSI * 1000)
-#define MILLI_V (V * 1000)
-
-#define NO 0
-#define YES 1
#define ABS(a) (((a) < 0.0) ? -(a) : (a))
#define LIMIT(x, lowhigh) (((x) > (lowhigh)) ? (lowhigh) : (((x) < (-lowhigh)) ? (-lowhigh) : (x)))
#define SAT(x, lowhigh) (((x) > (lowhigh)) ? (1.0) : (((x) < (-lowhigh)) ? (-1.0) : (0.0)))
@@ -146,6 +121,7 @@
#define MIN3(a, b, c) MIN(a, MIN(b, c))
#define MAX3(a, b, c) MAX(a, MAX(b, c))
+
typedef struct {
uint16_t rr1;
uint16_t rr2;
@@ -153,8 +129,18 @@ typedef struct {
uint16_t rl2;
uint16_t dcr;
uint16_t dcl;
- uint16_t batt1;
- uint16_t l_tx2;
- uint16_t bat1;
- uint16_t l_rx2;
+ uint16_t vbat;
+ uint16_t temp;
} adc_buf_t;
+
+//adc startup offsets
+typedef struct {
+ int32_t rr1;
+ int32_t rr2;
+ int32_t rl1;
+ int32_t rl2;
+ int32_t dcr;
+ int32_t dcl;
+ int32_t vbat;
+ int32_t temp;
+} adc_offsets_t;
diff --git a/Inc/modbus.h b/Inc/modbus.h
new file mode 100644
index 00000000..73e22c15
--- /dev/null
+++ b/Inc/modbus.h
@@ -0,0 +1,31 @@
+/*
+ * Copyright © 2011 Stéphane Raimbault
+ *
+ * License ISC, see LICENSE for more details.
+
+ * This library implements the Modbus protocol.
+ * http://libmodbus.org/
+ *
+ */
+
+#pragma once
+
+#include
+
+#define MB_CHAR_TIMEOUT (1) //max ms between chars
+#define MB_PACKET_TIMEOUT (3) //max ms between chars
+#define MB_BROADCAST_ADDR (0)
+#define MB_RX_BUFFER_SIZE (128)
+#define MB_SLAVE_ID (16)
+
+/* Protocol exceptions */
+typedef enum
+{
+ mb_ok = 0,
+ mb_illegal_func = 1,
+ mb_illegal_address = 2,
+ mb_illegal_value = 3,
+ mb_timeout = 4
+} mb_exception_t;
+
+void mb_update();
diff --git a/Inc/setup.h b/Inc/setup.h
index 48a16e92..1581178c 100644
--- a/Inc/setup.h
+++ b/Inc/setup.h
@@ -26,4 +26,6 @@ void MX_GPIO_Init(void);
void MX_TIM_Init(void);
void MX_ADC1_Init(void);
void MX_ADC2_Init(void);
-void UART_Init(void);
+void control_timer_init(void);
+
+extern volatile adc_buf_t adc_buffer;
diff --git a/Inc/stm32f1xx_it.h b/Inc/stm32f1xx_it.h
index 237a392e..9d594848 100644
--- a/Inc/stm32f1xx_it.h
+++ b/Inc/stm32f1xx_it.h
@@ -46,6 +46,7 @@ extern "C" {
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
+void PPM_ISR_Callback(void);
void NMI_Handler(void);
void HardFault_Handler(void);
void MemManage_Handler(void);
@@ -56,6 +57,8 @@ void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
void DMA2_Channel4_5_IRQHandler(void);
#ifdef __cplusplus
diff --git a/Inc/uart.h b/Inc/uart.h
new file mode 100644
index 00000000..39e46ac0
--- /dev/null
+++ b/Inc/uart.h
@@ -0,0 +1,38 @@
+/*
+ * uart.h
+ *
+ * Created on: Apr 12, 2018
+ * Author: tomvoc
+ */
+
+#pragma once
+
+#include "stm32f1xx_hal.h"
+#include "config.h"
+
+#define UART2_BAUD 115200
+#define UART2_RX_FIFO_SIZE 64
+#define UART2_TX_FIFO_SIZE 64
+
+#define UART3_BAUD 115200
+#define UART3_RX_FIFO_SIZE 64
+#define UART3_TX_FIFO_SIZE 64
+
+typedef enum
+{
+ UARTCh2,
+ UARTCh3
+} UART_ch_t;
+
+
+void UART_Init();
+void UARTRxEnable(UART_ch_t uartCh, uint8_t enable);
+void UARTTxEnable(UART_ch_t uartCh, uint8_t enable);
+uint32_t UARTRxAvailable(UART_ch_t uartCh);
+uint32_t UARTTxAvailable(UART_ch_t uartCh);
+int UARTSend(UART_ch_t uartCh, const uint8_t *buff, uint32_t len);
+int UARTSendStr(UART_ch_t uartCh, const char *msg);
+int UARTRead(UART_ch_t uartCh, uint8_t* buff, uint32_t len);
+void UARTFlushRX(UART_ch_t uartCh);
+void UARTFlushTX(UART_ch_t uartCh);
+int UARTTXReady(UART_ch_t uartCh);
diff --git a/Makefile b/Makefile
index 0f721c56..2484e1f0 100644
--- a/Makefile
+++ b/Makefile
@@ -33,12 +33,16 @@ Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc_ex.c \
Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal.c \
Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_adc.c \
Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_uart.c \
+Drivers/eeprom/eeprom.c \
+Drivers/eeprom/flash_stm32.c \
Src/system_stm32f1xx.c \
Src/setup.c \
-Src/control.c \
+Src/uart.c \
Src/main.c \
Src/bldc.c \
-Src/comms.c \
+Src/cfgbus.c \
+Src/control.c \
+Src/modbus.c \
Src/stm32f1xx_it.c \
# ASM sources
@@ -91,7 +95,8 @@ C_INCLUDES = \
-IDrivers/STM32F1xx_HAL_Driver/Inc \
-IDrivers/STM32F1xx_HAL_Driver/Inc/Legacy \
-IDrivers/CMSIS/Device/ST/STM32F1xx/Include \
--IDrivers/CMSIS/Include
+-IDrivers/CMSIS/Include \
+-IDrivers/eeprom
# compile gcc flags
diff --git a/README.md b/README.md
new file mode 100644
index 00000000..bbdc2c52
--- /dev/null
+++ b/README.md
@@ -0,0 +1,31 @@
+# hoverboard-firmware-hack
+
+This is a Fork fom NiklasFauth's hoverboard-firmware-hack.
+
+The goal is to make the board more configurable without requiring reprogramming for every setting,
+and to allow controller the board over different interfaces.
+
+Current state:
+ - implemented dma/interrupt based UART2/3 RX/TX (see uart.h/c)
+ - implemented simple modbus slave (supports commands 0x3(read) and ox10(write). Works with open-source QtModMaster tool
+ - cleaned code from some hacks/features. Some will be re-added later
+ - removed I2C/ADC/PWM control. This will be re-integrated soon
+ - clean up BLDC ADC handler, now more efficient, and only dealing with motors
+ - no more delays in code, but rather non-blocking Tick() based updates
+ - disabled buzzer, man I hate buzzers
+
+
+Coming soon:
+ - wrapper on modbus.c/h and gui to allow reading and writing arbritrary user defined settings using GUI only
+ - selectable control method (UART / I2C / ADC / PWM)
+ - motor speed tacho
+ - merge Niklas's updates
+
+Coming later:
+ - adding plot capabilities to the GUI to allow monitoring all the user configured variables
+
+
+If you have any feature requests, open up an issue and I will get back to you a.s.a.p!
+
+
+
diff --git a/Src/bldc.c b/Src/bldc.c
index 4ff12e4d..5b733982 100644
--- a/Src/bldc.c
+++ b/Src/bldc.c
@@ -1,36 +1,31 @@
#include "stm32f1xx_hal.h"
+#include
#include "defines.h"
#include "setup.h"
#include "config.h"
+#include "cfgbus.h"
+uint8_t enable = 0;
-volatile int posl = 0;
-volatile int posr = 0;
-volatile int pwml = 0;
-volatile int pwmr = 0;
-int16_t pwmrl = 0;
-
-extern volatile adc_buf_t adc_buffer;
-
-extern volatile uint32_t timeout;
+uint32_t offsetcount = 0;
+adc_offsets_t offsets = {0};
-uint8_t buzzerFreq = 0;
-uint8_t buzzerPattern = 0;
-
-uint8_t enable = 0;
+uint16_t _lastPosL = 0;
+uint16_t _lastPosR = 0;
const int pwm_res = 64000000 / 2 / PWM_FREQ; // = 2000
+//(hall_to_pos + 2) % 6
const uint8_t hall_to_pos[8] = {
- 0,
- 0,
- 2,
- 1,
- 4,
- 5,
- 3,
- 0,
+ 2,
+ 5,
+ 1,
+ 0,
+ 3,
+ 4,
+ 2,
+ 2,
};
inline void blockPWM(int pwm, int pos, int *u, int *v, int *w) {
@@ -72,194 +67,73 @@ inline void blockPWM(int pwm, int pos, int *u, int *v, int *w) {
}
}
-inline void blockPhaseCurrent(int pos, int u, int v, int *q) {
- switch(pos) {
- case 0:
- *q = u - v;
- // *u = 0;
- // *v = pwm;
- // *w = -pwm;
- break;
- case 1:
- *q = u;
- // *u = -pwm;
- // *v = pwm;
- // *w = 0;
- break;
- case 2:
- *q = u;
- // *u = -pwm;
- // *v = 0;
- // *w = pwm;
- break;
- case 3:
- *q = v;
- // *u = 0;
- // *v = -pwm;
- // *w = pwm;
- break;
- case 4:
- *q = v;
- // *u = pwm;
- // *v = -pwm;
- // *w = 0;
- break;
- case 5:
- *q = -(u - v);
- // *u = pwm;
- // *v = 0;
- // *w = -pwm;
- break;
- default:
- *q = 0;
- // *u = 0;
- // *v = 0;
- // *w = 0;
- }
-}
-
-uint16_t buzzerTimer = 0;
-
-int offsetcount = 0;
-int offsetrl1 = 2000;
-int offsetrl2 = 2000;
-int offsetrr1 = 2000;
-int offsetrr2 = 2000;
-int offsetdcl = 2000;
-int offsetdcr = 2000;
-
-float batteryVoltage;
-float adccmd1;
-float adccmd2;
-
-int curl = 0;
-// int errorl = 0;
-// int kp = 5;
-// volatile int cmdl = 0;
-
-int last_pos = 0;
-int timer = 0;
-const int max_time = PWM_FREQ / 10;
-volatile int vel = 0;
+//scan 8 channels with 2ADCs @ 20 clk cycles per sample
+//meaning ~80 ADC clock cycles @ 8MHz until new DMA interrupt =~ 100KHz
+//=640 cpu cycles
void DMA1_Channel1_IRQHandler() {
DMA1->IFCR = DMA_IFCR_CTCIF1;
- // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1);
- if(offsetcount < 1000) { // calibrate ADC offsets
+ // callibrate ADC offset before startup by averaging 1024 samples.
+ if(offsetcount < 1024) {
offsetcount++;
- offsetrl1 = (adc_buffer.rl1 + offsetrl1) / 2;
- offsetrl2 = (adc_buffer.rl2 + offsetrl2) / 2;
- offsetrr1 = (adc_buffer.rr1 + offsetrr1) / 2;
- offsetrr2 = (adc_buffer.rr2 + offsetrr2) / 2;
- offsetdcl = (adc_buffer.dcl + offsetdcl) / 2;
- offsetdcr = (adc_buffer.dcr + offsetdcr) / 2;
+ offsets.rl1 += adc_buffer.rl1;
+ offsets.rl2 += adc_buffer.rl2;
+ offsets.rr1 += adc_buffer.rr1;
+ offsets.rr2 += adc_buffer.rr2;
+ offsets.dcl += adc_buffer.dcl;
+ offsets.dcr += adc_buffer.dcr;
+ offsets.temp += adc_buffer.temp;
+ offsets.vbat += adc_buffer.vbat;
return;
+ } else if (offsetcount == 1024) {
+ offsetcount++;
+ offsets.rl1 /= 1024;
+ offsets.rl2 /= 1024;
+ offsets.rr1 /= 1024;
+ offsets.rr2 /= 1024;
+ offsets.dcl /= 1024;
+ offsets.dcr /= 1024;
+ offsets.temp /= 1024;
+ offsets.vbat /= 1024;
}
- batteryVoltage = batteryVoltage * 0.999 + ((float)adc_buffer.batt1 * ADC_BATTERY_VOLT) * 0.001;
- adccmd1 = adccmd1 * 0.999 + (float)adc_buffer.l_rx2 * 0.001;
- adccmd2 = adccmd2 * 0.999 + (float)adc_buffer.l_tx2 * 0.001;
-
- //0-4096
- //+-2000
-
- pwmrl = 0;
- if(adccmd1 - 700 > 0){
- pwmrl -= adccmd1 - 700;
- }
- if(adccmd2 - 700 > 0){
- pwmrl += adccmd2 - 700;
- }
-
- if (pwmrl < -100 && enable == 1) {
- buzzerFreq = 5;
- buzzerPattern = 1;
- } else if (enable == 1) {
- buzzerFreq = 0;
- buzzerPattern = 1;
- }
-
- pwmrl = powf((pwmrl/4), 3) / 255885;
- pwml = -pwmrl;
- pwmr = pwmrl;
-
-
-
- if(ABS((adc_buffer.dcl - offsetdcl) * MOTOR_AMP_CONV_DC_AMP) > DC_CUR_LIMIT || timeout > 50 || enable == 0) {
+ //disable PWM when current limit is reached (current chopping)
+ if(ABS(adc_buffer.dcl - offsets.dcl) > DC_CUR_THRESHOLD || enable == 0) {
LEFT_TIM->BDTR &= ~TIM_BDTR_MOE;
- //HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1);
} else {
LEFT_TIM->BDTR |= TIM_BDTR_MOE;
- //HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0);
}
- if(ABS((adc_buffer.dcr - offsetdcr) * MOTOR_AMP_CONV_DC_AMP) > DC_CUR_LIMIT || timeout > 50 || enable == 0) {
+ if(ABS(adc_buffer.dcr - offsets.dcr) > DC_CUR_THRESHOLD || enable == 0) {
RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE;
} else {
RIGHT_TIM->BDTR |= TIM_BDTR_MOE;
}
- int ul, vl, wl;
- int ur, vr, wr;
+ //determine next position based on hall sensors
+ uint8_t hall_l = (LEFT_HALL_PORT->IDR >> LEFT_HALL_LSB_PIN) & 0b111;
+ uint8_t hall_r = (RIGHT_HALL_PORT->IDR >> RIGHT_HALL_LSB_PIN) & 0b111;
- uint8_t hall_ul = !(LEFT_HALL_U_PORT->IDR & LEFT_HALL_U_PIN);
- uint8_t hall_vl = !(LEFT_HALL_V_PORT->IDR & LEFT_HALL_V_PIN);
- uint8_t hall_wl = !(LEFT_HALL_W_PORT->IDR & LEFT_HALL_W_PIN);
+ cfg.vars.pos_r = hall_to_pos[hall_r];
+ cfg.vars.pos_l = hall_to_pos[hall_l];
- uint8_t hall_ur = !(RIGHT_HALL_U_PORT->IDR & RIGHT_HALL_U_PIN);
- uint8_t hall_vr = !(RIGHT_HALL_V_PORT->IDR & RIGHT_HALL_V_PIN);
- uint8_t hall_wr = !(RIGHT_HALL_W_PORT->IDR & RIGHT_HALL_W_PIN);
+ //keep track of wheel movement
+ if(_lastPosL != cfg.vars.pos_l)
+ cfg.vars.tacho_l += (_lastPosL == (cfg.vars.pos_l + 1)%6) ? 1 : -1;
- uint8_t halll = hall_ul * 1 + hall_vl * 2 + hall_wl * 4;
- posl = hall_to_pos[halll];
- posl += 2;
- posl %= 6;
+ if(_lastPosR != cfg.vars.pos_r)
+ cfg.vars.tacho_r += (_lastPosR == (cfg.vars.pos_r + 1)%6) ? 1 : -1;
- uint8_t hallr = hall_ur * 1 + hall_vr * 2 + hall_wr * 4;
- posr = hall_to_pos[hallr];
- posr += 2;
- posr %= 6;
+ _lastPosL = cfg.vars.pos_l;
+ _lastPosR = cfg.vars.pos_r;
- blockPhaseCurrent(posl, adc_buffer.rl1 - offsetrl1, adc_buffer.rl2 - offsetrl2, &curl);
-
- setScopeChannel(2, (adc_buffer.rl1 - offsetrl1) / 8);
- setScopeChannel(3, (adc_buffer.rl2 - offsetrl2) / 8);
-
- buzzerTimer++;
-
- if (buzzerFreq != 0 && (buzzerTimer / 5000) % (buzzerPattern + 1) == 0) {
- if (buzzerTimer % buzzerFreq == 0) {
- HAL_GPIO_TogglePin(BUZZER_PORT, BUZZER_PIN);
- }
- } else {
- HAL_GPIO_WritePin(BUZZER_PORT, BUZZER_PIN, 0);
- }
-
- // //measure vel
- // timer++;
- // if(timer > max_time){
- // timer = max_time;
- // vel = 0;
- // }
-
- // if(posl != last_pos){
- // vel = 1000 * PWM_FREQ / timer / P / 6 * 2;
-
- // if((posl - last_pos + 6) % 6 > 2){
- // vel = -vel;
- // }
-
- // timer = 0;
- // }
- // last_pos = posl;
-
- //YOLOTEST
- // errorl = cmdl - curl;
- // pwml = kp * errorl;
+ //update PWM channels based on position
+ int ul, vl, wl;
+ int ur, vr, wr;
- blockPWM(pwml, posl, &ul, &vl, &wl);
- blockPWM(pwmr, posr, &ur, &vr, &wr);
+ blockPWM(cfg.vars.pwm_l, cfg.vars.pos_l, &ul, &vl, &wl);
+ blockPWM(cfg.vars.pwm_r, cfg.vars.pos_r, &ur, &vr, &wr);
LEFT_TIM->LEFT_TIM_U = CLAMP(ul + pwm_res / 2, 10, pwm_res-10);
LEFT_TIM->LEFT_TIM_V = CLAMP(vl + pwm_res / 2, 10, pwm_res-10);
@@ -268,5 +142,4 @@ void DMA1_Channel1_IRQHandler() {
RIGHT_TIM->RIGHT_TIM_U = CLAMP(ur + pwm_res / 2, 10, pwm_res-10);
RIGHT_TIM->RIGHT_TIM_V = CLAMP(vr + pwm_res / 2, 10, pwm_res-10);
RIGHT_TIM->RIGHT_TIM_W = CLAMP(wr + pwm_res / 2, 10, pwm_res-10);
- // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0);blockPhaseCurrent
}
diff --git a/Src/cfgbus.c b/Src/cfgbus.c
new file mode 100644
index 00000000..8c2d9d7d
--- /dev/null
+++ b/Src/cfgbus.c
@@ -0,0 +1,381 @@
+#include "cfgbus.h"
+#include "modbus.h"
+#include "uart.h"
+#include "eeprom.h"
+#include
+
+
+//these function pointers should point to a user configurable function
+//that stores/reads the 16bit value array in a non-volatile memory such as an eeprom
+//@return: the number of registers succesfully written, should equal len on success
+uint16_t (*CfgStore)(volatile uint16_t *data, uint16_t len) = &ee_store;
+uint16_t (*CfgLoad)(volatile uint16_t *data, uint16_t len) = &ee_load;
+
+#ifdef MIN
+#undef MIN
+#endif
+
+#define CFG_BUS_UART (UARTCh3)
+#define MIN(a, b) (((a) < (b)) ? (a) : (b))
+
+//DO NOT TOUCH, used to generate cfg struct, entry list, and count number of entries
+#define _VAR_ADDR(_var) (((uint16_t*)&cfg.vars._var)-&cfg.regs[0])
+#define _VAR_SIZE(_var) ((sizeof(cfg.vars._var)+1)/2)
+
+#define _XX_VAR(_var,_type) _VAR_ADDR(_var), _VAR_SIZE(_var), _type
+#define _U16(_var) _XX_VAR(_var,t_u16)
+#define _U32(_var) _XX_VAR(_var,t_u32)
+#define _U64(_var) _XX_VAR(_var,t_u64)
+#define _I16(_var) _XX_VAR(_var,t_i16)
+#define _I32(_var) _XX_VAR(_var,t_i32)
+#define _I64(_var) _XX_VAR(_var,t_i64)
+#define _FLT(_var) _XX_VAR(_var,t_flt)
+#define _DBL(_var) _XX_VAR(_var,t_dbl)
+#define _ERR(_var) _XX_VAR(_var,t_err)
+#define _BOOL(_var) _XX_VAR(_var,t_bool)
+
+#define _XX_STR(_var,_len) (_VAR_ADDR(_var)-_len/2), _len/2, t_str
+#define _STR8(_var) _XX_STR(_var,8)
+#define _STR9(_var) _XX_STR(_var,9)
+#define _STR10(_var) _XX_STR(_var,10)
+#define _STR11(_var) _XX_STR(_var,11)
+#define _STR12(_var) _XX_STR(_var,12)
+#define _STR13(_var) _XX_STR(_var,13)
+#define _STR14(_var) _XX_STR(_var,14)
+#define _STR15(_var) _XX_STR(_var,15)
+#define _STR16(_var) _XX_STR(_var,16)
+#define _STR17(_var) _XX_STR(_var,17)
+#define _STR18(_var) _XX_STR(_var,18)
+#define _STR19(_var) _XX_STR(_var,19)
+#define _STR20(_var) _XX_STR(_var,20)
+#define _STR21(_var) _XX_STR(_var,21)
+#define _STR22(_var) _XX_STR(_var,22)
+#define _STR23(_var) _XX_STR(_var,23)
+#define _STR24(_var) _XX_STR(_var,24)
+
+#define _LIST(_var,_2,_type,_rw,_name) { _type(_var), _rw, _name},
+#define CFG_ENTRY_HEADER_REGS (12)
+
+typedef enum
+{
+ cfg_magic_reg = 0,
+ cfg_dev_reg_first = 1,
+ cfg_dev_reg_last = 6,
+ cfg_err_code = 7,
+ cfg_err_cnt = 8,
+ cfg_list_addr = 9,
+ cfg_list_size = 10,
+ cfg_nr_entries = 11,
+} cfg_fixed_reg_t;
+
+
+typedef struct
+{
+ uint16_t address;
+ uint8_t size;
+ uint8_t type; //types declared in "type_t" enum
+ bool writeable;
+ const char* name; //only 16 chars sent over bus!!
+} cfg_entry_t;
+
+
+//counted in nr 16-bit registers
+//5+name_len bytes, + /0 character +1 to ceil /2 devision
+#define CFG_LIST_ENTRY_SIZE ((5+CFG_LIST_NAME_CHARS+2)/2)
+
+volatile cfg_mem_t cfg;
+
+const cfg_entry_t cfg_entries[CFG_NR_ENTRIES] = {
+ CFG_ENTRIES(_LIST)
+};
+
+//helper functions
+void _setWriteMask(uint16_t start, uint16_t nr_regs);
+bool _isWriteAllowed(uint16_t start, uint16_t nr_regs);
+void _endianRegCpy(volatile uint16_t* dst,volatile uint16_t* src, uint8_t nr_regs);
+inline bool _isListEntry(uint16_t start, uint16_t nr_regs);
+
+
+void CfgInit()
+{
+ //=======================================
+ //DO NOT CHANGE:: cfgbus required entries
+ //=======================================
+
+ if(ee_load(cfg.regs,CFG_NR_REGISTERS) != CFG_NR_REGISTERS)
+ {
+ for(int i=0; i> 8) & 0xFF; //MSB
+ data[1] = entry.address & 0xFF; //LSB
+ data[2] = entry.size;
+ data[3] = entry.type;
+ data[4] = entry.writeable;
+
+ //copy string contents
+ uint8_t cpy_len = MIN(CFG_LIST_NAME_CHARS,strlen(entry.name));
+ uint8_t remaining = (CFG_LIST_NAME_CHARS+1)-cpy_len;
+ strncpy((char *)&data[5],entry.name, cpy_len);
+ memset(&data[5+cpy_len],'\0',remaining); //fill remainder with 0 (always at least the last)
+ }
+ else
+ {
+ _endianRegCpy((uint16_t*)data,&cfg.regs[start],nr_regs);
+ }
+}
+
+
+mb_exception_t CfgRegWrite(uint16_t start, uint16_t nr_regs, uint8_t* data)
+{
+ //before any check, if it is a write to magic value, and data equals magic value
+ //store current settings in eeprom
+ if(start == 0 && ((uint16_t*)data)[0] == cfg.vars.magic)
+ {
+ if(CfgStore(cfg.regs,CFG_NR_REGISTERS) != CFG_NR_REGISTERS)
+ return mb_timeout;
+ else
+ return mb_ok;
+ }
+
+ if(_isListEntry(start,nr_regs))
+ return mb_illegal_address;
+
+ if(!_isWriteAllowed(start,nr_regs))
+ return mb_illegal_address;
+
+ _endianRegCpy(&cfg.regs[start],(uint16_t*)data,nr_regs);
+ return mb_ok;
+}
+
+
+//==============================================================
+//HELPER FUNCTIONS
+//==============================================================
+
+//this array stores a bit for every available 16-bit register
+//the bit represents 0:read/write, 1:read only
+uint8_t writeMask[(sizeof(cfg.regs)/16)+1] = {0};
+
+const uint8_t loMasks[8] = {0xFF,0xFE,0xFC,0xF8,0xF0,0xE0,0xC0,0x80};
+const uint8_t hiMasks[8] = {0x01,0x03,0x07,0x0F,0x1F,0x3F,0x7F,0xFF};
+
+
+void _setWriteMask(uint16_t start, uint16_t nr_regs)
+{
+ if(start+nr_regs > sizeof(writeMask)*8)
+ return;
+
+ uint16_t loByte = start/8;
+ uint16_t hiByte = (start+nr_regs-1)/8;
+
+ uint8_t loBit = start%8;
+ uint8_t hiBit = (start+nr_regs-1)%8;
+
+ if(loByte == hiByte)
+ {
+ writeMask[loByte] |= (loMasks[loBit] & hiMasks[hiBit]);
+ }
+ else
+ {
+ writeMask[loByte] |= loMasks[loBit];
+ writeMask[hiByte] |= hiMasks[hiBit];
+ }
+
+ for (int i=1; i sizeof(writeMask)*8)
+ return false;
+
+ uint16_t loByte = start/8;
+ uint16_t hiByte = (start+nr_regs-1)/8;
+
+ uint8_t loBit = start%8;
+ uint8_t hiBit = (start+nr_regs-1)%8;
+
+ volatile bool result;
+
+ if(loByte == hiByte)
+ {
+ result = (writeMask[loByte] & (loMasks[loBit] & hiMasks[hiBit])) == 0;
+ }
+ else
+ {
+ result = (writeMask[loByte] & loMasks[loBit]) == 0;
+ result = result && (writeMask[hiByte] & loMasks[hiBit])==0;
+ }
+
+ for (int i=1; iCNDTR == 0) {
- DMA1_Channel2->CCR &= ~DMA_CCR_EN;
- DMA1_Channel2->CNDTR = 10;
- DMA1_Channel2->CMAR = (uint32_t)uart_buf;
- DMA1_Channel2->CCR |= DMA_CCR_EN;
- }
- #endif
-
- #ifdef DEBUG_SERIAL_ASCII
- memset(uart_buf, 0, sizeof(uart_buf));
- sprintf(uart_buf, "%i;%i;%i;%i\n\r", ch_buf[0], ch_buf[1], ch_buf[2], ch_buf[3]);//, ch_buf[4], ch_buf[5], ch_buf[6], ch_buf[7]);
-
- if(DMA1_Channel2->CNDTR == 0) {
- DMA1_Channel2->CCR &= ~DMA_CCR_EN;
- DMA1_Channel2->CNDTR = strlen(uart_buf);
- DMA1_Channel2->CMAR = (uint32_t)uart_buf;
- DMA1_Channel2->CCR |= DMA_CCR_EN;
- }
- #endif
-}
-
-void consoleLog(char *message)
-{
- HAL_UART_Transmit_DMA(&huart2, (uint8_t *)message, strlen(message));
-}
diff --git a/Src/control.c b/Src/control.c
index 6690880e..8460f492 100644
--- a/Src/control.c
+++ b/Src/control.c
@@ -1,49 +1,128 @@
+/*
+ * control.c
+ *
+ * Created on: May 6, 2018
+ * Author: tomvoc
+ */
-#include "stm32f1xx_hal.h"
+#include "control.h"
#include "defines.h"
+#include "cfgbus.h"
#include "setup.h"
-#include "config.h"
-TIM_HandleTypeDef TimHandle;
-uint16_t ppm_captured_value[PPM_NUM_CHANNELS+1] = {0};
-uint8_t ppm_count = 0;
-uint32_t timeout = 100;
+#define LED_PERIOD (300) //ms
+volatile uint32_t _ledTick=0;
+volatile uint32_t _ctrlTick=0;
-void PPM_ISR_Callback() {
- // Dummy loop with 16 bit count wrap around
- uint16_t rc_delay = TIM2->CNT;
- TIM2->CNT = 0;
+volatile uint16_t _tachoL=0;
+volatile uint16_t _tachoR=0;
+volatile uint16_t _cntL;
+volatile uint16_t _cntR;
+volatile uint16_t _lastSpeedL = 0;
+volatile uint16_t _lastSpeedR = 0;
- if (rc_delay > 3000) {
- ppm_count = 0;
- }
- else if (ppm_count < PPM_NUM_CHANNELS){
- timeout = 0;
- ppm_captured_value[ppm_count] = CLAMP(rc_delay, 1000, 2000) - 1000;
- ppm_count++;
+//call this from main thread. Responsible for turning off the LED
+//LED is turned on in interrupt, so if LED flashes, we know main-loop
+//and control interrupt are running properly.
+void led_update(void)
+{
+ //turn off status LED if on for LED_PERIOD
+ if(_ledTick >= LED_PERIOD)
+ {
+ HAL_GPIO_TogglePin(LED_PORT,LED_PIN);
+ _ledTick = 0;
}
+}
+
+
+void init_controls(void)
+{
+
+}
+
+
+
+void update_controls(void)
+{
}
-void PPM_Init() {
- GPIO_InitTypeDef GPIO_InitStruct;
- /*Configure GPIO pin : PA3 */
- GPIO_InitStruct.Pin = GPIO_PIN_3;
- GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
- GPIO_InitStruct.Pull = GPIO_PULLDOWN;
- HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
-
- __HAL_RCC_TIM2_CLK_ENABLE();
- TimHandle.Instance = TIM2;
- TimHandle.Init.Period = UINT16_MAX;
- TimHandle.Init.Prescaler = (SystemCoreClock/DELAY_TIM_FREQUENCY_US)-1;;
- TimHandle.Init.ClockDivision = 0;
- TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
- HAL_TIM_Base_Init(&TimHandle);
-
- /* EXTI interrupt init*/
- HAL_NVIC_SetPriority(EXTI3_IRQn, 0, 0);
- HAL_NVIC_EnableIRQ(EXTI3_IRQn);
- HAL_TIM_Base_Start(&TimHandle);
+
+//called 64000000/65535 = 976.58 times per second
+void TIM3_IRQHandler(void)
+{
+ CTRL_TIM->SR = 0;
+
+ //calculate motor speeds
+ _cntL ++;
+
+ if(cfg.vars.tacho_l != _tachoL)
+ {
+ cfg.vars.speed_l = (((int32_t)cfg.vars.tacho_l - (int32_t)_tachoL) * 4096) / _cntL;
+ _cntL = 0;
+ }
+ else if(_cntL >= 100)
+ {
+ cfg.vars.speed_l = 0;
+ _cntL = 0;
+ }
+
+ _cntR ++;
+
+ if(cfg.vars.tacho_r != _tachoR)
+ {
+ cfg.vars.speed_r = (((int32_t)cfg.vars.tacho_r - (int32_t)_tachoR) * 4096) / _cntR;
+ _cntR = 0;
+ }
+ else if(_cntR >= 100)
+ {
+ cfg.vars.speed_r = 0;
+ _cntR = 0;
+ }
+
+
+ //update left motor PWM
+ if(_lastSpeedL != cfg.vars.setpoint_l)
+ {
+ cfg.vars.setpoint_l = CLAMP(cfg.vars.setpoint_l, -1000, 1000);
+ cfg.vars.setpoint_l = CLAMP(cfg.vars.setpoint_l, -cfg.vars.max_pwm_l, cfg.vars.max_pwm_l);
+
+ int32_t pwmDiff = (int32_t)cfg.vars.setpoint_l - cfg.vars.pwm_l;
+ pwmDiff = CLAMP(pwmDiff,-cfg.vars.rate_limit,cfg.vars.rate_limit);
+
+ cfg.vars.pwm_l += pwmDiff;
+
+ _lastSpeedL = cfg.vars.pwm_l;
+ }
+
+
+ //update right motor PWM
+ if(_lastSpeedR != cfg.vars.setpoint_r)
+ {
+ cfg.vars.setpoint_r = CLAMP(cfg.vars.setpoint_r, -1000, 1000);
+ cfg.vars.setpoint_r = CLAMP(cfg.vars.setpoint_r, -cfg.vars.max_pwm_r, cfg.vars.max_pwm_r);
+
+ int32_t pwmDiff = (int32_t)cfg.vars.setpoint_r - cfg.vars.pwm_r;
+ pwmDiff = CLAMP(pwmDiff,-cfg.vars.rate_limit,cfg.vars.rate_limit);
+
+ cfg.vars.pwm_r += pwmDiff;
+
+ _lastSpeedR = cfg.vars.pwm_r;
+ }
+
+
+ if(cfg.vars.buzzer == 0)
+ {
+ HAL_GPIO_WritePin(BUZZER_PORT,BUZZER_PIN,0);
+ }
+ else if( (_ctrlTick%cfg.vars.buzzer) == 0 && _ctrlTick%200 > 100 && _ctrlTick%3000 > 2000)
+ {
+ HAL_GPIO_TogglePin(BUZZER_PORT, BUZZER_PIN);
+ }
+
+ //update state variables
+ _ledTick++;
+ _ctrlTick++;
+ _tachoL = cfg.vars.tacho_l;
+ _tachoR = cfg.vars.tacho_r;
}
diff --git a/Src/main.c b/Src/main.c
index 2a4226a6..572cd2ae 100644
--- a/Src/main.c
+++ b/Src/main.c
@@ -1,217 +1,137 @@
-/*
-* This file is part of the stmbl project.
-*
-* Copyright (C) 2013-2018 Rene Hopf
-* Copyright (C) 2013-2018 Nico Stute
-*
-* This program is free software: you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as published by
-* the Free Software Foundation, either version 3 of the License, or
-* (at your option) any later version.
-*
-* This program is distributed in the hope that it will be useful,
-* but WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-* GNU General Public License for more details.
-*
-* You should have received a copy of the GNU General Public License
-* along with this program. If not, see .
-*/
-
-#include "stm32f1xx_hal.h"
-#include "defines.h"
-#include "setup.h"
-#include "config.h"
-
-void SystemClock_Config(void);
-
-extern TIM_HandleTypeDef htim_left;
-extern TIM_HandleTypeDef htim_right;
-extern ADC_HandleTypeDef hadc1;
-extern ADC_HandleTypeDef hadc2;
-extern volatile adc_buf_t adc_buffer;
-extern volatile uint16_t ppm_captured_value[PPM_NUM_CHANNELS+1];
-
-extern volatile int pwml;
-extern volatile int pwmr;
-
-extern uint8_t buzzerFreq;
-extern uint8_t buzzerPattern;
-
-extern uint8_t enable;
-
-extern volatile uint32_t timeout;
-
-extern float batteryVoltage;
-
-
-int milli_vel_error_sum = 0;
-
-int main(void) {
- HAL_Init();
- __HAL_RCC_AFIO_CLK_ENABLE();
- HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
- /* System interrupt init*/
- /* MemoryManagement_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0);
- /* BusFault_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0);
- /* UsageFault_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0);
- /* SVCall_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0);
- /* DebugMonitor_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0);
- /* PendSV_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0);
- /* SysTick_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
-
- SystemClock_Config();
-
- __HAL_RCC_DMA1_CLK_DISABLE();
- MX_GPIO_Init();
- MX_TIM_Init();
- MX_ADC1_Init();
- MX_ADC2_Init();
- UART_Init();
-
- HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, 1);
-
- HAL_ADC_Start(&hadc1);
- HAL_ADC_Start(&hadc2);
-
- for (int i = 8; i >= 0; i--) {
- buzzerFreq = i;
- HAL_Delay(100);
- }
- buzzerFreq = 0;
-
- HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1);
-
- int lastSpeedL = 0, lastSpeedR = 0;
- int speedL = 0, speedR = 0;
-
- #ifdef CONTROL_PPM
- PPM_Init();
- #endif
-
- enable = 1;
-
- while(1) {
- HAL_Delay(10);
- // int milli_cur = 3000;
- // int milli_volt = milli_cur * MILLI_R / 1000;// + vel * MILLI_PSI * 141;
- // // pwm = milli_volt * pwm_res / MILLI_V;
-
- // int milli_vel_cmd = 200;
- // int milli_vel_error = milli_vel_cmd - vel;
- // milli_vel_error_sum += milli_vel_error;
- // milli_vel_error_sum = CLAMP(milli_vel_error_sum, -200000, 200000);
- // pwm = CLAMP(milli_vel_cmd / 5 + milli_vel_error_sum / 200, -500, 500);
- // cmdl = 70;
-
- #ifdef CONTROL_PPM
- speedL = -(CLAMP((((ppm_captured_value[1]-500)+(ppm_captured_value[0]-500)/2.0)*(ppm_captured_value[2]/500.0)), -800, 800));
- speedR = (CLAMP((((ppm_captured_value[1]-500)-(ppm_captured_value[0]-500)/2.0)*(ppm_captured_value[2]/500.0)), -800, 800));
- #endif
-
- if ((speedL < lastSpeedL + 50 && speedL > lastSpeedL - 50) && (speedR < lastSpeedR + 50 && speedR > lastSpeedR - 50) && timeout < 50) {
- pwmr = speedR;
- pwml = speedL;
- }
-
- lastSpeedL = speedL;
- lastSpeedR = speedR;
- setScopeChannel(0, speedR);
- setScopeChannel(1, speedL);
-
- consoleScope();
-
- timeout=0;
-
- if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {
- enable = 0;
- while (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {}
- buzzerFreq = 0;
- buzzerPattern = 0;
- for (int i = 0; i < 8; i++) {
- buzzerFreq = i;
- HAL_Delay(100);
- }
- HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, 0);
- while(1) {}
- }
-
- if (batteryVoltage < 36.0 && batteryVoltage > 33.0) {
- buzzerFreq = 5;
- buzzerPattern = 8;
- } else if (batteryVoltage < 33.0 && batteryVoltage > 30.0) {
- buzzerFreq = 5;
- buzzerPattern = 1;
- } else if (batteryVoltage < 30.0) {
- buzzerPattern = 0;
- enable = 0;
- for (int i = 0; i < 8; i++) {
- buzzerFreq = i;
- HAL_Delay(100);
- }
- HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, 0);
- while(1) {}
- } else {
- buzzerFreq = 0;
- buzzerPattern = 0;
- }
-
-
- // if(vel > milli_vel_cmd){
- // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1);
- // }
- // else{
- // HAL_GPIO_WritePin(LED_PORT, LED_PIN, 0);
- // }
- }
-}
-
-/** System Clock Configuration
-*/
-void SystemClock_Config(void) {
- RCC_OscInitTypeDef RCC_OscInitStruct;
- RCC_ClkInitTypeDef RCC_ClkInitStruct;
- RCC_PeriphCLKInitTypeDef PeriphClkInit;
-
- /**Initializes the CPU, AHB and APB busses clocks
- */
- RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
- RCC_OscInitStruct.HSIState = RCC_HSI_ON;
- RCC_OscInitStruct.HSICalibrationValue = 16;
- RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
- RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI_DIV2;
- RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16;
- HAL_RCC_OscConfig(&RCC_OscInitStruct);
-
- /**Initializes the CPU, AHB and APB busses clocks
- */
- RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
- RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
- RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
- RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
- RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
-
- HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2);
-
- PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
- PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV8;
- HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
-
- /**Configure the Systick interrupt time
- */
- HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);
-
- /**Configure the Systick
- */
- HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
-
- /* SysTick_IRQn interrupt configuration */
- HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
-}
+/*
+* This file is part of the stmbl project.
+*
+* Copyright (C) 2013-2018 Rene Hopf
+* Copyright (C) 2013-2018 Nico Stute
+*
+* This program is free software: you can redistribute it and/or modify
+* it under the terms of the GNU General Public License as published by
+* the Free Software Foundation, either version 3 of the License, or
+* (at your option) any later version.
+*
+* This program is distributed in the hope that it will be useful,
+* but WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see .
+*/
+
+#include "stm32f1xx_hal.h"
+#include "defines.h"
+#include "setup.h"
+#include "config.h"
+#include "uart.h"
+#include "cfgbus.h"
+#include "modbus.h"
+#include "control.h"
+#include "eeprom.h"
+
+void SystemClock_Config(void);
+
+extern ADC_HandleTypeDef hadc1;
+extern ADC_HandleTypeDef hadc2;
+extern uint8_t enable;
+
+
+int main(void) {
+
+ HAL_Init();
+ __HAL_RCC_AFIO_CLK_ENABLE();
+
+ HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
+ /* System interrupt init*/
+ /* MemoryManagement_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0);
+ /* BusFault_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0);
+ /* UsageFault_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0);
+ /* SVCall_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0);
+ /* DebugMonitor_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0);
+ /* PendSV_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0);
+ /* SysTick_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
+
+ SystemClock_Config();
+
+ __HAL_RCC_DMA1_CLK_DISABLE();
+
+ MX_GPIO_Init();
+ MX_TIM_Init();
+ MX_ADC1_Init();
+ MX_ADC2_Init();
+ UART_Init();
+
+ volatile uint16_t ee_tmp = ee_init();
+ CfgInit();
+
+ HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, 1);
+
+ HAL_ADC_Start(&hadc1);
+ HAL_ADC_Start(&hadc2);
+
+ enable = 1;
+
+ UARTRxEnable(UARTCh2, 1);
+ UARTRxEnable(UARTCh3, 1);
+
+ control_timer_init();
+
+
+ while(1)
+ {
+ //show user board is alive
+ led_update();
+
+ //update cfg_bus communication
+ mb_update();
+
+ float vBatNew = ((float)(((uint32_t)adc_buffer.vbat)*VBAT_ADC_TO_UV))/1000000;
+ cfg.vars.vbat = vBatNew;
+
+ }
+}
+
+/** System Clock Configuration
+*/
+void SystemClock_Config(void) {
+ RCC_OscInitTypeDef RCC_OscInitStruct;
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+ RCC_PeriphCLKInitTypeDef PeriphClkInit;
+
+ //Initializes the CPU, AHB and APB bus oscillator
+ //HSI/2 * 16 = 8/2*16 = 64MHz
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSICalibrationValue = 16;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI_DIV2;
+ RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16;
+
+ HAL_RCC_OscConfig(&RCC_OscInitStruct);
+
+ //Initializes the CPU, AHB and APB clocks
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
+
+ HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2);
+
+ //configure ADC clock as 1/8th of PCLK2
+ //PCLK2 = APB2/1 = 64MHz -> ADC @ 8MHz
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
+ PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV8;
+ HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
+
+ //Configure the Systick interrupt time and interrupt
+ HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);
+ HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
+ HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
+}
diff --git a/Src/modbus.c b/Src/modbus.c
new file mode 100644
index 00000000..88cf508c
--- /dev/null
+++ b/Src/modbus.c
@@ -0,0 +1,359 @@
+/*
+ * Copyright © 2011-2012 Stéphane Raimbault
+ *
+ * License ISC, see LICENSE for more details.
+ *
+ * This library implements the Modbus protocol.
+ * http://libmodbus.org/
+ *
+ */
+
+#include
+#include
+#include "modbus.h"
+#include "cfgbus.h"
+#include
+
+//the following function pointers are used throughout the code. Point them to implementations to connect modbus
+//to a UART port and register file
+
+//should handle the logic of reading from and writing to holding registers (16bit).
+//start : the register index to start read/writing
+//nr_regs: the number of registers to read/write
+//data : the data to write, or the buffer to read to
+void (*mb_reg_read)(uint16_t start, uint16_t nr_regs, uint8_t* data) = &CfgRegRead;
+mb_exception_t (*reg_write)(uint16_t start, uint16_t nr_regs, uint8_t* data) = &CfgRegWrite;
+bool (*mb_valid_range)(uint16_t start, uint16_t nr_regs) = &CfgValidRange;
+
+//modbus physical communication (e.g. uart) read/write functions
+//data: data to write/buffer to read to
+//len : number of bytes to read/write
+int (*mb_read)(uint8_t * data, uint32_t len) = &CfgRead;
+int (*mb_write)(uint8_t * data, uint32_t len) = &CfgWrite;
+
+//returns the number of available data-bytes to read
+uint32_t (*mb_available)() = &CfgAvailable;
+
+//flush rx/tx buffers of the serial communication
+void (*mb_flush_rx)(void) = &CfgFlushRx;
+void (*mb_flush_tx)(void) = &CfgFlushTx;
+
+//get current timestamp in ms
+uint32_t (*mb_tick)(void) = &CfgTick;
+
+//gives the user information if something goes wrong. Use this to log or act
+//allowed to do nothing
+void (*mb_error)(int code) = &CfgSetError;
+
+
+//modbus frame header indices
+enum
+{
+ _idx_slave = 0,
+ _idx_func = 1,
+ _idx_addr = 2,
+ _idx_reg_cnt = 4,
+ _idx_data_len = 6,
+ _idx_data_start = 7
+};
+
+
+/* Supported function codes */
+enum
+{
+ _fc_read_regs = 0x03,
+ _fc_write_regs = 0x10,
+ _fc_invalid = 0xFF
+};
+
+
+enum
+{
+ _st_idle,
+ _st_header,
+ _st_receive,
+ _st_respond,
+ _st_error
+};
+
+
+typedef struct
+{
+ uint8_t slave;
+ uint8_t fcode;
+ uint16_t first_reg;
+ uint16_t nr_regs;
+ uint8_t data_len;
+} mb_hdr_t;
+
+
+mb_hdr_t _hdr = {0};
+uint8_t _rcvBuff[MB_RX_BUFFER_SIZE] = {0};
+uint8_t _state = _st_idle;
+uint32_t _lastTick = 0;
+uint32_t _lastAvailable = 0;
+
+
+static uint16_t mb_single_crc16(uint16_t crcIn, uint8_t data)
+{
+ uint16_t crc = crcIn ^ data;
+
+ for (uint8_t j = 0; j < 8; j++) {
+ if (crc & 0x0001)
+ crc = (crc >> 1) ^ 0xA001;
+ else
+ crc = crc >> 1;
+ }
+
+ return crc;
+}
+
+
+static uint16_t mb_crc16(uint16_t crcIn, uint8_t *data, uint8_t size) {
+
+ uint16_t crc = crcIn;
+
+ for(uint16_t i=0; i> 8) & 0xFF;
+
+ mb_write(msg, msg_length);
+}
+
+
+static void mb_flush(void) {
+ //wait until gap of pack-timeout occurs
+
+ uint32_t loopStart = mb_tick();
+ uint32_t start = 0;
+
+ while (loopStart - mb_tick() < 30) //wait max 30ms
+ {
+ if(!mb_available() && start == 0)
+ {
+ start = mb_tick();
+ }
+ else
+ {
+ mb_flush_rx();
+ start = 0;
+ }
+
+ if(mb_tick() - start > MB_PACKET_TIMEOUT)
+ {
+ mb_flush_rx();
+ break;
+ }
+ }
+
+}
+
+
+void mb_exception(uint8_t e, uint8_t nextState)
+{
+ mb_error(e);
+
+ uint8_t rsp[3];
+
+ rsp[0] = MB_SLAVE_ID;
+ rsp[1] = _hdr.fcode + 0x80;
+ rsp[2] = e;
+
+ mb_send_msg(rsp,3);
+ _state = nextState;
+}
+
+
+void inline mb_do_timeout(uint8_t nextState)
+{
+ mb_error(mb_timeout);
+ _state = nextState;
+}
+
+
+void mb_rsp_header(uint8_t* rsp)
+{
+ rsp[0] = _hdr.slave;
+ rsp[1] = _hdr.fcode;
+ rsp[2] = (_hdr.first_reg >> 8) & 0xFF;
+ rsp[3] = _hdr.first_reg & 0xFF;
+ rsp[4] = (_hdr.nr_regs >> 8) & 0xFF;
+ rsp[5] = _hdr.nr_regs & 0xFF;
+}
+
+
+int mb_check_integrity(uint8_t *data)
+{
+ //build crc for header
+ uint8_t hdr[6];
+ mb_rsp_header(hdr);
+ uint16_t crc = mb_crc16(0xFFFF,hdr,6);
+
+ //continue for data if write regs
+ if(_hdr.fcode == _fc_write_regs)
+ {
+ crc = mb_crc16(crc,&_hdr.data_len,1);
+ crc = mb_crc16(crc,data,_hdr.data_len);
+ }
+
+ //get crc from received data (local crc is LSB first, so invert bytes)
+ uint16_t masterCrc = ((uint16_t)(data[_hdr.data_len +1] << 8)) + data[_hdr.data_len];
+
+ return (crc == masterCrc) ? 0 : -1;
+}
+
+
+void mb_update() {
+
+ //waiting for message to be addressed to this slave
+ if(_state == _st_idle && mb_available())
+ {
+ mb_read(&_hdr.slave,1); //get slave address
+ if(_hdr.slave != MB_SLAVE_ID && _hdr.slave != MB_BROADCAST_ADDR )
+ {
+ mb_flush(); //not for me, ignore
+ return;
+ }
+
+ //reset state where necessary, and receive header
+ _hdr.data_len = 0;
+ _lastAvailable = mb_available();
+ _lastTick = mb_tick();
+ _state = _st_header;
+ }
+
+ //retrieve request header
+ if(_state == _st_header)
+ {
+ //wait for entire header before we proceed
+ //0: function code
+ //1..2: first reg address
+ //3..4: nr regs involved
+ //5: nr write bytes (only for writes)
+ if(mb_available() >= 6)
+ {
+ uint8_t rcv[5];
+ mb_read(rcv,5);
+ _hdr.fcode = rcv[0];
+ _hdr.first_reg = ((uint16_t)(rcv[1] << 8)) + rcv[2];
+ _hdr.nr_regs = ((uint16_t)(rcv[3] << 8)) + rcv[4];
+
+ if(_hdr.fcode != _fc_write_regs && _hdr.fcode != _fc_read_regs)
+ {
+ mb_exception(mb_illegal_func, _st_idle); //unsupported function
+ return;
+ }
+
+ if(!mb_valid_range(_hdr.first_reg,_hdr.nr_regs))
+ {
+ mb_exception(mb_illegal_address,_st_idle);
+ return;
+ }
+
+ if(_hdr.fcode == _fc_write_regs)
+ mb_read(&_hdr.data_len,1);
+
+ _lastTick = mb_tick();
+ _state = _st_receive;
+ }
+ else if (mb_available() > _lastAvailable) //new data so proceed
+ {
+ _lastTick = mb_tick();
+ _lastAvailable = mb_available();
+ }
+ else if (mb_tick() - _lastTick > MB_CHAR_TIMEOUT) //timed out
+ {
+ mb_do_timeout(_st_idle);
+ return;
+ }
+ }
+
+
+ if(_state == _st_receive)
+ {
+ if(mb_available() >= _hdr.data_len + 2)
+ {
+ mb_read(_rcvBuff,_hdr.data_len + 2);
+
+ //check integrity
+ if(mb_check_integrity(_rcvBuff) == 0)
+ {
+ _state = _st_respond;
+ }
+ else
+ {
+ mb_exception(mb_illegal_value,_st_idle);
+ return;
+ }
+ }
+ else if (mb_available() > _lastAvailable) //new data so proceed
+ {
+ _lastTick = mb_tick();
+ _lastAvailable = mb_available();
+ }
+ else if (mb_tick() - _lastTick > MB_CHAR_TIMEOUT) //timed out
+ {
+ mb_do_timeout(_st_idle);
+ return;
+ }
+ }
+
+
+ if(_state == _st_respond)
+ {
+
+ //0: The Slave Address
+ //1: The Function Code 16 (Preset Multiple Registers, 10 hex - 16 )
+ //2..3: The Data Address of the first register.
+ //4..5: The number of registers written.
+ //6..7: The CRC (cyclic redundancy check) for error checking.
+ if(_hdr.fcode == _fc_write_regs)
+ {
+ mb_exception_t res = reg_write(_hdr.first_reg, _hdr.nr_regs, _rcvBuff);
+
+ if(res != mb_ok)
+ {
+ mb_exception(mb_illegal_address,_st_idle);
+ return;
+ }
+
+ //respond
+ uint8_t rsp[6];
+ mb_rsp_header(rsp);
+ mb_send_msg(rsp,6);
+
+ _state = _st_idle;
+ }
+
+ // 0: The Slave Address
+ // 1: The Function Code 3 (read Analog Output Holding Registers)
+ // 2: The number of data bytes to follow (=nr_regs*2)
+ // 3..n: The contents of the registers
+ // n+1..n+2: The CRC (cyclic redundancy check).
+ if(_hdr.fcode == _fc_read_regs)
+ {
+ _rcvBuff[0] = _hdr.slave; //reuse to save memory
+ _rcvBuff[1] = _hdr.fcode;
+ _rcvBuff[2] = _hdr.nr_regs * 2;
+
+ mb_reg_read(_hdr.first_reg, _hdr.nr_regs, &_rcvBuff[3]);
+
+ mb_send_msg(_rcvBuff, 3 + _hdr.nr_regs * 2);
+
+ _state = _st_idle;
+ }
+
+ }
+
+}
diff --git a/Src/setup.c b/Src/setup.c
index 29d7498b..0550b2d8 100644
--- a/Src/setup.c
+++ b/Src/setup.c
@@ -17,96 +17,16 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see .
*/
-
-/*
-tim1 master, enable -> trgo
-tim8, gated slave mode, trgo by tim1 trgo. overflow -> trgo
-adc1,adc2 triggered by tim8 trgo
-adc 1,2 dual mode
-
-ADC1 ADC2
-R_Blau PC4 CH14 R_Gelb PC5 CH15
-L_Grün PA0 CH01 L_Blau PC3 CH13
-R_DC PC1 CH11 L_DC PC0 CH10
-BAT PC2 CH12 L_TX PA2 CH02
-BAT PC2 CH12 L_RX PA3 CH03
-
-pb10 usart3 dma1 channel2/3
-*/
-
#include "defines.h"
#include "config.h"
TIM_HandleTypeDef htim_right;
TIM_HandleTypeDef htim_left;
+TIM_HandleTypeDef htim_control;
ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2;
volatile adc_buf_t adc_buffer;
-void UART_Init() {
- __HAL_RCC_USART3_CLK_ENABLE();
- __HAL_RCC_DMA1_CLK_ENABLE();
-
- UART_HandleTypeDef huart3;
- huart3.Instance = USART3;
- huart3.Init.BaudRate = DEBUG_BAUD;
- huart3.Init.WordLength = UART_WORDLENGTH_8B;
- huart3.Init.StopBits = UART_STOPBITS_1;
- huart3.Init.Parity = UART_PARITY_NONE;
- huart3.Init.Mode = UART_MODE_TX;
- huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
- huart3.Init.OverSampling = UART_OVERSAMPLING_16;
- HAL_UART_Init(&huart3);
-
- USART3->CR3 |= USART_CR3_DMAT; // | USART_CR3_DMAR | USART_CR3_OVRDIS;
-
- GPIO_InitTypeDef GPIO_InitStruct;
- GPIO_InitStruct.Pin = GPIO_PIN_10;
- GPIO_InitStruct.Pull = GPIO_PULLUP;
- GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
- HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
-
- DMA1_Channel2->CCR = 0;
- DMA1_Channel2->CPAR = (uint32_t) & (USART3->DR);
- DMA1_Channel2->CNDTR = 0;
- DMA1_Channel2->CCR = DMA_CCR_MINC | DMA_CCR_DIR;
- DMA1->IFCR = DMA_IFCR_CTCIF2 | DMA_IFCR_CHTIF2 | DMA_IFCR_CGIF2;
-}
-
-/*
-void UART_Init() {
- __HAL_RCC_USART2_CLK_ENABLE();
- __HAL_RCC_DMA1_CLK_ENABLE();
-
- UART_HandleTypeDef huart2;
- huart2.Instance = USART2;
- huart2.Init.BaudRate = 115200;
- huart2.Init.WordLength = UART_WORDLENGTH_8B;
- huart2.Init.StopBits = UART_STOPBITS_1;
- huart2.Init.Parity = UART_PARITY_NONE;
- huart2.Init.Mode = UART_MODE_TX;
- huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
- huart2.Init.OverSampling = UART_OVERSAMPLING_16;
- HAL_UART_Init(&huart2);
-
- USART2->CR3 |= USART_CR3_DMAT; // | USART_CR3_DMAR | USART_CR3_OVRDIS;
-
- GPIO_InitTypeDef GPIO_InitStruct;
- GPIO_InitStruct.Pin = GPIO_PIN_2;
- GPIO_InitStruct.Pull = GPIO_PULLUP;
- GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
- HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
-
- DMA1_Channel7->CCR = 0;
- DMA1_Channel7->CPAR = (uint32_t) & (USART3->DR);
- DMA1_Channel7->CNDTR = 0;
- DMA1_Channel7->CCR = DMA_CCR_MINC | DMA_CCR_DIR;
- DMA1->IFCR = DMA_IFCR_CTCIF7 | DMA_IFCR_CHTIF7 | DMA_IFCR_CGIF7;
-}
-*/
-
void MX_GPIO_Init(void) {
GPIO_InitTypeDef GPIO_InitStruct;
@@ -115,27 +35,30 @@ void MX_GPIO_Init(void) {
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
- GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ //general GPIO struct init
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ //Digital Input pins
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+
GPIO_InitStruct.Pin = LEFT_HALL_U_PIN;
- HAL_GPIO_Init(LEFT_HALL_U_PORT, &GPIO_InitStruct);
+ HAL_GPIO_Init(LEFT_HALL_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = LEFT_HALL_V_PIN;
- HAL_GPIO_Init(LEFT_HALL_V_PORT, &GPIO_InitStruct);
+ HAL_GPIO_Init(LEFT_HALL_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = LEFT_HALL_W_PIN;
- HAL_GPIO_Init(LEFT_HALL_W_PORT, &GPIO_InitStruct);
+ HAL_GPIO_Init(LEFT_HALL_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = RIGHT_HALL_U_PIN;
- HAL_GPIO_Init(RIGHT_HALL_U_PORT, &GPIO_InitStruct);
+ HAL_GPIO_Init(RIGHT_HALL_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = RIGHT_HALL_V_PIN;
- HAL_GPIO_Init(RIGHT_HALL_V_PORT, &GPIO_InitStruct);
+ HAL_GPIO_Init(RIGHT_HALL_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = RIGHT_HALL_W_PIN;
- HAL_GPIO_Init(RIGHT_HALL_W_PORT, &GPIO_InitStruct);
+ HAL_GPIO_Init(RIGHT_HALL_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = CHARGER_PIN;
HAL_GPIO_Init(CHARGER_PORT, &GPIO_InitStruct);
@@ -144,6 +67,7 @@ void MX_GPIO_Init(void) {
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
+ //output push-pull pins
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pin = LED_PIN;
@@ -156,8 +80,10 @@ void MX_GPIO_Init(void) {
HAL_GPIO_Init(OFF_PORT, &GPIO_InitStruct);
+ //analog IO pins
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ //Current / Phase sense and battery measurements
GPIO_InitStruct.Pin = LEFT_DC_CUR_PIN;
HAL_GPIO_Init(LEFT_DC_CUR_PORT, &GPIO_InitStruct);
@@ -179,14 +105,11 @@ void MX_GPIO_Init(void) {
GPIO_InitStruct.Pin = DCLINK_PIN;
HAL_GPIO_Init(DCLINK_PORT, &GPIO_InitStruct);
- //Analog in
- GPIO_InitStruct.Pin = GPIO_PIN_3;
- HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
- GPIO_InitStruct.Pin = GPIO_PIN_2;
- HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+ //alternate function push-pull
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ //left MTR timer HI pins
GPIO_InitStruct.Pin = LEFT_TIM_UH_PIN;
HAL_GPIO_Init(LEFT_TIM_UH_PORT, &GPIO_InitStruct);
@@ -196,6 +119,7 @@ void MX_GPIO_Init(void) {
GPIO_InitStruct.Pin = LEFT_TIM_WH_PIN;
HAL_GPIO_Init(LEFT_TIM_WH_PORT, &GPIO_InitStruct);
+ //left MTR timer LO pins
GPIO_InitStruct.Pin = LEFT_TIM_UL_PIN;
HAL_GPIO_Init(LEFT_TIM_UL_PORT, &GPIO_InitStruct);
@@ -205,6 +129,7 @@ void MX_GPIO_Init(void) {
GPIO_InitStruct.Pin = LEFT_TIM_WL_PIN;
HAL_GPIO_Init(LEFT_TIM_WL_PORT, &GPIO_InitStruct);
+ //right MTR timer HI pins
GPIO_InitStruct.Pin = RIGHT_TIM_UH_PIN;
HAL_GPIO_Init(RIGHT_TIM_UH_PORT, &GPIO_InitStruct);
@@ -214,6 +139,7 @@ void MX_GPIO_Init(void) {
GPIO_InitStruct.Pin = RIGHT_TIM_WH_PIN;
HAL_GPIO_Init(RIGHT_TIM_WH_PORT, &GPIO_InitStruct);
+ //right MTR timer LO pins
GPIO_InitStruct.Pin = RIGHT_TIM_UL_PIN;
HAL_GPIO_Init(RIGHT_TIM_UL_PORT, &GPIO_InitStruct);
@@ -224,6 +150,28 @@ void MX_GPIO_Init(void) {
HAL_GPIO_Init(RIGHT_TIM_WL_PORT, &GPIO_InitStruct);
}
+
+void control_timer_init(void)
+{
+ __HAL_RCC_TIM3_CLK_ENABLE();
+
+ htim_control.Instance = CTRL_TIM;
+ htim_control.Init.Prescaler = 0;
+ htim_control.Init.CounterMode = TIM_COUNTERMODE_UP;
+ htim_control.Init.Period = 0xFFFF;
+ htim_control.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ htim_control.Init.RepetitionCounter = 0;
+ htim_control.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+
+ HAL_TIM_PWM_Init(&htim_control);
+
+ HAL_NVIC_SetPriority(TIM3_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(TIM3_IRQn);
+
+ HAL_TIM_Base_Start_IT(&htim_control);
+}
+
+
void MX_TIM_Init(void) {
__HAL_RCC_TIM1_CLK_ENABLE();
__HAL_RCC_TIM8_CLK_ENABLE();
@@ -325,6 +273,8 @@ void MX_TIM_Init(void) {
__HAL_TIM_ENABLE(&htim_right);
}
+
+/* ADC1 init function */
void MX_ADC1_Init(void) {
ADC_MultiModeTypeDef multimode;
ADC_ChannelConfTypeDef sConfig;
@@ -337,42 +287,38 @@ void MX_ADC1_Init(void) {
hadc1.Init.DiscontinuousConvMode = DISABLE;
hadc1.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T8_TRGO;
hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
- hadc1.Init.NbrOfConversion = 5;
+ hadc1.Init.NbrOfConversion = 4;
HAL_ADC_Init(&hadc1);
+
/**Enable or disable the remapping of ADC1_ETRGREG:
* ADC1 External Event regular conversion is connected to TIM8 TRG0
*/
__HAL_AFIO_REMAP_ADC1_ETRGREG_ENABLE();
- /**Configure the ADC multi-mode
- */
+ //Configure the ADC multi-mode
multimode.Mode = ADC_DUALMODE_REGSIMULT;
HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode);
sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5;
- sConfig.Channel = ADC_CHANNEL_14;
+ sConfig.Channel = ADC_CHANNEL_14; //right motor phase B sense
sConfig.Rank = 1;
HAL_ADC_ConfigChannel(&hadc1, &sConfig);
- sConfig.Channel = ADC_CHANNEL_0;
+ sConfig.Channel = ADC_CHANNEL_0; //left motor phase A sense
sConfig.Rank = 2;
HAL_ADC_ConfigChannel(&hadc1, &sConfig);
sConfig.SamplingTime = ADC_SAMPLETIME_13CYCLES_5;
- sConfig.Channel = ADC_CHANNEL_11;
+ sConfig.Channel = ADC_CHANNEL_11; //right motor shunt current
sConfig.Rank = 3;
HAL_ADC_ConfigChannel(&hadc1, &sConfig);
- sConfig.Channel = ADC_CHANNEL_12;
+ sConfig.Channel = ADC_CHANNEL_12; //v-battery
sConfig.Rank = 4;
HAL_ADC_ConfigChannel(&hadc1, &sConfig);
- sConfig.Channel = ADC_CHANNEL_12;
- sConfig.Rank = 5;
- HAL_ADC_ConfigChannel(&hadc1, &sConfig);
-
hadc1.Instance->CR2 |= ADC_CR2_DMA;
__HAL_ADC_ENABLE(&hadc1);
@@ -380,59 +326,61 @@ void MX_ADC1_Init(void) {
__HAL_RCC_DMA1_CLK_ENABLE();
DMA1_Channel1->CCR = 0;
- DMA1_Channel1->CNDTR = 5;
- DMA1_Channel1->CPAR = (uint32_t) & (ADC1->DR);
+ DMA1_Channel1->CNDTR = 4;
+ DMA1_Channel1->CPAR = (uint32_t)&(ADC1->DR);
DMA1_Channel1->CMAR = (uint32_t)&adc_buffer;
- DMA1_Channel1->CCR = DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1 | DMA_CCR_MINC | DMA_CCR_CIRC | DMA_CCR_TCIE;
+
+ //ADC DMA settings:
+ //Mem size 32-bit,
+ //Peripheral size 32-bit, I
+ //Increment memory address,
+ //Circular operation,
+ //Peripheral-to-memory
+ //Transfer complete interrupt
+ //Priority level high
+ DMA1_Channel1->CCR = DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1 | DMA_CCR_MINC | DMA_CCR_CIRC | DMA_CCR_TCIE | DMA_CCR_PL_1;
DMA1_Channel1->CCR |= DMA_CCR_EN;
HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn);
}
+
/* ADC2 init function */
void MX_ADC2_Init(void) {
ADC_ChannelConfTypeDef sConfig;
__HAL_RCC_ADC2_CLK_ENABLE();
- // HAL_ADC_DeInit(&hadc2);
- // hadc2.Instance->CR2 = 0;
- /**Common config
- */
hadc2.Instance = ADC2;
hadc2.Init.ScanConvMode = ADC_SCAN_ENABLE;
hadc2.Init.ContinuousConvMode = DISABLE;
hadc2.Init.DiscontinuousConvMode = DISABLE;
hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
- hadc2.Init.NbrOfConversion = 5;
+ hadc2.Init.NbrOfConversion = 4;
HAL_ADC_Init(&hadc2);
sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5;
- sConfig.Channel = ADC_CHANNEL_15;
+ sConfig.Channel = ADC_CHANNEL_15; //right motor phace C sense
sConfig.Rank = 1;
HAL_ADC_ConfigChannel(&hadc2, &sConfig);
- sConfig.Channel = ADC_CHANNEL_13;
+ sConfig.Channel = ADC_CHANNEL_13; //left motor phace B sense
sConfig.Rank = 2;
HAL_ADC_ConfigChannel(&hadc2, &sConfig);
sConfig.SamplingTime = ADC_SAMPLETIME_13CYCLES_5;
- sConfig.Channel = ADC_CHANNEL_10;
+ sConfig.Channel = ADC_CHANNEL_10; //left motor shunt current
sConfig.Rank = 3;
HAL_ADC_ConfigChannel(&hadc2, &sConfig);
- sConfig.Channel = ADC_CHANNEL_2;
+ sConfig.Channel = ADC_CHANNEL_TEMPSENSOR; //internal temperature
sConfig.Rank = 4;
HAL_ADC_ConfigChannel(&hadc2, &sConfig);
- sConfig.Channel = ADC_CHANNEL_3;
- sConfig.Rank = 5;
- HAL_ADC_ConfigChannel(&hadc2, &sConfig);
-
hadc2.Instance->CR2 |= ADC_CR2_DMA;
__HAL_ADC_ENABLE(&hadc2);
}
diff --git a/Src/stm32f1xx_it.c b/Src/stm32f1xx_it.c
index a487d147..3c32bda9 100644
--- a/Src/stm32f1xx_it.c
+++ b/Src/stm32f1xx_it.c
@@ -165,11 +165,6 @@ void SysTick_Handler(void) {
}
-void EXTI3_IRQHandler(void)
-{
- PPM_ISR_Callback();
- __HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_3);
-}
/******************************************************************************/
/* STM32F1xx Peripheral Interrupt Handlers */
diff --git a/Src/uart.c b/Src/uart.c
new file mode 100644
index 00000000..6ac3cfb4
--- /dev/null
+++ b/Src/uart.c
@@ -0,0 +1,499 @@
+/*
+ * uart.c
+ *
+ * Created on: Apr 12, 2018
+ * Author: tomvoc
+ */
+
+#include "uart.h"
+#include "string.h"
+#include "defines.h"
+
+volatile uint8_t uart2_rx[UART2_RX_FIFO_SIZE]={0};
+uint8_t uart2_tx[UART2_TX_FIFO_SIZE]={0};
+volatile uint8_t uart3_rx[UART3_RX_FIFO_SIZE]={0};
+uint8_t uart3_tx[UART3_TX_FIFO_SIZE]={0};
+
+UART_HandleTypeDef huart2;
+UART_HandleTypeDef huart3;
+
+#define UART2_RX_DMA (DMA1_Channel6)
+#define UART2_TX_DMA (DMA1_Channel7)
+
+#define UART3_RX_DMA (DMA1_Channel3)
+#define UART3_TX_DMA (DMA1_Channel2)
+
+uint32_t pRxUart2 = 0;
+uint32_t pRxUart3 = 0;
+uint32_t pTxUart2 = 0;
+uint32_t pTxUart3 = 0;
+uint32_t uart2_tx_size = 0;
+uint32_t uart3_tx_size = 0;
+
+void UART_Init()
+{
+
+ __HAL_RCC_USART2_CLK_ENABLE();
+ __HAL_RCC_USART3_CLK_ENABLE();
+ __HAL_RCC_DMA1_CLK_ENABLE();
+
+ huart2.Instance = USART2;
+ huart2.Init.BaudRate = UART2_BAUD;
+ huart2.Init.WordLength = UART_WORDLENGTH_8B;
+ huart2.Init.StopBits = UART_STOPBITS_1;
+ huart2.Init.Parity = UART_PARITY_NONE;
+ huart2.Init.Mode = UART_MODE_TX_RX;
+ huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart2.Init.OverSampling = UART_OVERSAMPLING_16;
+ HAL_UART_Init(&huart2);
+
+ huart3.Instance = USART3;
+ huart3.Init.BaudRate = UART3_BAUD;
+ huart3.Init.WordLength = UART_WORDLENGTH_8B;
+ huart3.Init.StopBits = UART_STOPBITS_1;
+ huart3.Init.Parity = UART_PARITY_NONE;
+ huart3.Init.Mode = UART_MODE_TX_RX;
+ huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart3.Init.OverSampling = UART_OVERSAMPLING_16;
+ HAL_UART_Init(&huart3);
+
+ //enable DMA tx/rx for both UART channels
+ USART2->CR3 |= USART_CR3_DMAT | USART_CR3_DMAR;
+ USART3->CR3 |= USART_CR3_DMAT | USART_CR3_DMAR;
+
+ //USART2 GPIO Configuration PA2=TX, PA3=RX
+ //USART3 GPIO Configuration PB10=TX, PB11=RX
+ GPIO_InitTypeDef GPIO_InitStruct;
+
+ //Init TX GPIO's
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Pin = GPIO_PIN_2;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+ GPIO_InitStruct.Pin = GPIO_PIN_10;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ //Init RX GPIO's
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_INPUT;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Pin = GPIO_PIN_3;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+ GPIO_InitStruct.Pin = GPIO_PIN_11;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ //Setup UART2/UART3 RX DMA as follows:
+ //Mem size 8-bit, Peripheral size 8-bit, Increment memory address,
+ //Circular operation, Peripheral-to-memory, Transfer complete interrupt
+ //Priority level medium
+ UART2_RX_DMA->CCR = 0;
+ UART2_RX_DMA->CNDTR = UART2_RX_FIFO_SIZE;
+ UART2_RX_DMA->CPAR = (uint32_t)&(USART2->DR);
+ UART2_RX_DMA->CMAR = (uint32_t)uart2_rx;
+ UART2_RX_DMA->CCR = DMA_CCR_MINC | DMA_CCR_CIRC | DMA_CCR_TCIE | DMA_CCR_PL_0;
+ DMA1->IFCR = DMA_IFCR_CTCIF2 | DMA_IFCR_CHTIF2 | DMA_IFCR_CGIF2;
+
+ UART3_RX_DMA->CCR = 0;
+ UART3_RX_DMA->CNDTR = UART3_RX_FIFO_SIZE;
+ UART3_RX_DMA->CPAR = (uint32_t)&(USART3->DR);
+ UART3_RX_DMA->CMAR = (uint32_t)uart3_rx;
+ UART3_RX_DMA->CCR = DMA_CCR_MINC | DMA_CCR_CIRC | DMA_CCR_TCIE | DMA_CCR_PL_0;
+ DMA1->IFCR = DMA_IFCR_CTCIF3 | DMA_IFCR_CHTIF3 | DMA_IFCR_CGIF3;
+
+ //clear pending DMA interrupt flags
+ DMA1->IFCR = DMA_IFCR_CGIF6;
+ DMA1->IFCR = DMA_IFCR_CGIF3;
+
+ HAL_NVIC_SetPriority(DMA1_Channel6_IRQn, 5, 5);
+ HAL_NVIC_EnableIRQ(DMA1_Channel6_IRQn);
+ HAL_NVIC_SetPriority(DMA1_Channel3_IRQn, 5, 5);
+ HAL_NVIC_EnableIRQ(DMA1_Channel3_IRQn);
+
+ //Setup UART2/UART3 TX DMA as follows:
+ //Mem size 8-bit, Peripheral size 8-bit, Increment memory address,
+ //Non-circular operation, Memory-to-peripheral, transfer complete interrupt
+ //Priority level low
+ UART2_TX_DMA->CCR = 0;
+ UART2_TX_DMA->CNDTR = 0;
+ UART2_TX_DMA->CPAR = (uint32_t)&(USART2->DR);
+ UART2_TX_DMA->CMAR = (uint32_t)uart2_tx;
+ UART2_TX_DMA->CCR = DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE;
+ DMA1->IFCR = DMA_IFCR_CTCIF4 | DMA_IFCR_CHTIF4 | DMA_IFCR_CGIF4;
+
+ UART3_TX_DMA->CCR = 0;
+ UART3_TX_DMA->CNDTR = 0;
+ UART3_TX_DMA->CPAR = (uint32_t)&(USART3->DR);
+ UART3_TX_DMA->CMAR = (uint32_t)uart3_tx;
+ UART3_TX_DMA->CCR = DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE;
+ DMA1->IFCR = DMA_IFCR_CTCIF5 | DMA_IFCR_CHTIF5 | DMA_IFCR_CGIF5;
+
+ //clear pending DMA interrupt flags
+ DMA1->IFCR = DMA_IFCR_CGIF7;
+ DMA1->IFCR = DMA_IFCR_CGIF2;
+
+ HAL_NVIC_SetPriority(DMA1_Channel7_IRQn, 6, 6);
+ HAL_NVIC_EnableIRQ(DMA1_Channel7_IRQn);
+ HAL_NVIC_SetPriority(DMA1_Channel2_IRQn, 6, 6);
+ HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn);
+
+}
+
+void UARTRxEnable(UART_ch_t uartCh, uint8_t enable)
+{
+ switch(uartCh)
+ {
+ case UARTCh2:
+ if(enable)
+ UART2_RX_DMA->CCR |= DMA_CCR_EN;
+ else
+ UART2_RX_DMA->CCR &= ~DMA_CCR_EN;
+ break;
+
+ case UARTCh3:
+ if(enable)
+ UART3_RX_DMA->CCR |= DMA_CCR_EN;
+ else
+ UART3_RX_DMA->CCR &= ~DMA_CCR_EN;
+ break;
+ }
+}
+
+
+int UARTRead(UART_ch_t uartCh, uint8_t* buff, uint32_t len)
+{
+ int result = -1;
+ uint32_t readCnt = MIN(len,UARTRxAvailable(uartCh));
+
+ switch(uartCh)
+ {
+ case UARTCh2:
+ for(int i =0; iCNDTR;
+
+ if(pRxUart2 > pDMA) //if write position has come around
+ {
+ result = UART2_RX_FIFO_SIZE - pRxUart2; //items readPos until end
+ result += pDMA; //+items 0-writePos
+ }
+ else if ( pRxUart2 < pDMA) //if writePos is leading readPos
+ {
+ result = pDMA - pRxUart2; //items between read and write pos
+ }
+
+ break;
+
+ case UARTCh3:
+ //write position of DMA
+ pDMA = UART3_RX_FIFO_SIZE - UART3_RX_DMA->CNDTR;
+
+ if(pRxUart3 > pDMA) //if write position has come around
+ {
+ result = UART3_RX_FIFO_SIZE - pRxUart3; //items readPos until end
+ result += pDMA; //+items 0-writePos
+ }
+ else if ( pRxUart3 < pDMA) //if writePos is leading readPos
+ {
+ result = pDMA - pRxUart3; //items between read and write pos
+ }
+ break;
+ }
+
+ return result;
+}
+
+
+uint32_t UARTTxAvailable(UART_ch_t uartCh)
+{
+ uint32_t result = 0;
+ uint32_t pDMA = 0;
+
+ switch(uartCh)
+ {
+ case UARTCh2:
+ //read position of DMA
+ pDMA = (UART2_TX_DMA->CMAR-(uint32_t)uart2_tx) + uart2_tx_size - UART2_TX_DMA->CNDTR;
+
+ if(pTxUart2 > pDMA)
+ {
+ result = UART2_TX_FIFO_SIZE - pTxUart2; //items write pos until end
+ result += pDMA; //+items 0-dma read position
+ }
+ else if ( pTxUart2 < pDMA) //if write position has come around, but DMA has not
+ {
+ result = pDMA - pTxUart2; //items between write pos and DMA
+ }
+ else
+ {
+ result = UART2_TX_FIFO_SIZE;
+ }
+
+ break;
+
+ case UARTCh3:
+ //read position of DMA
+ pDMA = (UART3_TX_DMA->CMAR-(uint32_t)uart3_tx) + uart3_tx_size - UART3_TX_DMA->CNDTR;
+
+ if(pTxUart3 > pDMA)
+ {
+ result = UART3_TX_FIFO_SIZE - pTxUart3; //items write pos until end
+ result += pDMA; //+items 0-dma read position
+ }
+ else if ( pTxUart3 < pDMA) //if write position has come around, but DMA has not
+ {
+ result = pDMA - pTxUart3; //items between write pos and DMA
+ }
+ else
+ {
+ result = UART3_TX_FIFO_SIZE;
+ }
+ }
+
+ return result;
+}
+
+
+int UARTQueue(UART_ch_t uartCh, const uint8_t *buff, uint32_t len)
+{
+ int writeCnt = MIN(len,UARTTxAvailable(uartCh));
+
+ switch(uartCh)
+ {
+ case UARTCh2:
+ for(int i =0; iCMAR-(uint32_t)uart2_tx) + uart2_tx_size - UART2_TX_DMA->CNDTR;
+
+ if(len > 0)
+ {
+ if(pDMA == UART2_TX_FIFO_SIZE) //if we reached end of buffer
+ {
+ pStart = 0;
+ }
+ else if(pDMA + len < UART2_TX_FIFO_SIZE) //if amount to send is within buffer limits
+ {
+ pStart = pDMA;
+ }
+ else if(pDMA + len >= UART2_TX_FIFO_SIZE )
+ {
+ pStart = pDMA;
+ len = UART2_TX_FIFO_SIZE - pDMA;
+ }
+
+ uart2_tx_size = len;
+ UART2_TX_DMA->CCR &= ~DMA_CCR_EN;
+ UART2_TX_DMA->CNDTR = uart2_tx_size;
+ UART2_TX_DMA->CMAR = (uint32_t)&uart2_tx[pStart];
+ UART2_TX_DMA->CCR |= DMA_CCR_EN;
+ }
+ break;
+
+ case UARTCh3:
+ //limit DMA size to 16 bytes to improve response time
+ len = MIN(16,UART3_TX_FIFO_SIZE - UARTTxAvailable(uartCh));
+ pDMA = (UART3_TX_DMA->CMAR-(uint32_t)uart3_tx) + uart3_tx_size - UART3_TX_DMA->CNDTR;;
+
+ if(len > 0)
+ {
+ if(pDMA == UART3_TX_FIFO_SIZE) //if we reached end of buffer
+ {
+ pStart = 0;
+ }
+ else if(pDMA + len < UART3_TX_FIFO_SIZE) //if amount to send is within buffer limits
+ {
+ pStart = pDMA;
+ }
+ else if(pDMA + len >= UART3_TX_FIFO_SIZE )
+ {
+ pStart = pDMA;
+ len = UART3_TX_FIFO_SIZE - pDMA;
+ }
+
+ uart3_tx_size = len;
+ UART3_TX_DMA->CCR &= ~DMA_CCR_EN;
+ UART3_TX_DMA->CNDTR = uart3_tx_size;
+ UART3_TX_DMA->CMAR = (uint32_t)&uart3_tx[pStart];
+ UART3_TX_DMA->CCR |= DMA_CCR_EN;
+ }
+ break;
+ }
+
+ return len;
+}
+
+
+int UARTSend(UART_ch_t uartCh, const uint8_t *buff, uint32_t len)
+{
+
+ int result = UARTQueue(uartCh, buff, len);
+
+ if(result > 0){
+ switch(uartCh)
+ {
+ case UARTCh2:
+ if(UART2_TX_DMA->CNDTR == 0)
+ UARTStartTx(uartCh);
+ break;
+
+ case UARTCh3:
+ if(UART3_TX_DMA->CNDTR == 0)
+ UARTStartTx(uartCh);
+ break;
+ }
+ }
+
+ return result;
+
+}
+
+
+void UARTFlushRX(UART_ch_t uartCh)
+{
+ switch(uartCh)
+ {
+ case UARTCh2:
+ pRxUart2 = UART2_RX_FIFO_SIZE - UART2_RX_DMA->CNDTR;
+ break;
+ case UARTCh3:
+ pRxUart3 = UART3_RX_FIFO_SIZE - UART3_RX_DMA->CNDTR;
+ break;
+ }
+}
+
+void UARTFlushTX(UART_ch_t uartCh)
+{
+ //just stop DMA
+ switch(uartCh)
+ {
+ case UARTCh2:
+ HAL_NVIC_DisableIRQ(DMA1_Channel7_IRQn);
+ UART2_TX_DMA->CCR &= ~DMA_CCR_EN;
+ UART2_TX_DMA->CNDTR = 0;
+ UART2_TX_DMA->CMAR = (uint32_t)uart2_tx;
+ uart2_tx_size = 0;
+ pTxUart2 = 0;
+ HAL_NVIC_EnableIRQ(DMA1_Channel7_IRQn);
+ break;
+ case UARTCh3:
+ HAL_NVIC_DisableIRQ(DMA1_Channel2_IRQn);
+ UART3_TX_DMA->CCR &= ~DMA_CCR_EN;
+ UART3_TX_DMA->CNDTR = 0;
+ UART3_TX_DMA->CMAR = (uint32_t)uart3_tx;
+ uart3_tx_size = 0;
+ pTxUart3 = 0;
+ HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn);
+ break;
+ }
+}
+
+int UARTSendStr(UART_ch_t uartCh, const char *msg)
+{
+ return UARTSend(uartCh, (uint8_t *)msg, strlen(msg));
+}
+
+int UARTTXReady(UART_ch_t uartCh)
+{
+ int result = -1;
+ switch(uartCh)
+ {
+ case UARTCh2:
+ result = (UART2_TX_DMA->CNDTR == 0) ? 0 : -1;
+ break;
+ case UARTCh3:
+ result = (UART3_TX_DMA->CNDTR == 0) ? 0 : -1;
+ break;
+ }
+
+ return result;
+}
+
+
+
+//will be called every 64 received bytes, update FIFO info here
+void DMA1_Channel6_IRQHandler(void) //UART2-RX
+{
+ DMA1->IFCR = DMA_IFCR_CGIF6;
+}
+
+//will be called every 64 reveived bytes, update FIFO info here
+void DMA1_Channel3_IRQHandler(void) //UART3-RX
+{
+ DMA1->IFCR = DMA_IFCR_CGIF3;
+}
+
+//update TX FIFO info and restart DMA here
+void DMA1_Channel7_IRQHandler(void) //UART2-TX
+{
+ DMA1->IFCR = DMA_IFCR_CGIF7;
+ UARTStartTx(UARTCh2);
+}
+
+//update TX FIFO info and restart DMA here
+void DMA1_Channel2_IRQHandler(void) //UART3-TX
+{
+ DMA1->IFCR = DMA_IFCR_CGIF2;
+ UARTStartTx(UARTCh3);
+}
+
+
+
diff --git a/build/hover.hex b/build/hover.hex
deleted file mode 100644
index 33c30136..00000000
--- a/build/hover.hex
+++ /dev/null
@@ -1,1312 +0,0 @@
-:020000040800F2
-:1000000000C00020653A0008253A0008293A000897
-:100010002D3A0008313A0008353A00080000000087
-:10002000000000000000000000000000393A000855
-:100030003D3A000800000000413A0008453A000837
-:10004000AD3A0008AD3A0008AD3A0008AD3A0008F4
-:10005000AD3A0008AD3A0008AD3A0008AD3A0008E4
-:10006000AD3A0008513A0008AD3A0008E132000804
-:10007000AD3A0008AD3A0008AD3A0008AD3A0008C4
-:10008000AD3A0008AD3A0008AD3A0008AD3A0008B4
-:10009000AD3A0008AD3A0008AD3A0008AD3A0008A4
-:1000A000AD3A0008AD3A0008AD3A0008AD3A000894
-:1000B000AD3A0008AD3A0008AD3A0008AD3A000884
-:1000C000AD3A0008AD3A0008AD3A0008AD3A000874
-:1000D000AD3A0008AD3A0008AD3A0008AD3A000864
-:1000E000AD3A0008AD3A0008AD3A0008AD3A000854
-:1000F000AD3A0008AD3A0008AD3A0008AD3A000844
-:10010000AD3A0008AD3A0008AD3A0008AD3A000833
-:10011000AD3A0008AD3A0008AD3A0008AD3A000823
-:10012000AD3A0008AD3A0008AD3A0008AD3A000813
-:1001300000000000000000000000000000000000BF
-:1001400000000000000000000000000000000000AF
-:10015000000000000000000000000000000000009F
-:10016000000000000000000000000000000000008F
-:10017000000000000000000000000000000000007F
-:10018000000000000000000000000000000000006F
-:10019000000000000000000000000000000000005F
-:1001A000000000000000000000000000000000004F
-:1001B000000000000000000000000000000000003F
-:1001C000000000000000000000000000000000002F
-:1001D000000000000000000000000000000000001F
-:0401E0005FF8E0F1F3
-:1001E800044B05481B1A062B02D9044B03B11847C8
-:1001F800704700BF8B00002088000020000000002E
-:1002080005490648091A891001EBD171491002D035
-:10021800034B03B11847704788000020880000206E
-:100228000000000010B5064C237843B9FFF7D8FF4B
-:10023800044B13B10448AFF300800123237010BDB1
-:1002480088000020000000004450000808B5084B52
-:100258001BB108480849AFF300800848036813B980
-:10026800BDE80840CCE7064B002BF9D09847F7E7E4
-:1002780000000000445000088C0000208800002086
-:100288000000000081F0004102E000BF83F000435D
-:1002980030B54FEA41044FEA430594EA050F08BF19
-:1002A80090EA020F1FBF54EA000C55EA020C7FEADD
-:1002B800645C7FEA655C00F0E2804FEA5454D4EB5A
-:1002C8005555B8BF6D420CDD2C4480EA020281EA24
-:1002D800030382EA000083EA010180EA020281EA5C
-:1002E8000303362D88BF30BD11F0004F4FEA0131AE
-:1002F8004FF4801C4CEA113102D0404261EB4101BD
-:1003080013F0004F4FEA03334CEA133302D0524242
-:1003180063EB430394EA050F00F0A780A4F10104FE
-:10032800D5F1200E0DDB02FA0EFC22FA05F2801838
-:1003380041F1000103FA0EF2801843FA05F359411E
-:100348000EE0A5F120050EF1200E012A03FA0EFC9D
-:1003580028BF4CF0020C43FA05F3C01851EBE371C7
-:1003680001F0004507D54FF0000EDCF1000C7EEBE4
-:1003780000006EEB0101B1F5801F1BD3B1F5001F22
-:100388000CD349085FEA30004FEA3C0C04F1010441
-:100398004FEA445212F5800F80F09A80BCF1004F6A
-:1003A80008BF5FEA500C50F1000041EB045141EAEC
-:1003B800050130BD5FEA4C0C404141EB010111F4ED
-:1003C800801FA4F10104E9D191F0000F04BF014698
-:1003D8000020B1FA81F308BF2033A3F10B03B3F176
-:1003E80020020CDA0C3208DD02F1140CC2F10C0206
-:1003F80001FA0CF021FA02F10CE002F11402D8BF64
-:10040800C2F1200C01FA02F120FA0CFCDCBF41EA2F
-:100418000C019040E41AA2BF01EB0451294330BDFE
-:100428006FEA04041F3C1CDA0C340EDC04F11404DB
-:10043800C4F1200220FA04F001FA02F340EA0300B2
-:1004480021FA04F345EA030130BDC4F10C04C4F1F8
-:10045800200220FA02F001FA04F340EA03002946D8
-:1004680030BD21FA04F0294630BD94F0000F83F422
-:10047800801306BF81F480110134013D4EE77FEA05
-:10048800645C18BF7FEA655C29D094EA050F08BF51
-:1004980090EA020F05D054EA000C04BF1946104632
-:1004A80030BD91EA030F1EBF0021002030BD5FEA76
-:1004B800545C05D14000494128BF41F0004130BD9E
-:1004C80014F580043CBF01F5801130BD01F00045F2
-:1004D80045F0FE4141F470014FF0000030BD7FEA65
-:1004E800645C1ABF194610467FEA655C1CBF0B4660
-:1004F800024650EA013406BF52EA033591EA030F77
-:1005080041F4002130BD00BF90F0000F04BF00216E
-:10051800704730B54FF4806404F132044FF00005A1
-:100528004FF0000150E700BF90F0000F04BF00211A
-:10053800704730B54FF4806404F1320410F0004580
-:1005480048BF40424FF000013EE700BF42004FEA7B
-:10055800E2014FEA31014FEA02701FBF12F07F43F8
-:1005680093F07F4F81F06051704792F0000F14BFF5
-:1005780093F07F4F704730B54FF4607401F0004539
-:1005880021F0004120E700BF50EA010208BF704790
-:1005980030B54FF000050AE050EA010208BF704785
-:1005A80030B511F0004502D5404261EB41014FF4EE
-:1005B800806404F132045FEA915C3FF4DCAE4FF0F2
-:1005C80003025FEADC0C18BF03325FEADC0C18BFD9
-:1005D800033202EBDC02C2F1200300FA03FC20FA2A
-:1005E80002F001FA03FE40EA0E0021FA02F1144477
-:1005F800C1E600BF70B54FF0FF0C4CF4E06C1CEA8C
-:1006080011541DBF1CEA135594EA0C0F95EA0C0F00
-:1006180000F0DEF82C4481EA030621EA4C5123EA73
-:100628004C5350EA013518BF52EA033541F48011A2
-:1006380043F4801338D0A0FB02CE4FF00005E1FB55
-:1006480002E506F00042E0FB03E54FF00006E1FB9F
-:1006580003569CF0000F18BF4EF0010EA4F1FF04E2
-:10066800B6F5007F64F5407404D25FEA4E0E6D4122
-:1006780046EB060642EAC62141EA55514FEAC52033
-:1006880040EA5E504FEACE2EB4F1FD0C88BFBCF5AF
-:10069800E06F1ED8BEF1004F08BF5FEA500E50F160
-:1006A800000041EB045170BD06F0004646EA010126
-:1006B80040EA020081EA0301B4EB5C04C2BFD4EB58
-:1006C8000C0541EA045170BD41F480114FF0000E51
-:1006D800013C00F3AB8014F1360FDEBF002001F0BF
-:1006E800004170BDC4F10004203C35DA0C341BDC39
-:1006F80004F11404C4F1200500FA05F320FA04F00B
-:1007080001FA05F240EA020001F0004221F000413E
-:1007180010EBD37021FA04F642EB06015EEA430EB1
-:1007280008BF20EAD37070BDC4F10C04C4F12005E1
-:1007380000FA04F320FA05F001FA04F240EA020094
-:1007480001F0004110EBD37041F100015EEA430E65
-:1007580008BF20EAD37070BDC4F1200500FA05F285
-:100768004EEA020E20FA04F301FA05F243EA020304
-:1007780021FA04F001F0004121FA04F220EA020013
-:1007880000EBD3705EEA430E08BF20EAD37070BD59
-:1007980094F0000F0FD101F00046400041EB010139
-:1007A80011F4801F08BF013CF7D041EA060195F01B
-:1007B800000F18BF704703F00046520043EB0303D5
-:1007C80013F4801F08BF013DF7D043EA06037047C2
-:1007D80094EA0C0F0CEA135518BF95EA0C0F0CD0CD
-:1007E80050EA410618BF52EA4306D1D181EA030113
-:1007F80001F000414FF0000070BD50EA410606BF0D
-:100808001046194652EA430619D094EA0C0F02D151
-:1008180050EA013613D195EA0C0F05D152EA033696
-:100828001CBF104619460AD181EA030101F00041B4
-:1008380041F0FE4141F470014FF0000070BD41F0FD
-:10084800FE4141F4780170BD70B54FF0FF0C4CF4D7
-:10085800E06C1CEA11541DBF1CEA135594EA0C0FF6
-:1008680095EA0C0F00F0A7F8A4EB050481EA030E43
-:1008780052EA03354FEA013100F088804FEA03332A
-:100888004FF0805545EA131343EA12634FEA0222F8
-:1008980045EA111545EA10654FEA00260EF00041B9
-:1008A8009D4208BF964244F1FD0404F5407402D20B
-:1008B8005B084FEA3202B61A65EB03055B084FEA9C
-:1008C80032024FF480104FF4002CB6EB020E75EB99
-:1008D800030E22BFB61A754640EA0C005B084FEAC1
-:1008E8003202B6EB020E75EB030E22BFB61A75463E
-:1008F80040EA5C005B084FEA3202B6EB020E75EB89
-:10090800030E22BFB61A754640EA9C005B084FEA00
-:100918003202B6EB020E75EB030E22BFB61A75460D
-:1009280040EADC0055EA060E18D04FEA051545EAFC
-:1009380016754FEA06164FEAC30343EA52734FEAA5
-:10094800C2025FEA1C1CC0D111F4801F0BD141EA1E
-:1009580000014FF000004FF0004CB6E711F4801F83
-:1009680004BF01430020B4F1FD0C88BFBCF5E06F63
-:100978003FF6AFAEB5EB030C04BFB6EB020C5FEA73
-:10098800500C50F1000041EB045170BD0EF0004EC8
-:100998004EEA113114EB5C04C2BFD4EB0C0541EAFA
-:1009A800045170BD41F480114FF0000E013C90E6F7
-:1009B80045EA060E8DE60CEA135594EA0C0F08BFBB
-:1009C80095EA0C0F3FF43BAF94EA0C0F0AD150EABA
-:1009D80001347FF434AF95EA0C0F7FF425AF10464D
-:1009E80019462CE795EA0C0F06D152EA03353FF475
-:1009F800FDAE1046194622E750EA410618BF52EAF2
-:100A080043067FF4C5AE50EA41047FF40DAF52EAC5
-:100A180043057FF4EBAE12E74FF0FF3C06E000BF62
-:100A28004FF0010C02E000BF4FF0010C4DF804CD6F
-:100A38004FEA410C7FEA6C5C4FEA430C18BF7FEA2F
-:100A48006C5C1BD001B050EA410C0CBF52EA430C5D
-:100A580091EA030F02BF90EA020F0020704710F1DD
-:100A6800000F91EA030F58BF994208BF90422CBF6C
-:100A7800D8176FEAE37040F0010070474FEA410C65
-:100A88007FEA6C5C02D150EA013C07D14FEA430C83
-:100A98007FEA6C5CD6D152EA033CD3D05DF8040BF4
-:100AA800704700BF8446104662468C461946634626
-:100AB80000E000BF01B5FFF7B7FF002848BF10F1FD
-:100AC800000F01BD4DF808EDFFF7F4FF0CBF012042
-:100AD80000205DF808FB00BF4DF808EDFFF7EAFFBE
-:100AE80034BF012000205DF808FB00BF4DF808ED79
-:100AF800FFF7E0FF94BF012000205DF808FB00BF6E
-:100B08004DF808EDFFF7CEFF94BF012000205DF8F7
-:100B180008FB00BF4DF808EDFFF7C4FF34BF012004
-:100B280000205DF808FB00BF4FEA4102B2F1E04344
-:100B380024BFB3F5001CDCF1FE5C0DD901F0004CBC
-:100B48004FEAC0024CEA5070B2F1004F40EB83000C
-:100B580008BF20F00100704711F0804F21D113F138
-:100B68003872BCBF01F00040704741F480114FEA71
-:100B78005252C2F11802C2F1200C10FA0CF320FAFA
-:100B880002F018BF40F001004FEAC1234FEAD32317
-:100B980003FA0CFC40EA0C0023FA02F34FEA430381
-:100BA800CCE77FEA625307D150EA01331EBF4FF00A
-:100BB800FE4040F44000704701F0004040F0FE4025
-:100BC80040F40000704700BF80F0004002E000BF22
-:100BD80081F0004142001FBF5FEA410392EA030F20
-:100BE8007FEA226C7FEA236C6AD04FEA1262D2EB6A
-:100BF8001363C1BFD218414048404140B8BF5B426F
-:100C0800192B88BF704710F0004F40F4000020F007
-:100C18007F4018BF404211F0004F41F4000121F01D
-:100C28007F4118BF494292EA030F3FD0A2F1010267
-:100C380041FA03FC10EB0C00C3F1200301FA03F1A5
-:100C480000F0004302D5494260EB4000B0F5000FC8
-:100C580013D3B0F1807F06D340084FEA310102F187
-:100C68000102FE2A51D2B1F1004F40EBC25008BF39
-:100C780020F0010040EA03007047490040EB000003
-:100C880010F4000FA2F10102EDD1B0FA80FCACF132
-:100C9800080CB2EB0C0200FA0CF0AABF00EBC25031
-:100CA80052421843BCBFD0401843704792F0000F1F
-:100CB80081F4000106BF80F400000132013BB5E772
-:100CC8004FEA41037FEA226C18BF7FEA236C21D0E8
-:100CD80092EA030F04D092F0000F08BF084670474D
-:100CE80090EA010F1CBF0020704712F07F4F04D11B
-:100CF800400028BF40F00040704712F100723CBF2E
-:100D080000F50000704700F0004343F0FE4040F457
-:100D1800000070477FEA226216BF08467FEA236315
-:100D28000146420206BF5FEA412390EA010F40F400
-:100D3800800070474FF0000304E000BF10F000434C
-:100D480048BF40425FEA000C08BF704743F0964333
-:100D580001464FF000001CE050EA010208BF70474E
-:100D68004FF000030AE000BF50EA010208BF7047D5
-:100D780011F0004302D5404261EB41015FEA010CEA
-:100D880002BF84460146002043F0B64308BFA3F1E2
-:100D98008053A3F50003BCFA8CF2083AA3EBC253C4
-:100DA80010DB01FA02FC634400FA02FCC2F12002E3
-:100DB800BCF1004F20FA02F243EB020008BF20F01A
-:100DC8000100704702F1200201FA02FCC2F1200280
-:100DD80050EA4C0021FA02F243EB020008BF20EA75
-:100DE800DC7070474FF0FF0C1CEAD0521EBF1CEAA3
-:100DF800D15392EA0C0F93EA0C0F6FD01A4480EA91
-:100E0800010C400218BF5FEA41211ED04FF0006379
-:100E180043EA501043EA5111A0FB01310CF00040A5
-:100E2800B1F5000F3EBF490041EAD3715B0040EACB
-:100E3800010062F17F02FD2A1DD8B3F1004F40EB9B
-:100E4800C25008BF20F00100704790F0000F0CF06E
-:100E5800004C08BF49024CEA502040EA51207F3A32
-:100E6800C2BFD2F1FF0340EAC250704740F400000D
-:100E78004FF00003013A5DDC12F1190FDCBF00F0FE
-:100E880000407047C2F10002410021FA02F1C2F1AC
-:100E9800200200FA02FC5FEA310040F1000053EA48
-:100EA8004C0308BF20EADC70704792F0000F00F096
-:100EB800004C02BF400010F4000F013AF9D040EA9C
-:100EC8000C0093F0000F01F0004C02BF490011F430
-:100ED800000F013BF9D041EA0C018FE70CEAD1532E
-:100EE80092EA0C0F18BF93EA0C0F0AD030F0004CAE
-:100EF80018BF31F0004CD8D180EA010000F0004062
-:100F0800704790F0000F17BF90F0004F084691F01F
-:100F1800000F91F0004F14D092EA0C0F01D1420259
-:100F28000FD193EA0C0F03D14B0218BF084608D122
-:100F380080EA010000F0004040F0FE4040F400006C
-:100F4800704740F0FE4040F4400070474FF0FF0CFF
-:100F58001CEAD0521EBF1CEAD15392EA0C0F93EA46
-:100F68000C0F69D0A2EB030280EA010C49024FEA98
-:100F7800402037D04FF0805343EA111143EA101351
-:100F88000CF000408B4238BF5B0042F17D024FF409
-:100F9800000C8B4224BF5B1A40EA0C00B3EB510FE4
-:100FA80024BFA3EB510340EA5C00B3EB910F24BFCD
-:100FB800A3EB910340EA9C00B3EBD10F24BFA3EB52
-:100FC800D10340EADC001B0118BF5FEA1C1CE0D11A
-:100FD800FD2A3FF650AF8B4240EBC25008BF20F0CD
-:100FE800010070470CF0004C4CEA50207F32C2BF21
-:100FF800D2F1FF0340EAC250704740F400004FF0BE
-:101008000003013A37E792F0000F00F0004C02BFEE
-:10101800400010F4000F013AF9D040EA0C0093F0B8
-:10102800000F01F0004C02BF490011F4000F013B12
-:10103800F9D041EA0C0195E70CEAD15392EA0C0F7A
-:1010480008D142027FF47DAF93EA0C0F7FF470AFB2
-:10105800084676E793EA0C0F04D14B023FF44CAFF5
-:1010680008466EE730F0004C18BF31F0004CCAD18A
-:1010780030F000427FF45CAF31F000437FF43CAFC6
-:101088005FE700BF4FF0FF3C06E000BF4FF0010CE8
-:1010980002E000BF4FF0010C4DF804CD4FEA4002CA
-:1010A8004FEA41037FEA226C18BF7FEA236C11D014
-:1010B80001B052EA530C18BF90EA010F58BFB2EBC7
-:1010C800030088BFC81738BF6FEAE17018BF40F047
-:1010D800010070477FEA226C02D15FEA402C05D1FB
-:1010E8007FEA236CE4D15FEA412CE1D05DF8040B80
-:1010F800704700BF844608466146FFE70FB5FFF713
-:10110800C9FF002848BF10F1000F0FBD4DF808EDCA
-:10111800FFF7F4FF0CBF012000205DF808FB00BFBB
-:101128004DF808EDFFF7EAFF34BF012000205DF815
-:1011380008FB00BF4DF808EDFFF7E0FF94BF012062
-:1011480000205DF808FB00BF4DF808EDFFF7D2FF5F
-:1011580094BF012000205DF808FB00BF4DF808EDA2
-:10116800FFF7C8FF34BF012000205DF808FB00BF6F
-:101178004FEA4002B2F1FE4F0FD34FF09E03B3EB9C
-:1011880012620DD94FEA002343F0004310F0004FDC
-:1011980023FA02F018BF404270474FF00000704732
-:1011A80012F1610F01D1420205D110F0004008BFD1
-:1011B8006FF0004070474FF00000704782B0084B56
-:1011C8001B68084AA2FB03235B0A00FB03F001909B
-:1011D80000BF019B5A1E0192002BF9D102B0704743
-:1011E80000000020D34D621070B582B00446036839
-:1011F80013F0010F6BD0A84B5B6803F00C03042BB2
-:101208000AD0A54B5B6803F00C03082B0DD1A24B49
-:101218005B6813F4803F08D09F4B1B6813F4003FB2
-:1012280055D06368002B52D1B8E16368B3F5803FAD
-:1012380005D1994A136843F48033136026E063B9F3
-:1012480003F1804303F504331A6822F480321A60EC
-:101258001A6822F480221A6018E0B3F5A02F0CD186
-:1012680003F18043A3F53C331A6842F480221A60E4
-:101278001A6842F480321A6008E0874B1A6822F430
-:1012880080321A601A6822F480221A6063687BB17F
-:1012980001F01CF8054605E001F018F8401B642829
-:1012A80000F27E817C4B1B6813F4003FF4D00EE003
-:1012B80001F00CF8054605E001F008F8401B642829
-:1012C80000F27081744B1B6813F4003FF4D123685B
-:1012D80013F0020F50D0704B5B6813F00C0F0AD05C
-:1012E8006D4B5B6803F00C03082B16D16A4B5B68E7
-:1012F80013F4803F11D1684B1B6813F0020F03D021
-:101308002369012B40F05081634A136823F0F803E6
-:10131800616943EAC10313602EE02369D3B1012256
-:101328005E4B1A6000F0D2FF054605E000F0CEFFE4
-:10133800401B022800F23A81574B1B6813F0020F3A
-:10134800F4D0554A136823F0F803616943EAC103EE
-:10135800136011E00022514B1A6000F0B7FF0546F8
-:1013680005E000F0B3FF401B022800F221814A4B40
-:101378001B6813F0020FF4D1236813F0080F29D06B
-:10138800A369ABB10122464B1A6000F09FFF0546E6
-:1013980005E000F09BFF401B022800F20B813E4B4A
-:1013A8005B6A13F0020FF4D00120FFF707FF11E08A
-:1013B80000223B4B1A6000F089FF054605E000F06B
-:1013C80085FF401B022800F2F780334B5B6A13F05D
-:1013D800020FF4D1236813F0040F00F089802E4B1C
-:1013E800DB6913F0805F0BD12B4BDA6942F0805236
-:1013F800DA61DB6903F080530193019B012500E06A
-:101408000025284B1B6813F4807F13D1254A1368E5
-:1014180043F48073136000F059FF064605E000F0BE
-:1014280055FF801B642800F2C9801E4B1B6813F40B
-:10143800807FF4D0E368012B05D1174A136A43F083
-:101448000103136222E063B903F1804303F5043317
-:101458001A6A22F001021A621A6A22F004021A6257
-:1014680014E0052B09D10C4B1A6A42F004021A62E7
-:101478001A6A42F001021A6208E0074B1A6A22F05F
-:1014880001021A621A6A22F004021A62E368CBB1F6
-:1014980000F01CFF06460FE0001002400000424228
-:1014A800800442420070004000F010FF801B41F2AF
-:1014B8008833984200F28480494B1B6A13F0020F6C
-:1014C800F2D00FE000F002FF064606E000F0FEFE54
-:1014D800801B41F28833984274D8414B1B6A13F041
-:1014E800020FF3D125B13E4AD36923F08053D3616B
-:1014F800E369002B68D03A4A526802F00C02082AC5
-:1015080064D0022B37D10022364B1A6000F0DEFE81
-:10151800054604E000F0DAFE401B022858D8304B9C
-:101528001B6813F0007FF5D1236AB3F5803F06D11D
-:101538002B494B6823F40032A36813434B602848B7
-:10154800436823F47411236A626A13430B434360AC
-:101558000122244B1A6000F0B9FE044604E000F0B2
-:10156800B5FE001B022835D81D4B1B6813F0007F01
-:10157800F5D0002031E000221A4B1A6000F0A6FED8
-:10158800044604E000F0A2FE001B022824D8144BF5
-:101598001B6813F0007FF5D100201EE001201CE03D
-:1015A80003201AE0032018E0012016E0032014E0CD
-:1015B800032012E0032010E003200EE003200CE0DB
-:1015C80003200AE0032008E0002006E0012004E0F0
-:1015D800032002E0032000E0032002B070BD00BF3A
-:1015E800001002406000424230B486B0164D02AC92
-:1015F80028686968AA68EB680FC42B8AADF80430BC
-:10160800124B5A6802F00C03082B19D1C2F383431A
-:1016180006A90B4413F8103C12F4803F0CD00B4A77
-:101628005268C2F340420A4412F8140C084AB2FB4A
-:10163800F0F003FB00F004E0064800FB03F000E0D4
-:10164800034806B030BC70476050000800100240E4
-:1016580000127A0000093D0070B55C4B1B6803F06E
-:1016680007038B420BD2594A136823F007030B4335
-:101678001360136803F007038B4240F097800368F8
-:1016880013F0020F06D0524C636823F0F00283680F
-:10169800134363600D460446036813F0010F4DD0F1
-:1016A8004268012A05D14A4B1B6813F4003F0DD14B
-:1016B8007EE0022A05D1464B1B6813F0007F05D156
-:1016C80078E0434B1B6813F0020F75D040494B6814
-:1016D80023F0030313434B6000F0F8FD06466368EC
-:1016E800012B0ED106E000F0F1FD801B41F288339A
-:1016F800984263D8364B5B6803F00C03042BF2D195
-:101708001CE0022B15D106E000F0E0FD801B41F241
-:101718008833984254D82E4B5B6803F00C03082B8F
-:10172800F2D10BE000F0D2FD801B41F288339842E1
-:1017380048D8274B5B6813F00C0FF3D1234B1B6879
-:1017480003F00703AB420AD9204A136823F00703C2
-:101758002B431360136803F00703AB4234D12368AB
-:1017680013F0040F06D01A494B6823F4E062E368CB
-:1017780013434B60236813F0080F07D0144A5368CB
-:1017880023F46053216943EAC1035360FFF72CFF38
-:101798000F4B5B68C3F303130E4AD35CD8400E4B60
-:1017A8001860002000F062FD002070BD012070BDAF
-:1017B800012070BD012070BD012070BD032070BDE7
-:1017C800032070BD032070BD012070BD00200240C1
-:1017D800001002407450000800000020014B1868F7
-:1017E800704700BF0000002008B5FFF7F7FF044B63
-:1017F8005B68C3F30223034AD35CD84008BD00BF2B
-:10180800001002408450000808B5FFF7E7FF044BBA
-:101818005B68C3F3C223034AD35CD84008BD00BF4A
-:10182800001002408450000830B4036A23F001031A
-:101838000362036A4468826922F073020D682A43CE
-:1018480023F002038D682B43104DA84203D005F501
-:101858000065A84205D123F00803CD682B4323F087
-:1018680004030A4DA84203D005F50065A84205D136
-:1018780024F440744D692C438D692C434460826183
-:101888004A684263036230BC704700BF002C0140C5
-:1018980030B4036A23F480730362036A4468C2693C
-:1018A80022F073020D682A4323F400738D6843EA1B
-:1018B8000523124DA84203D005F50065A84206D1BC
-:1018C80023F40063CD6843EA052323F480630B4DBA
-:1018D800A84203D005F50065A84207D124F4405476
-:1018E8004D6944EA05148D6944EA05144460C261EF
-:1018F8004A68C263036230BC704700BF002C0140D5
-:1019080030B4036A23F480530362036A4468C269EB
-:1019180022F4E6420D6842EA052223F400538D685A
-:1019280043EA0533094DA84203D005F50065A842EE
-:1019380004D124F480444D6944EA85144460C261AA
-:101948004A680264036230BC704700BF002C014043
-:1019580010B4036A046A24F001040462846924F060
-:10196800F00444EA021223F00A0319438261016277
-:101978005DF8044B704700BF10B4036A23F01003EE
-:1019880003628469036A24F4704444EA023223F04F
-:10199800A00343EA0111826101625DF8044B7047BC
-:1019A80010B4846824F47F4442EA032319430C43A7
-:1019B80084605DF8044B704710B50C460268936864
-:1019C80023F0700349680B4323F0070321680B4396
-:1019D80093606368502B1FD002D8402B0BD010BDEA
-:1019E800602B1FD0702B22D10068E168A2682369A0
-:1019F800FFF7D6FF10BD0368196A1A6A22F00102C0
-:101A08001A620268936923F0F003246943EA041315
-:101A180093610368196210BD0068A1682269FFF725
-:101A280097FF10BD0068A1682269FFF7A5FF10BDE8
-:101A3800704700BF38B590F83C30012B18D00446E9
-:101A4800012580F83C50022380F83D30FFF7B4FFB1
-:101A58002268D36823F04003D3602268D36823F454
-:101A68008043D36084F83D50002084F83C0038BDA2
-:101A7800022038BD0368244A904212D002F5006261
-:101A880090420ED0B0F1804F0BD0A2F59832904220
-:101A980007D002F58062904203D002F5806290423E
-:101AA80003D123F070034A681343174A904212D0B7
-:101AB80002F5006290420ED0B0F1804F0BD0A2F533
-:101AC8009832904207D002F58062904203D002F526
-:101AD8008062904203D123F44073CA68134323F011
-:101AE80080034A69134303608B68C3620B6883628F
-:101AF800054B984203D003F50063984201D10B6966
-:101B08000363012343617047002C0140C0B110B545
-:101B1800044690F83D3013F0FF0F04D1002380F8FD
-:101B28003C30FFF785FF022384F83D30214651F809
-:101B3800040BFFF79FFF012384F83D30002010BD00
-:101B48000120704730B4036A23F010030362036A6C
-:101B58004468826922F4E6420D6842EA052223F0CD
-:101B680020038D6843EA0513114DA84203D005F5FB
-:101B78000065A84206D123F08003CD6843EA051327
-:101B880023F040030A4DA84203D005F50065A8429A
-:101B980007D124F440644D6944EA85048D6944EA18
-:101BA8008504446082614A688263036230BC70477E
-:101BB800002C014038B590F83C30012B66D00D461A
-:101BC8000446012380F83C30022380F83D300C2A7B
-:101BD80055D8DFE802F0075454541A5454542E547C
-:101BE800545441000068FFF71FFE2268936943F0D0
-:101BF800080393612268936923F0040393612268C0
-:101C080091692B690B43936139E00068FFF79AFFEC
-:101C18002268936943F4006393612268936923F40B
-:101C28008063936122689369296943EA0123936178
-:101C380025E00068FFF72CFE2268D36943F008030B
-:101C4800D3612268D36923F00403D3612268D16980
-:101C58002B690B43D36112E00068FFF751FE22683D
-:101C6800D36943F40063D3612268D36923F48063A2
-:101C7800D3612268D369296943EA0123D361012327
-:101C880084F83D30002084F83C0038BD022038BD7F
-:101C980010B401238B40046A24EA03030362036A35
-:101CA8008A401A4302625DF8044B704710B5044637
-:101CB80000680122FFF7ECFF23680C4A934205D025
-:101CC80002F50062934203D1012202E0012200E002
-:101CD80000221AB15A6C42F400425A64226813680E
-:101CE80043F001031360002010BD00BF002C014029
-:101CF80010B404238B40046A24EA03030362036AD2
-:101D08008A401A4302625DF8044B704710B50446D6
-:101D180000680422FFF7ECFF2268536C43F4004389
-:101D280053642268136843F001031360002010BD58
-:101D380090F83C30012B22D0012380F83C30CB684E
-:101D480023F440728B68134323F480624B68134377
-:101D580023F400620B68134323F480520B69134386
-:101D680023F400524B6913438A6923F44043134315
-:101D780002685364002380F83C30184670470220FC
-:101D8800704700BF90F83C30012B21D030B40122BD
-:101D980080F83C20022380F83D300468636823F013
-:101DA80070036360046865680B682B4363600468AC
-:101DB800A36823F08003A3600468A5684B682B43DD
-:101DC800A36080F83D20002380F83C30184601E0ED
-:101DD8000220704730BC704790F82430012B27D080
-:101DE800012380F8243003689A6812F0010F10D19B
-:101DF800124A926812F0010F0BD1114A934208D18E
-:101E080010B45A6822F470240A6822435A600023E6
-:101E180009E0836A43F0200383620123002280F8EB
-:101E2800242018467047002280F82420184601E034
-:101E3800022070475DF8044B704700BF002801403E
-:101E48000024014000F00700064AD36823F4E06349
-:101E58001B041B0C43EA002040F0BF6040F4003034
-:101E6800D060704700ED00E030B4164BDC68C4F376
-:101E78000224C4F10705042D28BF0425231D062BC1
-:101E880001D9033C00E00024012303FA05F5013DD4
-:101E98002940A140A340013B1A400A43002806DA22
-:101EA80000F00F001201D2B2074B1A5407E01201DA
-:101EB800D2B200F1604000F5614080F8002330BCE8
-:101EC800704700BF00ED00E014ED00E0410900F0AC
-:101ED8001F0001238340024A42F82130704700BFA7
-:101EE80000E100E00138B0F1807F0AD2064B58606B
-:101EF800F021064A82F823100020986007221A6011
-:101F080070470120704700BF10E000E000ED00E0DE
-:101F1800042805D1054A136843F004031360704789
-:101F2800024A136823F004031360704710E000E0CE
-:101F3800704700BF08B5FFF7FBFF08BDF0B583B0D9
-:101F480000273C46E2E00122A2400B68134093427E
-:101F580040F0DB804D68122D2DD00BD8022D27D0F4
-:101F680003D85DB3012D1ED035E0032D30D0112DDF
-:101F78001BD030E0684EB54220D008D8A6F58016B0
-:101F8800B5421BD006F58036B54224D116E0634E23
-:101F9800B54213D006F58036B5420FD0A6F58016A7
-:101FA800B54218D10AE0CF6815E0CF68043712E0CF
-:101FB800CF6808370FE0CF680C370CE08D684DB15B
-:101FC800012D02D10261082705E04261082702E0DD
-:101FD800002700E00427FF2B01D8844601E000F128
-:101FE800040CFF2B02D84FEA840E03E0A4F1080E7C
-:101FF8004FEA8E0EDCF800600F2202FA0EF226EA93
-:10200800020507FA0EF22A43CCF800204A6812F0BB
-:10201800805F7AD0424A956945F0010595619269D9
-:1020280002F001020192019AA208961C3D4D55F852
-:10203800266004F0030E4FEA8E0E0F2505FA0EF502
-:1020480026EA0506384DA8421FD005F58065A84246
-:1020580019D005F58065A84213D005F58065A8421A
-:102068000DD005F58065A84207D005F58065A84222
-:1020780001D105250AE0062508E0042506E0032528
-:1020880004E0022502E0012500E0002505FA0EF52E
-:1020980035430232234E46F822504A6812F4803FF4
-:1020A80004D0224D2A681A432A6004E01F4D2A688A
-:1020B80022EA03022A604A6812F4003F04D01B4D4A
-:1020C8006A681A436A6004E0184D6A6822EA0302E3
-:1020D8006A604A6812F4801F04D0144DAA681A4333
-:1020E800AA6004E0114DAA6822EA0302AA604A68BD
-:1020F80012F4001F04D00D4DEA681343EB6004E0AE
-:102108000A4DEA6822EA0303EB6001340F2C7FF6DC
-:102118001AAF03B0F0BD00BF00002110000031105D
-:102128000010024000000140000801400004014086
-:1021380083680B4201D0012070470020704700BF20
-:102148000AB101617047090401617047C3685940C9
-:10215800C160704770B582B00446036813F0010F80
-:102168005CD03E4BDB6913F0805F0BD13B4BDA69E7
-:1021780042F08052DA61DB6903F080530193019BDE
-:10218800012600E00026364B1B6813F4807F12D12D
-:10219800334A136843F48073136000F097F80546D8
-:1021A80004E000F093F8401B64284FD82C4B1B68C0
-:1021B80013F4807FF5D0294B1B6A13F4407321D0A8
-:1021C800626802F440729A421CD0244A136A23F4CB
-:1021D8004070244901250D6000250D60106213F040
-:1021E800010F0FD000F072F8054606E000F06EF817
-:1021F800401B41F2883398422AD8184B1B6A13F0C7
-:10220800020FF3D015490B6A23F440726368134335
-:102218000B621EB1CB6923F08053CB61236813F0A6
-:10222800020F06D00D494B6823F44042A3681343BC
-:102238004B60236813F0100F0CD008494B6823F447
-:102248008002636913434B60002004E0032002E02E
-:10225800032000E0002002B070BD00BF0010024063
-:102268000070004040044242704700BF10B5044669
-:10227800074B1B680748A0FB03308009FFF732FEB5
-:102288004FF0FF3021460022FFF7EEFD002010BD81
-:1022980000000020D34D621008B5074A136843F0C8
-:1022A800100313600320FFF7CDFD0020FFF7DEFFCA
-:1022B800FFF7DAFF002008BD00200240024A136839
-:1022C80001331360704700BFE8000020014B186815
-:1022D800704700BFE800002030B583B00190FFF7D9
-:1022E800F5FF0546019CB4F1FF3F00D00134FFF72C
-:1022F800EDFF401BA042FAD303B030BD704700BFCA
-:1023080070B483B00023019390F82430012B00F0BF
-:102318008380012380F824304B68062B0DD806688B
-:10232800756B03EB8303053B1F229A4025EA0204E1
-:102338000A689A40224372631CE00C2B0DD8066889
-:10234800356B03EB8303233B1F229A4025EA0204E3
-:102358000A689A40224332630CE00668F56A03EB88
-:102368008303413B1F229A4025EA02040A689A40E7
-:102378002243F2620B68092B0DD90668F56803EB56
-:1023880043031E3B07229A4025EA02048A689A40C2
-:102398002243F2600BE00668356903EB430307222A
-:1023A8009A4025EA02048A689A40224332610B68FF
-:1023B800103B012B26D80368194A93421CD19A680E
-:1023C80012F4000F20D19A6842F400029A600B6858
-:1023D800102B1BD1134B1B68134AA2FB03239B0C26
-:1023E80003EB83035B00019302E0019B013B019334
-:1023F800019B002BF9D10AE0836A43F02003836232
-:10240800012304E0002302E0002300E0002300226F
-:1024180080F82420184600E0022003B070BC704702
-:10242800002401400000002083DE1B4330B583B048
-:102438000023019303689A6812F0010F2FD19A685C
-:1024480042F001029A60174B1B68174AA2FB03234C
-:102458009B0C019302E0019B013B0193019B002B24
-:10246800F9D10446FFF732FF054611E0FFF72EFFCA
-:10247800401B02280CD9A36A43F01003A362E36A45
-:1024880043F00103E362002384F82430012007E0CD
-:1024980023689B6813F0010FE8D0002000E00020BB
-:1024A80003B030BD0000002083DE1B4390F82430C9
-:1024B800012B70D010B50446012380F82430FFF7B3
-:1024C800B5FF0346002861D1A26A22F4407222F0C7
-:1024D800010242F48072A262226830498A4205D120
-:1024E800A1F58061496811F4702F0ED1A16A21F419
-:1024F8008011A162516811F4806F1CD0A16A21F487
-:10250800405141F48051A16215E0A16A41F4801163
-:10251800A16223498A4203D001F580618A420AD127
-:102528001F49496811F4806F05D0A16A21F4405110
-:1025380041F48051A162A16A11F4805F04D0E16A7C
-:1025480021F00601E16201E00021E162002184F846
-:1025580024106FF0020111602268916801F4602173
-:10256800B1F5602F0DD10D498A4205D1A1F58061E1
-:10257800496811F4702F04D1916841F4A001916069
-:1025880007E0916841F48011916002E0002284F82C
-:102598002420184610BD0220704700BF00280140C3
-:1025A8000024014038B503689A6812F0010F1ED064
-:1025B80004469A6822F001029A60FFF787FE0546F2
-:1025C8000EE0FFF783FE401B022809D9A36A43F0F7
-:1025D8001003A362E36A43F00103E362012038BDFC
-:1025E80023689B6813F0010FEBD1002038BD002051
-:1025F80038BD00BF002800F0888070B50446836AA3
-:1026080023B9C36280F82430FFF778FE2046FFF72D
-:10261800C9FFA36A13F0100F71D100286FD1A36A04
-:1026280023F4885323F0020343F00203A362626891
-:102638002168374B994206D1E369B3F5402F03D19E
-:102648004FF4002300E0E3691343E56843EA4503D8
-:10265800A268B2F5807F04D0012A05D14FF48072B8
-:1026680003E04FF4807200E000226669012E0FD16A
-:1026780035B9A569013D42EA453242F4006207E0F6
-:10268800A56A45F02005A562E56A45F00105E56201
-:102698004D6825F469452A434A6021688D681D4ABA
-:1026A8002A401A438A60A268B2F5807F01D0012AC5
-:1026B80003D12269013A110500E000212568EA6A80
-:1026C80022F470020A43EA6222689168124A0A40B8
-:1026D800934208D10023E362A36A23F0030343F083
-:1026E8000103A36270BDA36A23F0120343F0100331
-:1026F800A362E36A43F00103E362012070BDA36AA9
-:1027080043F01003A362012070BD0120704700BF91
-:10271800003C0140FDF7E1FFFE0E1FFF2DE9F843E5
-:10272800814601680B6923F44052C36813430B6167
-:10273800816803691943436919430068C26822F430
-:10274800B05323F00C030B43C360D9F800104B6956
-:1027580023F44072D9F8183013434B61D9F800506C
-:102768005B4B9D4259D1FFF74FF800EB800000EB1F
-:102778008000D9F80440A400B0FBF4F4554EA6FB41
-:10278800043464092401FFF73FF800EB800000EBF4
-:102798008000D9F804309B00B0FBF3F7FFF734F85A
-:1027A80000EB800000EB8000D9F804309B00B0FB00
-:1027B800F3F3A6FB03235B094FF0640808FB1373CC
-:1027C8001B013233A6FB03235B0903F0F0031C440F
-:1027D800FFF71AF800EB800000EB8000D9F804300E
-:1027E8009B00B0FBF3F7FFF70FF800EB800000EB5E
-:1027F8008000D9F804309B00B0FBF3F3A6FB032359
-:102808005B0908FB13731B013233A6FB0323C3F3D5
-:1028180043131C44AC60BDE8F883FEF7E5FF00EB0A
-:10282800800000EB8000D9F80440A400B0FBF4F469
-:10283800284EA6FB043464092401FEF7D5FF00EBFB
-:10284800800000EB8000D9F804309B00B0FBF3F760
-:10285800FEF7CAFF00EB800000EB8000D9F80430D7
-:102868009B00B0FBF3F3A6FB03235B094FF064085E
-:1028780008FB13731B013233A6FB03235B0903F028
-:10288800F0031C44FEF7B0FF00EB800000EB800073
-:10289800D9F804309B00B0FBF3F7FEF7A5FF00EB77
-:1028A800800000EB8000D9F804309B00B0FBF3F304
-:1028B800A6FB03235B0908FB13731B013233A6FB3A
-:1028C8000323C3F343131C44AC60BDE8F88300BF83
-:1028D800003801401F85EB51704700BF68B310B541
-:1028E800044690F8393013F0FF0F04D1002380F824
-:1028F8003830FFF7F1FF242384F839302268D36891
-:1029080023F40053D3602046FFF708FF22681369B9
-:1029180023F4904313612268536923F02A03536117
-:102928002268D36843F40053D3600020E063202377
-:1029380084F8393084F83A3010BD0120704700BF60
-:102948000F4B1A6842F001021A6059680D4A0A4092
-:102958005A601A6822F0847222F480321A601A6867
-:1029680022F480221A605A6822F4FE025A604FF458
-:102978001F029A604FF00062034B9A60704700BFD5
-:10298800001002400000FFF800ED00E030B597B0FD
-:102998001F4BDA6942F48022DA61DA6902F4802294
-:1029A8000092009A5A6942F001025A615B6903F089
-:1029B80001030193019B174D06954FF4E1330793EB
-:1029C8000024089409940A9408230B930C940D94FA
-:1029D80006A8FFF783FF6B6943F080036B614FF430
-:1029E8008063029301230493022303930323059333
-:1029F800094802A9FFF7A2FA084B1C60084A9A6026
-:102A08005C6090221A6070221C3B5A6017B030BD7F
-:102A18000010024000480040000C01401C00024029
-:102A2800044800402DE9F04F89B07B4B9A6942F089
-:102A380004029A619A6902F004020192019A9A6961
-:102A480042F008029A619A6902F008020292029A18
-:102A58009A6942F010029A619B6903F0100303938C
-:102A6800039B002305930693022707974FF0200A3C
-:102A78000DEB0A0444F810AD68482146FFF75EFAEA
-:102A88004023049365482146FFF758FA80250495AA
-:102A980062482146FFF752FA4FF480630493604876
-:102AA8002146FFF74BFA4FF4006304935C48214634
-:102AB800FFF744FA4FF48056049659482146FFF729
-:102AC8003DFA049657482146FFF738FA04975548C7
-:102AD8002146FFF733FA4FF00108CDF814804FF084
-:102AE8000409CDF810904D482146FFF727FA102623
-:102AF80004964C482146FFF721FACDF810A0494822
-:102B08002146FFF71BFA03230593CDF810804448AC
-:102B18002146FFF713FACDF8108042482146FFF707
-:102B28000DFA4FF0080BCDF810B03D482146FFF7DD
-:102B380005FA04973A482146FFF700FA0496384800
-:102B48002146FFF7FBF9CDF810A035482146FFF7DD
-:102B5800F5F9CDF8109032482146FFF7EFF9CDF896
-:102B680010B030482146FFF7E9F9CDF810902D480C
-:102B78002146FFF7E3F905974023049328482146A7
-:102B8800FFF7DCF9049526482146FFF7D7F94FF4FB
-:102B98008079CDF8109022482146FFF7CFF90495A7
-:102BA80020482146FFF7CAF9CDF810801B48214676
-:102BB800FFF7C4F9049719482146FFF7BFF9CDF884
-:102BC800109018482146FFF7B9F94FF400730493A1
-:102BD80014482146FFF7B2F94FF480630493114873
-:102BE8002146FFF7ABF94FF4005304930B482146F5
-:102BF800FFF7A4F94FF48043049308482146FFF7F0
-:102C08009DF94FF40043049304482146FFF796F9D1
-:102C180009B0BDE8F08F00BF00100240000C014071
-:102C280000100140000801402DE9F04F99B0754BA4
-:102C38009A6942F400629A619A6902F40062019208
-:102C4800019A9A6942F400529A619B6903F400530D
-:102C58000293029B6C4EDFF8B891C6F800900024EE
-:102C680074604FF02008C6F808804FF4FA6BC6F875
-:102C78000CB034617461B4613046FEF747FF10232D
-:102C880016931794304616A9FFF77CF860230F9324
-:102C98001094119408271297139414944FF4007306
-:102CA800159330460FA92246FEF784FF30460FA938
-:102CB8000422FEF77FFF30460FA93A46FEF77AFF57
-:102CC8004FF4006308934FF4806309930A94CDF896
-:102CD8002C800C940D940E9430460DEB0801FFF7F0
-:102CE80027F84A4DDFF82CA1C5F800A06C60C5F89C
-:102CF8000880C5F80CB02C616C61AC612846FEF701
-:102D080005FFCDF8588080231793284616A9FFF7AA
-:102D180039F8049418A9052341F8543D2846FEF7CC
-:102D280089FE60230F9310941194129713941494AE
-:102D38004FF40073159328460FA92246FEF73AFF71
-:102D480028460FA90422FEF735FF28460FA93A4660
-:102D5800FEF730FF4FF4006308934FF48063099344
-:102D68000A94CDF82C800C940D940E9428460DEB03
-:102D78000801FEF7DDFFDAF8443023F40043CAF80F
-:102D88004430D9F8443023F40043C9F84430284685
-:102D98002146FEF78BFF28460421FEF787FF2846C9
-:102DA8003946FEF783FF28462146FEF7AFFF28463F
-:102DB8000421FEF7ABFF28463946FEF7A7FF304649
-:102DC8002146FEF773FF30460421FEF76FFF3046B9
-:102DD8003946FEF76BFF30462146FEF797FF30462F
-:102DE8000421FEF793FF30463946FEF78FFF2B6824
-:102DF80001221A633268136843F00103136019B0A3
-:102E0800BDE8F08F001002401C010020A001002046
-:102E1800002C0140003401402DE9F04387B0414EB9
-:102E2800B36943F40073B361B36903F400730093A7
-:102E3800009B3D4C3D4B23604FF48073A3600025FD
-:102E4800E56065614FF44023E36165604FF0050874
-:102E5800C4F810802046FFF7CDFB354A536843F489
-:102E68008023536006A94FF4C02341F8043D20464F
-:102E7800FEF7B2FF012304930E2202920393204629
-:102E880002A9FFF73DFA029502270397204602A9F7
-:102E9800FFF736FA04970B2702970323039320467C
-:102EA80002A9FFF72DFA4FF00C09CDF8089004237A
-:102EB8000393204602A9FFF723FACDF80890CDF82E
-:102EC8000C80204602A9FFF71BFA23689A6842F48F
-:102ED80080729A609A6842F001029A60736943F0BE
-:102EE80001037361736903F001030193019B114BA3
-:102EF8001D60C3F80480104A9A60104ADA6040F6F0
-:102F0800A2221A601A6842F001021A60384629465D
-:102F18002A46FEF7A9FF3846FEF7D8FF07B0BDE8F6
-:102F2800F08300BF001002405C0100200024014033
-:102F380000000140080002404C2401408C010020A0
-:102F4800F0B585B0274B9A6942F480629A619B6913
-:102F580003F480630093009B234C244B23604FF4BD
-:102F68008073A3600023E36063614FF46022E26131
-:102F78006360052626612046FFF73CFB0123039387
-:102F88000F2201920293204601A9FFF7B9F90D23F8
-:102F9800019302250295204601A9FFF7B1F903958F
-:102FA8000A23019303270297204601A9FFF7A8F9EE
-:102FB80001950423029320460DEB0301FFF7A0F9C6
-:102FC80001970296204601A9FFF79AF923689A68A3
-:102FD80042F480729A609A6842F001029A6005B0E1
-:102FE800F0BD00BF00100240EC00002000280140A6
-:102FF8004FF08042536A9BB20021516240F6B832CA
-:10300800934202D90F4B197070470E4A1278052A5D
-:1030180016D800200C490860B3F5FA6F08D8B3F544
-:103028007A7F03D3A3F57A739BB203E0002301E010
-:103038004FF47A73054921F812300132014B1A70A6
-:10304800704700BFB200002004000020A400002048
-:1030580030B597B002250C950123109310231193D6
-:103068001395002414944FF4601315930CA8FEF7DD
-:10307800BBF80F230793089509944FF480630A93CC
-:103088000B9407A82946FEF7E7FA01954FF4404349
-:10309800039301A8FFF75EF8FEF7A0FB084BA3FB1C
-:1030A80000308009FEF71EFF0420FEF731FF4FF0C5
-:1030B800FF3021462246FEF7D7FE17B030BD00BFCD
-:1030C800D34D621010B582B0FFF7E6F8724CA369D1
-:1030D80043F00103A361A36903F001030193019B7A
-:1030E8000320FEF7AFFE6FF00B0000210A46FEF743
-:1030F800BBFE6FF00A0000210A46FEF7B5FE6FF02E
-:10310800090000210A46FEF7AFFE6FF00400002117
-:103118000A46FEF7A9FE6FF0030000210A46FEF7F3
-:10312800A3FE6FF0010000210A46FEF79DFE4FF056
-:10313800FF3000210A46FEF797FEFFF789FF636913
-:1031480023F001036361FFF76DFCFFF76DFDFFF7E7
-:1031580063FEFFF7F5FEFFF719FC50482021012216
-:10316800FEF7EEFF4E48FFF7A1F94E48FFF79EF92C
-:10317800082405E04C4B1C706420FFF7ADF8013CB7
-:10318800002CF7DA0022484B1A7048480421012223
-:10319800FEF7D6FF0122464B1A700A20FFF79CF86B
-:1031A800444B1B68312B04D80023434A1360434A1D
-:1031B80013600020014600F0F7FB0120002100F019
-:1031C800F3FB00F0F7FB00223A4B1A603348022168
-:1031D800FEF7AEFFE0B10022354B1A702F480221EE
-:1031E800FEF7A6FF0028F9D100242F4B1C70344BA2
-:1031F8001C7005E02C4B1C706420FFF76DF801343F
-:10320800072CF7DD254820210022FEF799FFFEE76D
-:103218002C4B1C6820462C49FDF782FF58B12046EC
-:103228002A49FDF79BFF30B105221F4B1A7008226F
-:10323800234B1A70B1E720462449FDF771FF58B1B6
-:1032480020462349FDF78AFF30B10522164B1A7034
-:1032580001221B4B1A70A0E720461D49FDF760FFAD
-:1032680098B10024164B1C70114B1C7005E00E4BD6
-:103278001C706420FFF730F80134072CF7DD07488D
-:1032880020210022FEF75CFFFEE70023064A1370A8
-:103298000B4A137081E700BF00100240000801408C
-:1032A8005C010020EC000020D8000020000C014048
-:1032B800D900002004000020BC000020B400002039
-:1032C800D0000020E8010020000010420000044265
-:1032D8000000F041000000002DE9F8430222AC4B49
-:1032E8005A60AC4B1B68B3F57A7F3BDA0133A94AC5
-:1032F8001360A94A938899B2A84803680B4403EB62
-:10330800D3735B100360D38899B2A54803680B4454
-:1033180003EBD3735B100360138899B2A148036869
-:103328000B4403EBD3735B100360538899B29E4838
-:1033380003680B4403EBD3735B100360538999B2A2
-:103348009A4803680B4403EBD3735B10036013893B
-:103358009AB297490B68134403EBD3735B100B6065
-:10336800BDE8F883934D2868FDF7F0F880A3D3E90A
-:103378000023FDF73FF906460F46874CA08980B227
-:10338800FDF7D8FCFDF7E2F87BA3D3E90023FDF7AE
-:1033980031F97BA3D3E90023FDF72CF902460B464C
-:1033A80030463946FCF774FFFDF7BEFB2860824EB5
-:1033B8003068FDF7CBF86EA3D3E90023FDF71AF9BF
-:1033C80080468946608A80B2FDF7B4FCFDF7BEF8F6
-:1033D8006BA3D3E90023FDF70DF902460B464046DF
-:1033E8004946FCF755FFFDF79FFB05463060DFF8BF
-:1033F8000082D8F80000FDF7A9F85DA3D3E90023FF
-:10340800FDF7F8F806460F46E08980B2FDF792FC12
-:10341800FDF79CF85AA3D3E90023FDF7EBF8024621
-:103428000B4630463946FCF733FFFDF77DFB044673
-:10343800C8F800000022614B1A8028466049FDF751
-:10344800C7FB05460021FDF789FE38B10020294653
-:10345800FDF7BEFBFDF78CFE584B188020465849F7
-:10346800FDF7B6FB05460021FDF778FE58B1534C31
-:10347800B4F90000FDF762FC01462846FDF7AAFBF7
-:10348800FDF776FE20804D4B188803B213F1640FC8
-:103498000ADA4C4B1B78012B06D105224A4B1A70CD
-:1034A80001224A4B1A7009E0464B1B78012B05D1C3
-:1034B8000022454B1A700122444B1A7000B20028B2
-:1034C80000DA03308010FDF739FC414900F036FF7F
-:1034D8004049FDF73BFDFDF74BFE80B2374B1880A6
-:1034E80000B242423C4B1A603C4B18602A4B588948
-:1034F80080B22E4B1C68001BFDF716F822A3D3E9F7
-:103508000023FDF777F800220023FDF7E5FA80B1E4
-:10351800214B588980B2001BFDF706F81AA3D3E99E
-:103528000023FDF767F800222D4BFDF7D5FAC0B947
-:103538000FE0194B588980B2001BFCF7F5FF12A366
-:10354800D3E90023FDF756F80022264BFDF7E2FAEF
-:1035580038B9254B1B68322B03D81A4B1B78002B24
-:1035680048D1224A536C23F40043536447E000BF18
-:103578002B8716D9CEF7EF3FF5E4E827181C9B3FB9
-:10358800FCA9F1D24D62503F7B14AE47E17A943FDB
-:1035980000000240B80000208C0100200800002034
-:1035A8000C000020180000201C0000201000002043
-:1035B80014000020E8010020E0010020C0000020E5
-:1035C80000002F44D9000020D8000020D00000209F
-:1035D8000000404040E37948B4000020BC000020CF
-:1035E800000038C0000038400400002000340140CA
-:1035F800E4010020924A536C43F400435364914B16
-:10360800188980B2904B1C68001BFCF78DFF8AA3B9
-:10361800D3E90023FCF7EEFF00220023FDF75CFA54
-:1036280080B1884B188980B2001BFCF77DFF82A30C
-:10363800D3E90023FCF7DEFF0022844BFDF74CFAA8
-:10364800B8B90FE07F4B188980B2001BFCF76CFFFC
-:1036580079A3D3E90023FCF7CDFF00227C4BFDF7CB
-:1036680059FA30B97B4B1B68322B02D87A4B1B783E
-:103678002BB97A4A536C23F40043536404E0774A25
-:10368800536C43F400435364754A936813F0200F56
-:103698000CBF01210021936813F0400F0CBF0123D8
-:1036A8000023926812F0800F0CBF012400246D4A99
-:1036B800906810F4806F0CBF01200020956815F405
-:1036C800006F0CBF01260026926812F4805F03EB9E
-:1036D800440301EB4303644DEB5C64490B600B68E6
-:1036E80003F102030B600C68614B83FB0472A2EBCD
-:1036F800E47202EB42024FEA4202A4EB02020A60C1
-:103708000CBF02220022324400EB4202A85C594A54
-:103718001060106802301060106883FB0043A3EB50
-:10372800E07303EB43035B00C31A13600B68454C5B
-:10373800A28892B250490968501AE28892B24F4C56
-:103748002468121B052B18D8DFE803F003070A0DBD
-:103758001013821A4A4B1A6012E0494B18600FE0A6
-:10376800474B18600CE0464B1A6009E0444B1A605E
-:1037780006E0121A424B1A6002E00022404B1A601F
-:10378800304B9A8893B2591A00D507310220C910D4
-:1037980000F00AF92B4BDB889BB2384A1168591A9A
-:1037A80000D507310320014100F0FEF8354A13889F
-:1037B80001339BB21380344A1478ACB1334AA2FB6C
-:1037C8000312120B32490978013192FBF1F001FB27
-:1037D80010224AB993FBF4F204FB12334BB92D487B
-:1037E8001021FEF7B3FC04E02A4810210022FEF75E
-:1037F800A7FC294B1A681D4B1B68052B4ED8DFE820
-:1038080003F003070B0E111514465242002548E039
-:1038180055421446002244E05542002441E05442F7
-:1038280000253EE05442154600223AE01546524231
-:10383800002436E0AFF300807B14AE47E17A943F72
-:10384800003401408C01002014000020000038C022
-:103858000000384004000020D9000020002C01405E
-:10386800000C0140001001408C500008C4000020EA
-:10387800ABAAAA2ACC000020080000200C000020D7
-:10388800D4000020C8000020D80000205917B7D164
-:10389800D000002000080140B40000200022144697
-:1038A80015463D4B1B683D49096805291AD8DFE8CC
-:1038B80001F003070B0E111519465B42002014E0B6
-:1038C80058421946002310E0584200210DE05942A1
-:1038D80000200AE059421846002306E018465B42D9
-:1038E800002102E000231946184605F57A7540F2D2
-:1038F800C676B54203DC0A2DB8BF0A2501E040F2BE
-:10390800C675274E756304F57A7440F2C675AC42E5
-:1039180003DC0A2CB8BF0A2401E040F2C674204D2B
-:10392800AC6302F57A7240F2C674A24203DC0A2A3A
-:10393800B8BF0A2201E040F2C672194CE26300F5F2
-:103948007A7240F2C670824203DC0A2AB8BF0A22A1
-:1039580001E040F2C6721348426301F57A7240F200
-:10396800C6718A4203DC0A2AB8BF0A2201E040F283
-:10397800C6720C498A6303F57A7340F2C6729342A1
-:1039880003DC0A2BB8BF0A2301E040F2C673054ADC
-:10399800D363BDE8F88300BFBC000020CC00002042
-:1039A80000340140002C0140014B23F810107047EF
-:1039B8005002002030B583B0144C20460021642208
-:1039C80000F098F812490A884B888888C98800B29C
-:1039D800009009B2019120460E4912B21BB200F0C4
-:1039E80091F80D4B5B6873B90B4C236823F0010306
-:1039F8002360064D284600F0A9F86060E56023685A
-:103A080043F00103236003B030BD00BFEC01002088
-:103A180050020020945000081C000240704700BF6C
-:103A2800FEE700BFFEE700BFFEE700BFFEE700BFFE
-:103A3800704700BF704700BF704700BF08B5FEF76A
-:103A48003DFCFEF777FA08BD08B5FFF7D1FA082262
-:103A5800014B5A6108BD00BF00040140002103E08A
-:103A68000B4B5B58435004310A480B4B42189A429F
-:103A7800F6D30A4A02E0002342F8043B084B9A4274
-:103A8800F9D3FEF75DFF00F00FF8FFF71BFB704757
-:103A98001051000800000020880000208800002045
-:103AA800A4020020FEE700000E4B70B51E460E4C27
-:103AB8000025E41AA410A54204D056F825309847EA
-:103AC8000135F8E701F0BAFA084B094C1E46E41A2A
-:103AD800A4100025A54204D056F825309847013592
-:103AE800F8E770BD0851000808510008085100089F
-:103AF8000C51000803460244934202D003F8011B0C
-:103B0800FAE770470EB400B54FF402719CB0ADF8F7
-:103B180014106FF00041049107914FF6FF711DAB2F
-:103B2800ADF81610084953F8042B0290069008685F
-:103B380002A9019300F06CF8029B00221A701CB0D5
-:103B48005DF804EB03B0704780000020034613F8CB
-:103B5800012B002AFBD1181A013870472DE9F047CC
-:103B68008E688246B3420C469046994640D38A896D
-:103B780012F4906F3AD02568096902236F1A6569B3
-:103B880005EB450595FBF3F57B1C4B449D4238BF7F
-:103B98001D4653050FD5294600F03AFB064698B155
-:103BA80021693A4600F0CAFAA38923F4906343F0E6
-:103BB8008003A38113E02A4600F080FB064670B913
-:103BC8005046216900F0E0FA0C23CAF80030A389B6
-:103BD8004FF0FF3043F04003A381BDE8F087266132
-:103BE8003E4426604E466561ED1BA560B14500D296
-:103BF8004E4632462068414600F0ABFAA3680020E2
-:103C08009B1BA36023681E442660BDE8F087000064
-:103C18002DE9F0439DB003938B8906461C060D469B
-:103C280090460CD50B6953B9402100F0F1FA286091
-:103C3800286110B90C233360CCE040236B6100236A
-:103C4800099320238DF8293030238DF82A304346F4
-:103C58001C4613F8012B1AB9B4EB08090FD002E07F
-:103C6800252AF5D1F8E73046294642464B46FFF764
-:103C780075FF013000F0A980099B4B440993237814
-:103C8800002B00F0A28000234FF0FF32049307932B
-:103C9800059206938DF853301A9304F101084446AF
-:103CA800DFF8489121784846052200F039FA08F1F2
-:103CB8000108049B30B1C9EB000001228240134384
-:103CC8000493ECE7D80644BF20228DF85320190747
-:103CD80044BF2B228DF8532022782A2A02D0079934
-:103CE80023460EE0039A0134111D12680391002A3D
-:103CF800BBBF524243F0020307920792B8BF049336
-:103D08000AE01C4622780133303A092A03D80A20EF
-:103D180000FB0121F5E7079123782E2B1AD1637850
-:103D28002A2B0AD1039B02341A1D1B680392002B0D
-:103D3800B8BF4FF0FF3305930CE0611C00220C461E
-:103D480023780131303B092B03D80A2000FB0232CB
-:103D5800F5E70592DFF8988021784046032200F0C5
-:103D6800DFF938B1049AC8EB0000402383401343BD
-:103D78000493013421781A48062204F101088DF8C9
-:103D8800281000F0CDF988B1164B33B9039B0733DF
-:103D980023F007030833039313E003AB0093304683
-:103DA80004A92A46104BAFF3008007E003AB009349
-:103DB800304604A92A460C4B00F092F8421C0746EC
-:103DC80003D0099B3B44099341E7AB895B0601D4C7
-:103DD800099801E04FF0FF301DB0BDE8F08300BF47
-:103DE800AE50000800000000653B0008A450000821
-:103DF800AA5000082DE9F84391461F468A680B69C6
-:103E080006469342B8BF1346C9F8003091F84320DC
-:103E18000C46DDF8208012B10133C9F80030236860
-:103E2800990642BFD9F800300233C9F80030256836
-:103E380015F006051CD094F843302268003318BFEB
-:103E4800012392061FD5E118302081F843005A1C3F
-:103E580094F845102244023382F8431013E03046A8
-:103E6800394604F119020123C047013007D0013552
-:103E7800E368D9F800209B1A9D42F0DBDBE74FF09E
-:103E8800FF30BDE8F8833046394604F14302C047A5
-:103E98000130F4D02268D9F80050E36802F0060235
-:103EA800042A08BF5D1B2269A3680CBF25EAE575D3
-:103EB80000259342C4BF9B1AED184FF00009A9458D
-:103EC8000ADA3046394604F11A020123C0470130A4
-:103ED800D5D009F10109F2E70020BDE8F883000018
-:103EE8002DE9FF410C461746227E98466E2A064663
-:103EF8000A9B01F1430100F0B08012D8632A23D055
-:103F08000AD8002A00F0BD80582A40F0CC8084F8F6
-:103F18004520DFF804E257E0642A1ED0692A1CD045
-:103F2800C1E0732A00F0B18009D86F2A2ED0702A18
-:103F380040F0B980226842F0200222603FE0752AF2
-:103F480024D0782A3BD0AEE01A6804F14205111D4E
-:103F58001960136884F84230A9E020681A6810F0E4
-:103F6800800F02D0101D186008E010F0400F02F119
-:103F78000400186002D0B2F9003000E01368002B8A
-:103F88003EDA2D225B4284F8432039E020681A6823
-:103F980010F0800F02D0101D186007E010F0400FDD
-:103FA80002F10400186001D0138800E01368227E33
-:103FB800DFF864E16F2A0CBF08220A221CE078228D
-:103FC800DFF858E184F845202268186812F0800F5D
-:103FD80000F104051D6003D1550601D5038800E0F2
-:103FE8000368D00744BF42F0200222601BB9226850
-:103FF80022F0200222601022002084F8430002E010
-:10400800DFF814E10A226568002DA8BF2068A560C2
-:10401800A4BF20F00400206003B965B10D46B3FBCE
-:10402800F2F002FB10331EF8033005F8013D034699
-:104038000028F4D100E00D46082A0BD12368DA07DE
-:1040480008D5236962689A42DEBF302305F8013C2F
-:1040580005F1FF35491B21612EE025681A6815F026
-:10406800800F606903D0151D1D60136808E015F006
-:10407800400F02F104051D60136801D0188000E0AC
-:104088001860002323610D4616E01A68111D196097
-:10409800156800212846626800F042F808B1401B04
-:1040A8006060636804E004F1420584F8422001235B
-:1040B8002361002384F84330CDF800803046214640
-:1040C80003AA3B46FFF796FE013002D14FF0FF30BE
-:1040D8001FE0304639462A462369C0470130F5D0EB
-:1040E80023689B0705D4E068039B9842B8BF18462D
-:1040F8000FE00025E368039A9B1A9D42F3DA3046E5
-:10410800394604F119020123C0470130DED00135D8
-:10411800F0E704B0BDE8F081B5500008C6500008CB
-:1041280010B5C9B202449042034605D01C7801304C
-:104138008C42F8D1184610BD002010BD10B5431EA2
-:104148000A44914204D011F8014B03F8014FF8E7F3
-:1041580010BD814210B501EB020301D3421E0BE0F2
-:104168009842FBD28118D21AD34204D013F8014DD9
-:1041780001F8014DF8E710BD994204D011F8014B40
-:1041880002F8014FF8E710BD30B500293CD051F8CE
-:10419800042C0B1F1D49002AB8BF9B180A680C463F
-:1041A80012B95A600B6030BD93420DD21968581885
-:1041B800904201BF5A5852181A60426823605A60E8
-:1041C80030BD994203D80A4651680029F9D11468CC
-:1041D80015199D420AD11B682344D01888421360E0
-:1041E80012D10868034413604B680CE002D90C2311
-:1041F800036030BD1C681819884201BF0868496807
-:10420800001918605960536030BD00BFE0000020FD
-:1042180070B5CC1C24F0030408340C2C38BF0C24D3
-:10422800002C064603DA0C233360002070BD8C4254
-:10423800F9D3204A136810461946A1B10A68121B1F
-:104248000ED40B2A03D90A608B188C501FE08B42BE
-:104258000BBF5A684A6802605A6018BF0B4616E0DE
-:104268000B464968E9E7144D2B681BB9304600F046
-:104278004BF828603046214600F046F8421C0346B9
-:10428800D1D0C51C25F0030585420AD11C6003F175
-:104298000B001A1D20F00700821A0AD051429950CB
-:1042A80070BD3046E91A00F02FF80130BBD02B461C
-:1042B800ECE770BDE0000020DC000020F8B5074600
-:1042C80015460E4621B91146BDE8F840FFF7A0BFD4
-:1042D8001AB9FFF759FF2846F8BD00F025F8A8429B
-:1042E8000ED238462946FFF793FF044650B13146AF
-:1042F8002A46FFF723FF38463146FFF745FF01E01E
-:104308003046F8BD2046F8BD38B5064C00230546B2
-:104318000846236000F07EFE431C02D1236803B1E7
-:104328002B6038BDA002002051F8040C0028BEBF45
-:10433800091851F8043CC018043870472DE9F041B9
-:104348008AB007460E4600F083F99B4D044695F95E
-:104358000030013303D0304600F0E0FD18B92046A4
-:104368000AB0BDE8F081384600F0D8FD8046002844
-:1043780032D130460021FCF7C9FE0028EFD08F4A21
-:104388000123384601920093CDF82080FCF7DEF82F
-:10439800CDE902013046FCF7D9F895F90030884F8D
-:1043A80000265A1CCDE90401CDE906670DD0022B81
-:1043B8000BD0684600F016FD002800F09A80089B94
-:1043C8001BB100F035FE089B0360DDE90601FCF730
-:1043D800ABFB0AB0BDE8F08138460021FCF796FE39
-:1043E80018B330460021FCF791FE8046002855D0CE
-:1043F8007249002301223846089300920191FCF784
-:10440800A5F8CDE902013046FCF7A0F895F900308F
-:1044180000260027CDE90401CDE90667002BC8D0A6
-:10442800674B0022CDE90623CFE7204600F06EFD5A
-:104438008046002862D020460021FCF767FE00284D
-:104448008DD0384600F062FD002888D0304600F054
-:104458005DFD002883D0594900230422384608937B
-:1044680000920191FCF772F8CDE902013046FCF7A1
-:104478006DF895F9003000260027022BCDE90401DC
-:10448800CDE9066700F09280684600F0ABFC002892
-:1044980000F08C80089B002B97D092E7304600F004
-:1044A80035FD00283FF45BAF30460021FCF738FEAD
-:1044B80000283FF454AF414A012338460093019243
-:1044C800CDF82080FCF742F8CDE902013046FCF730
-:1044D8003DF82B78CDE90401002B3FD03949002065
-:1044E800022BCDE9060133D100F0A2FD21230360A0
-:1044F800D0E700F09DFD2123036060E7384600F017
-:1045080005FD002897D0304600F000FD002892D025
-:10451800204600F003FD034628BB284901223846FF
-:10452800089300920191FCF711F8CDE90201304699
-:10453800FCF70CF82C78CDE904017CB100200021AF
-:1045480002460B46FCF780F9022CCDE90601CBD0D8
-:10455800684600F047FC00289CD1C5E700220023EC
-:10456800CDE90623F4E7154A032338460093019260
-:10457800CDF82080FBF7EAFFCDE902013046FBF7D2
-:10458800E5FF95F90030CDE90401FBB90E4B4FF07A
-:10459800604238460021CDE90623FCF7C1FD00281A
-:1045A80036D195F90030022B7FF46EAF00F040FD54
-:1045B800222303606EE700BF84000020D850000863
-:1045C8000000F03F0000F0FFFFFFEF471D4B002207
-:1045D80038460021CDE90623FCF7A2FD0028E0D0EB
-:1045E80030464FF07C51FCF7FDFBFBF7AFFF06466A
-:1045F8000F4600F0F9FB02460B4630463946FCF7F9
-:1046080061FA0028CDD1104B0022CDE90623C8E776
-:1046180030464FF07C51FCF7E5FBFBF797FF064669
-:104628000F4600F0E1FB02460B4630463946FCF7E0
-:1046380049FA0028B5D1054B4FF06042CDE9062371
-:10464800AFE700BF0000F07F0000F0FFFFFFEFC7FB
-:104658002DE9F04F31F0004987B00D460C4612D0D5
-:1046680020F0004ABAF1FF4F8046064605DD4F4864
-:1046780007B0BDE8F04F00F06BBCB9F1FF4F07DDA4
-:10468800BAF17E5FF3D14FF07E5007B0BDE8F08FEE
-:10469800002848DB0027B9F1FF4F3CD0B9F17E5F15
-:1046A80054D0B4F1804F40465DD0B4F17C5F19D04E
-:1046B80000F028FCBAF1FF4F28D0BAF1000F25D03E
-:1046C800BAF17E5F22D0F60F013E57EA060358D0B2
-:1046D800B9F19A4F72DD364B9A453DDC002C41DB2F
-:1046E8000020D2E7002E47DA00F00CFCBAF1FF4FA9
-:1046F80002D0BAF1000FE3D1AAF17E5A57EA0A03B1
-:1047080040D0012FC1D100F10040BEE7002C40DBB2
-:10471800002EBADAF0E7BAF17E5FB4D027DD002CBC
-:10472800DEDB2846B1E7B9F1974F13DAB9F17E5FBE
-:104738000ADB4FEAE953C3F1960349FA03F202FA96
-:1047480003F34B4500F03B820027A7E7002C26DB4C
-:1047580040469AE702279EE7164B9A4540F38F8218
-:10476800002CBDDD14480146FCF73CFB8DE7002C0E
-:10477800B6DA05F1004088E707B0BDE8F04F00F071
-:10478800DDBA40460146FCF723FA0146FCF7DEFB9A
-:104798007BE701464FF07E50FCF7D8FBB8E741466F
-:1047A8004FF07E50FCF7D2FB6FE700BFDC500008EB
-:1047B800F7FF7F3F0700803FCAF24971BAF5000F43
-:1047C80080F205824FF09741FCF70CFB82466FF0B0
-:1047D8001701B54A4FEAEA53CAF3160A7F3B9245D6
-:1047E80003EB010C4AF07E5840F3EE81AF4B9A453B
-:1047F80040F3408200220CF1010CA8F50008019258
-:104808000392AB4B019A404653F82230CDF814C0BE
-:1048180019469A46FCF7DCF9514681464046CDF8E0
-:1048280008A0FCF7D7F901464FF07E50FCF78EFB45
-:104838000346484619460493FCF7D4FA4FEA680140
-:10484800039A41F00051C34601F5802120F47F68A6
-:1048580028F00F080A448246114640460392FCF7A6
-:10486800C1FA01464846FCF7B3F9039A0299814612
-:104878001046FCF7ADF901465846FCF7A9F9014680
-:104888004046FCF7AFFA01464846FCF7A1F9049BFD
-:104898001946FCF7A7FA514683465046FCF7A2FA98
-:1048A80001468146FCF79EFA824902904846FCF789
-:1048B80099FA8149FCF78EF94946FCF793FA7F4942
-:1048C800FCF788F94946FCF78DFA7D49FCF782F92F
-:1048D8004946FCF787FA7B49FCF77CF94946FCF71F
-:1048E80081FA7949FCF776F9029B01461846FCF7EC
-:1048F80079FA814641465046FCF76CF95946FCF76F
-:1049080071FA4946FCF766F9414681464046FCF78C
-:1049180069FA6E490390FCF75DF94946CDF80890AD
-:10492800FCF758F920F47F6929F00F0949464046F9
-:10493800FCF758FA494680465846FCF753FA63494B
-:1049480083464846FCF744F9039A1146FCF740F9B8
-:1049580001460298FCF73CF95146FCF743FA014638
-:104968005846FCF737F9834640465946FCF732F972
-:1049780020F47F6A2AF00F0A50465549FCF732FAAC
-:10498800544981465046FCF72DFA4146029050465C
-:10499800FCF71EF901465846FCF71AF94E49FCF790
-:1049A80021FA029B01461846FCF714F94B4B019972
-:1049B80053F82110FCF70EF9DDF814C08046604664
-:1049C800FCF7BCF98246019A454B414653F822B0A0
-:1049D8004846FCF7FFF85946FCF7FCF85146CDF875
-:1049E80004A0FCF7F7F820F47F6A2AF00F0A01996F
-:1049F8005046FCF7EDF85946FCF7EAF84946FCF74B
-:104A0800E7F801464046FCF7E3F824F47F6424F015
-:104A18000F04013F57EA06038046214628460CBF8B
-:104A2800304E4FF07E56FCF7D3F85146FCF7DAF9D2
-:104A3800414607462846FCF7D5F901463846FCF7B3
-:104A4800C9F8214607465046FCF7CCF98046384657
-:104A58004146FCF7BFF8002881460446C24620F0CC
-:104A6800004540F3F180B5F1864F00F3C08000F0B7
-:104A7800B080B5F17C5F00F3C2800025A84624F41D
-:104A88007F6424F00F0420461749FCF7ABF9514620
-:104A980081462046FCF79CF801463846FCF798F812
-:104AA8001249FCF79FF923E071C41C00D6B35D00DE
-:104AB800F050000842F1533E55326C3E05A38B3E40
-:104AC800ABAAAA3EB76DDB3E9A99193F0000404059
-:104AD8000038763FA0C39D364F38763FE85000082F
-:104AE800E0500008000080BF0072313F1872313F6B
-:104AF800834907462046FCF775F901463846FCF716
-:104B080069F8074648463946FCF764F849460446BA
-:104B1800FCF75EF801463846FCF75AF8214681460C
-:104B28002046FCF75FF907467649FCF75BF97649BA
-:104B3800FCF74EF83946FCF755F97449FCF74AF882
-:104B48003946FCF74FF97249FCF742F83946FCF749
-:104B580049F97049FCF73EF83946FCF743F9014634
-:104B68002046FCF735F8074620463946FCF73AF95F
-:104B78004FF0804182463846FCF72AF801465046F5
-:104B8800FCF7E4F9494607462046FCF72BF9494665
-:104B9800FCF720F801463846FCF71AF82146FCF7DE
-:104BA80017F801464FF07E50FCF712F84119B1F59D
-:104BB800000FC0F29F803046FCF714F965E502F05B
-:104BC8000102C2F1020769E50022019218E60021FC
-:104BD800FFE551493846FBF7FDFF41468246484606
-:104BE800FBF7F6FF01465046FCF7B8FA38B13046F5
-:104BF8004A49FCF7F7F84949FCF7F4F845E5ED159B
-:104C08007E3D4FF400022A412244C2F3C751444872
-:104C1800C2F31603C1F196057F3940FA01F143F456
-:104C280000032B4122EA0101404683EAE478FBF7BE
-:104C3800CFFF824638465146FBF7CCFF08EBD478C5
-:104C48004FEAC85504461AE7364B9D420ADC7FF402
-:104C580010AF4146FBF7BCFF01463846FCF76AFA3D
-:104C68000028CCD030463049FCF7BCF82E49FCF778
-:104C7800B9F80AE501234FF400120193C0E54FF09B
-:104C88007E51FBF7A5FF29498046FCF7ABF8284978
-:104C980081464046FCF7A6F8414682464046FCF766
-:104CA800A1F84FF07A5183464046FCF79BF801463D
-:104CB8002048FBF78DFF4146FCF794F801464FF07A
-:104CC8007C50FBF785FF01465846FCF78BF81A49DC
-:104CD800FCF788F801465046FBF77AFF80464846BD
-:104CE8004146FBF777FF20F47F6A2AF00F0A49460E
-:104CF800504684E6414600F02FF901465BE700BFC5
-:104D08008CBEBF354CBB31330EEADD3555B38A381E
-:104D1800610B363BABAA2A3E3CAA3833CAF249712A
-:104D2800FFFF7F00000016436042A20D00AAB83FB3
-:104D380070A5EC36ABAAAA3E3BAAB83F20F00042C9
-:104D4800B2F1FF4F70B5034604462DD25AB300287E
-:104D58003DDBB2F5000F4FEAE0502CD30026314678
-:104D68007F38C3F31603C20743F4000348BF5B0050
-:104D780040105B0019244FF080728D189D4202DCB0
-:104D88005B1BA9181644013C4FEA43034FEA520241
-:104D9800F3D113B106F001031E44761006F17C56D8
-:104DA80006EBC05070BD70BD0146FCF71BF82146EC
-:104DB800FBF710FF70BD14F400020FD15B0019025D
-:104DC80002F10102FAD5C2F101021044C6E7014618
-:104DD800FBF7FEFE0146FCF7B9F870BD012210444E
-:104DE800BCE700BF00207047F0B5C1F30A5EAEF221
-:104DF800FF35132D83B002460B460C464FEAD17699
-:104E080007462EDC002D48DB3C49294101EA030016
-:104E180010432BD049080B4053EA02070CD04FF43B
-:104E28008023132D24EA010143FA05F444EA01041E
-:104E38000CBF4FF0004700273149234601EBC60657
-:104E4800D6E900453A4620462946FBF721FACDE93E
-:104E58000001DDE9000122462B46FBF717FA03B0F3
-:104E6800F0BD332D06DDB5F5806F43D010461946E9
-:104E780003B0F0BDAEF2134E4FF0FF3121FA0EF140
-:104E88000142F3D049080142D6D04FF0804320EACE
-:104E9800010143FA0EF70F43CEE721F00041014329
-:104EA800E4D0C3F3130141EA000CCCF1000141EA5C
-:104EB8000C0C13495C0C4FEA1C3C0CF4002C6404E9
-:104EC80001EBC6014CEA0403D1E900452046294616
-:104ED800FBF7DEF9CDE90001DDE9000122462B46AA
-:104EE800FBF7D4F9024621F0004141EAC6731046A7
-:104EF8001946BDE7FBF7CCF9BAE700BFFFFF0F0083
-:104F0800F850000820F00040704700BF20F0004033
-:104F1800B0F1FF4FACBF00200120704730F00040D7
-:104F280001D102207047A0F50003B3F1FE4F01D272
-:104F380004207047054B421E9A4201D8032070474F
-:104F4800A0F1FF40B0FA80F040097047FEFF7F00F3
-:104F5800004870470000C07F30F0004238B5034673
-:104F6800044615D0B2F1FF4F0ED2B2F5000F0D4630
-:104F78000FD3D20D2A44FE2A2EDC002A1DDD24F090
-:104F8800FF4444EAC25038BD0146FBF723FE38BD52
-:104F980038BD4FF09841FBF725FF184A0346954264
-:104FA80007DBC0F3C7520446193AE3E7144800F098
-:104FB8002BF81349FBF716FF38BD12F1160F13DA59
-:104FC8004CF2503295421946F0DD0E4800F01CF8BC
-:104FD8000C49FBF707FF38BD19460A4800F014F8DA
-:104FE8000849FBF7FFFE38BD193224F0FF4040EABC
-:104FF800C2504FF04C51FBF7F5FE38BDB03CFFFFF7
-:105008006042A20DCAF2497101F0004120F000404F
-:1050180008437047044A05491368002B08BF0B462C
-:105028001844106018467047E4000020A8020020C9
-:10503800014B1868704700BF80000020F8B500BF1A
-:10504800F8BC08BC9E467047F8B500BFF8BC08BC61
-:045058009E467047B9
-:1050600002030405060708090A0B0C0D0E0F1010A9
-:105070000102000000000000000000000102030423
-:1050800006070809000000000102030400000201F5
-:105090000405030025693B25693B25693B25690A11
-:1050A0000D004300232D302B2000686C4C006566FA
-:1050B0006745464700303132333435363738394169
-:1050C000424344454600303132333435363738397F
-:1050D0006162636465660000706F776600000000BF
-:1050E0000000000000C0153F00000000DCCFD135FB
-:1050F0000000803F0000C03F00000000000030437F
-:0851000000000000000030C3B4
-:045108005502000844
-:04510C002D02000868
-:1051100000A24A0464000000D0070000D00700008D
-:10512000D0070000D0070000D0070000D007000023
-:10513000000000000000000000000000000000006F
-:10514000000000000000000000000000000000005F
-:10515000A250000800000000000000000000000055
-:10516000000000000000000000000000000000003F
-:10517000000000000000000000000000000000002F
-:10518000000000000000000000000000000000001F
-:085190002000002001000000D6
-:0400000508003A6550
-:00000001FF
diff --git a/hoverboard.xml b/hoverboard.xml
new file mode 100644
index 00000000..e45ed99e
--- /dev/null
+++ b/hoverboard.xml
@@ -0,0 +1,19 @@
+
+
+
+
+
+
+
+
+]>
+
+
+
+ hoverboard
+ SWD
+ ST-Link
+ stm32f103rctx
+
+
diff --git a/hoverboard_sw Debug.cfg b/hoverboard_sw Debug.cfg
new file mode 100644
index 00000000..107cc9c0
--- /dev/null
+++ b/hoverboard_sw Debug.cfg
@@ -0,0 +1,27 @@
+# This is an hoverboard board with a single STM32F103RCTx chip
+#
+# Generated by System Workbench for STM32
+# Take care that such file, as generated, may be overridden without any early notice. Please have a look to debug launch configuration setup(s)
+
+source [find interface/stlink.cfg]
+
+set WORKAREASIZE 0x8000
+
+transport select "hla_swd"
+
+set CHIPNAME STM32F103RCTx
+
+# Enable debug when in low power modes
+set ENABLE_LOW_POWER 1
+
+# Stop Watchdog counters when halt
+set STOP_WATCHDOG 1
+
+# STlink Debug clock frequency
+set CLOCK_FREQ 1800
+
+# use software system reset
+reset_config none
+set CONNECT_UNDER_RESET 0
+
+source [find target/stm32f1x.cfg]
diff --git a/hoverboard_sw Default.cfg b/hoverboard_sw Default.cfg
new file mode 100644
index 00000000..79faac00
--- /dev/null
+++ b/hoverboard_sw Default.cfg
@@ -0,0 +1,28 @@
+# This is an hoverboard board with a single STM32F103RCTx chip
+#
+# Generated by System Workbench for STM32
+# Take care that such file, as generated, may be overridden without any early notice. Please have a look to debug launch configuration setup(s)
+
+source [find interface/stlink.cfg]
+
+set WORKAREASIZE 0x8000
+
+transport select "hla_swd"
+
+set CHIPNAME STM32F103RCTx
+
+# Enable debug when in low power modes
+set ENABLE_LOW_POWER 1
+
+# Stop Watchdog counters when halt
+set STOP_WATCHDOG 1
+
+# STlink Debug clock frequency
+set CLOCK_FREQ 4000
+
+# use hardware reset, connect under reset
+# connect_assert_srst needed if low power mode application running (WFI...)
+reset_config srst_only srst_nogate connect_assert_srst
+set CONNECT_UNDER_RESET 1
+
+source [find target/stm32f1x.cfg]