Add files via upload

This commit is contained in:
midelic 2017-12-01 04:35:35 +02:00 committed by GitHub
parent f57d436640
commit b24564ffe9
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
37 changed files with 3834 additions and 0 deletions

View File

@ -0,0 +1,11 @@
@echo off
echo Installing Maple DFU driver...
"%~dp0wdi-simple" --vid 0x1EAF --pid 0x0003 --type 1 --name "Maple DFU" --dest "%~dp0maple-dfu"
echo.
echo Installing Maple Serial driver...
"%~dp0wdi-simple" --vid 0x1EAF --pid 0x0004 --type 3 --name "Maple Serial" --dest "%~dp0maple-serial"
echo.
pause

Binary file not shown.

View File

@ -0,0 +1,570 @@
#include "EEPROM.h"
// See http://www.st.com/web/en/resource/technical/document/application_note/CD00165693.pdf
/**
* @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 EEPROMClass::EE_CheckPage(uint32 pageBase, uint16 status)
{
uint32 pageEnd = pageBase + (uint32)PageSize;
// Page Status not EEPROM_ERASED and not a "state"
if ((*(__io uint16*)pageBase) != EEPROM_ERASED && (*(__io uint16*)pageBase) != status)
return EEPROM_BAD_FLASH;
for(pageBase += 4; pageBase < pageEnd; pageBase += 4)
if ((*(__io uint32*)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 EEPROMClass::EE_ErasePage(uint32 pageBase)
{
FLASH_Status FlashStatus;
uint16 data = (*(__io uint16*)(pageBase));
if ((data == EEPROM_ERASED) || (data == EEPROM_VALID_PAGE) || (data == EEPROM_RECEIVE_DATA))
data = (*(__io uint16*)(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 EEPROMClass::EE_CheckErasePage(uint32 pageBase, uint16 status)
{
uint16 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 EEPROMClass::EE_FindValidPage(void)
{
uint16 status0 = (*(__io uint16*)PageBase0); // Get Page0 actual status
uint16 status1 = (*(__io uint16*)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 EEPROMClass::EE_GetVariablesCount(uint32 pageBase, uint16 skipAddress)
{
uint16 varAddress, nextAddress;
uint32 idx;
uint32 pageEnd = pageBase + (uint32)PageSize;
uint16 count = 0;
for (pageBase += 6; pageBase < pageEnd; pageBase += 4)
{
varAddress = (*(__io uint16*)pageBase);
if (varAddress == 0xFFFF || varAddress == skipAddress)
continue;
count++;
for(idx = pageBase + 4; idx < pageEnd; idx += 4)
{
nextAddress = (*(__io uint16*)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 EEPROMClass::EE_PageTransfer(uint32 newPage, uint32 oldPage, uint16 SkipAddress)
{
uint32 oldEnd, newEnd;
uint32 oldIdx, newIdx, idx;
uint16 address, data, found;
FLASH_Status FlashStatus;
// Transfer process: transfer variables from old to the new active page
newEnd = newPage + ((uint32)PageSize);
// Find first free element in new page
for (newIdx = newPage + 4; newIdx < newEnd; newIdx += 4)
if ((*(__io uint32*)newIdx) == 0xFFFFFFFF) // Verify if element
break; // contents are 0xFFFFFFFF
if (newIdx >= newEnd)
return EEPROM_OUT_SIZE;
oldEnd = oldPage + 4;
oldIdx = oldPage + (uint32)(PageSize - 2);
for (; oldIdx > oldEnd; oldIdx -= 4)
{
address = *(__io uint16*)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*)(idx)) == address)
{
found = 1;
break;
}
if (found)
continue;
if (newIdx < newEnd)
{
data = (*(__io uint16*)(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 EEPROMClass::EE_VerifyPageFullWriteVariable(uint16 Address, uint16 Data)
{
FLASH_Status FlashStatus;
uint32 idx, pageBase, pageEnd, newPage;
uint16 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*)idx) == Address) // Find last value for address
{
count = (*(__io uint16*)(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*)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);
}
EEPROMClass::EEPROMClass(void)
{
PageBase0 = EEPROM_PAGE0_BASE;
PageBase1 = EEPROM_PAGE1_BASE;
PageSize = EEPROM_PAGE_SIZE;
Status = EEPROM_NOT_INIT;
}
uint16 EEPROMClass::init(uint32 pageBase0, uint32 pageBase1, uint32 pageSize)
{
PageBase0 = pageBase0;
PageBase1 = pageBase1;
PageSize = pageSize;
return init();
}
uint16 EEPROMClass::init(void)
{
uint16 status0, status1;
FLASH_Status FlashStatus;
FLASH_Unlock();
Status = EEPROM_NO_VALID_PAGE;
status0 = (*(__io uint16 *)PageBase0);
status1 = (*(__io uint16 *)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 = 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 EEPROMClass::format(void)
{
uint16 status;
FLASH_Status FlashStatus;
FLASH_Unlock();
// Erase Page0
status = EE_CheckErasePage(PageBase0, EEPROM_VALID_PAGE);
if (status != EEPROM_OK)
return status;
if ((*(__io uint16*)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 EEPROMClass::erases(uint16 *Erases)
{
uint32 pageBase;
if (Status != EEPROM_OK)
if (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*)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
* @retval Data for variable or EEPROM_DEFAULT_DATA, if any errors
*/
uint16 EEPROMClass::read (uint16 Address)
{
uint16 data;
read(Address, &data);
return data;
}
/**
* @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 EEPROMClass::read(uint16 Address, uint16 *Data)
{
uint32 pageBase, pageEnd;
// Set default data (empty EEPROM)
*Data = EEPROM_DEFAULT_DATA;
if (Status == EEPROM_NOT_INIT)
if (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)(PageSize - 2));
// Check each active page address starting from end
for (pageBase += 6; pageEnd >= pageBase; pageEnd -= 4)
if ((*(__io uint16*)pageEnd) == Address) // Compare the read address with the virtual address
{
*Data = (*(__io uint16*)(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/upadtes 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 EEPROMClass::write(uint16 Address, uint16 Data)
{
if (Status == EEPROM_NOT_INIT)
if (init() != EEPROM_OK)
return Status;
if (Address == 0xFFFF)
return EEPROM_BAD_ADDRESS;
// Write the variable virtual address and value in the EEPROM
uint16 status = EE_VerifyPageFullWriteVariable(Address, Data);
return status;
}
/**
* @brief Writes/upadtes variable data in EEPROM.
The value is written only if differs from the one already saved at the same address.
* @param VirtAddress: Variable virtual address
* @param Data: 16 bit data to be written
* @retval Success or error status:
* - EEPROM_SAME_VALUE: If new Data matches existing EEPROM Data
* - 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 EEPROMClass::update(uint16 Address, uint16 Data)
{
if (read(Address) == Data)
return EEPROM_SAME_VALUE;
else
return write(Address, Data);
}
/**
* @brief Return number of variable
* @retval Number of variables
*/
uint16 EEPROMClass::count(uint16 *Count)
{
if (Status == EEPROM_NOT_INIT)
if (init() != EEPROM_OK)
return Status;
// Get valid Page for write operation
uint32 pageBase = EE_FindValidPage();
if (pageBase == 0)
return EEPROM_NO_VALID_PAGE; // No valid page, return max. numbers
*Count = EE_GetVariablesCount(pageBase, 0xFFFF);
return EEPROM_OK;
}
uint16 EEPROMClass::maxcount(void)
{
return ((PageSize / 4)-1);
}
EEPROMClass EEPROM;

View File

@ -0,0 +1,93 @@
#ifndef __EEPROM_H
#define __EEPROM_H
#include <wirish.h>
#include "flash_stm32.h"
// HACK ALERT. This definition may not match your processor
// To Do. Work out correct value for EEPROM_PAGE_SIZE on the STM32F103CT6 etc
#define MCU_STM32F103RB
#ifndef EEPROM_PAGE_SIZE
#if defined (MCU_STM32F103RB)
#define EEPROM_PAGE_SIZE (uint16)0x400 /* Page size = 1KByte */
#elif defined (MCU_STM32F103ZE) || defined (MCU_STM32F103RE) || defined (MCU_STM32F103RD)
#define EEPROM_PAGE_SIZE (uint16)0x800 /* Page size = 2KByte */
#else
#error "No MCU type specified. Add something like -DMCU_STM32F103RB to your compiler arguments (probably in a Makefile)."
#endif
#endif
#ifndef EEPROM_START_ADDRESS
#if defined (MCU_STM32F103RB)
#define EEPROM_START_ADDRESS ((uint32)(0x8000000 + 128 * 1024 - 2 * EEPROM_PAGE_SIZE))
#elif defined (MCU_STM32F103ZE) || defined (MCU_STM32F103RE)
#define EEPROM_START_ADDRESS ((uint32)(0x8000000 + 512 * 1024 - 2 * EEPROM_PAGE_SIZE))
#elif defined (MCU_STM32F103RD)
#define EEPROM_START_ADDRESS ((uint32)(0x8000000 + 384 * 1024 - 2 * EEPROM_PAGE_SIZE))
#else
#error "No MCU type specified. Add something like -DMCU_STM32F103RB to your compiler arguments (probably in a Makefile)."
#endif
#endif
/* Pages 0 and 1 base and end addresses */
#define EEPROM_PAGE0_BASE ((uint32)(EEPROM_START_ADDRESS + 0x000))
#define EEPROM_PAGE1_BASE ((uint32)(EEPROM_START_ADDRESS + EEPROM_PAGE_SIZE))
/* Page status definitions */
#define EEPROM_ERASED ((uint16)0xFFFF) /* PAGE is empty */
#define EEPROM_RECEIVE_DATA ((uint16)0xEEEE) /* PAGE is marked to receive data */
#define EEPROM_VALID_PAGE ((uint16)0x0000) /* PAGE containing valid data */
/* Page full define */
enum : uint16
{
EEPROM_OK = ((uint16)0x0000),
EEPROM_OUT_SIZE = ((uint16)0x0081),
EEPROM_BAD_ADDRESS = ((uint16)0x0082),
EEPROM_BAD_FLASH = ((uint16)0x0083),
EEPROM_NOT_INIT = ((uint16)0x0084),
EEPROM_SAME_VALUE = ((uint16)0x0085),
EEPROM_NO_VALID_PAGE = ((uint16)0x00AB)
};
#define EEPROM_DEFAULT_DATA 0xFFFF
class EEPROMClass
{
public:
EEPROMClass(void);
uint16 init(void);
uint16 init(uint32, uint32, uint32);
uint16 format(void);
uint16 erases(uint16 *);
uint16 read (uint16 address);
uint16 read (uint16 address, uint16 *data);
uint16 write(uint16 address, uint16 data);
uint16 update(uint16 address, uint16 data);
uint16 count(uint16 *);
uint16 maxcount(void);
uint32 PageBase0;
uint32 PageBase1;
uint32 PageSize;
uint16 Status;
private:
FLASH_Status EE_ErasePage(uint32);
uint16 EE_CheckPage(uint32, uint16);
uint16 EE_CheckErasePage(uint32, uint16);
uint16 EE_Format(void);
uint32 EE_FindValidPage(void);
uint16 EE_GetVariablesCount(uint32, uint16);
uint16 EE_PageTransfer(uint32, uint32, uint16);
uint16 EE_VerifyPageFullWriteVariable(uint16, uint16);
};
extern EEPROMClass EEPROM;
#endif /* __EEPROM_H */

View File

@ -0,0 +1,167 @@
#include <EEPROM.h>
int ledPin = 13; // LED connected to digital pin 13
const char HELP_MSG[] = "Press :\r\n" \
" 0 display configuration\r\n" \
" 1 set configuration to 0x801F000 / 0x801F800 / 0x400 (RB MCU)\r\n" \
" 2 set configuration to 0x801F000 / 0x801F800 / 0x800 (ZE/RE MCU)\r\n" \
" 3 write/read variable\r\n" \
" 4 increment address\r\n" \
" 5 display pages top/bottom\r\n" \
" 6 initialize EEPROM\r\n" \
" 7 format EEPROM\r\n";
uint16 DataWrite = 0;
uint16 AddressWrite = 0x10;
void setup()
{
// initialize the digital pin as an output:
pinMode(ledPin, OUTPUT);
Serial.begin(115200);
Serial.print(HELP_MSG);
}
void loop()
{
uint16 Status;
uint16 Data;
while (Serial.available())
{
char cmd = (char)Serial.read();
Serial.println(cmd);
if (cmd == '0')
{
DisplayConfig();
}
else if (cmd == '1')
{
EEPROM.PageBase0 = 0x801F000;
EEPROM.PageBase1 = 0x801F800;
EEPROM.PageSize = 0x400;
DisplayConfig();
}
else if (cmd == '2')
{
EEPROM.PageBase0 = 0x801F000;
EEPROM.PageBase1 = 0x801F800;
EEPROM.PageSize = 0x800;
DisplayConfig();
}
else if (cmd == '3')
{
Status = EEPROM.write(AddressWrite, DataWrite);
Serial.print("EEPROM.write(0x");
Serial.print(AddressWrite, HEX);
Serial.print(", 0x");
Serial.print(DataWrite, HEX);
Serial.print(") : Status : ");
Serial.println(Status, HEX);
Status = EEPROM.read(AddressWrite, &Data);
Serial.print("EEPROM.read(0x");
Serial.print(AddressWrite, HEX);
Serial.print(", &..) = 0x");
Serial.print(Data, HEX);
Serial.print(" : Status : ");
Serial.println(Status, HEX);
++DataWrite;
}
else if (cmd == '4')
{
++AddressWrite;
}
else if (cmd == '5')
{
DisplayPages(0x20);
DisplayPagesEnd(0x20);
}
else if (cmd == '6')
{
Status = EEPROM.init();
Serial.print("EEPROM.init() : ");
Serial.println(Status, HEX);
Serial.println();
}
else if (cmd == '7')
{
Status = EEPROM.format();
Serial.print("EEPROM.format() : ");
Serial.println(Status, HEX);
}
else
Serial.print(HELP_MSG);
}
digitalWrite(ledPin, HIGH);
delay(500);
digitalWrite(ledPin, LOW);
delay(500);
}
void DisplayConfig(void)
{
Serial.print ("EEPROM.PageBase0 : 0x");
Serial.println(EEPROM.PageBase0, HEX);
Serial.print ("EEPROM.PageBase1 : 0x");
Serial.println(EEPROM.PageBase1, HEX);
Serial.print ("EEPROM.PageSize : 0x");
Serial.print (EEPROM.PageSize, HEX);
Serial.print (" (");
Serial.print (EEPROM.PageSize, DEC);
Serial.println(")");
}
void DisplayHex(uint16 value)
{
if (value <= 0xF)
Serial.print("000");
else if (value <= 0xFF)
Serial.print("00");
else if (value <= 0xFFF)
Serial.print("0");
Serial.print(value, HEX);
}
void DisplayPages(uint32 endIndex)
{
Serial.println("Page 0 Top Page 1");
for (uint32 idx = 0; idx < endIndex; idx += 4)
{
Serial.print (EEPROM.PageBase0 + idx, HEX);
Serial.print (" : ");
DisplayHex(*(uint16*)(EEPROM.PageBase0 + idx));
Serial.print (" ");
DisplayHex(*(uint16*)(EEPROM.PageBase0 + idx + 2));
Serial.print (" ");
Serial.print (EEPROM.PageBase1 + idx, HEX);
Serial.print (" : ");
DisplayHex(*(uint16*)(EEPROM.PageBase1 + idx));
Serial.print (" ");
DisplayHex(*(uint16*)(EEPROM.PageBase1 + idx + 2));
Serial.println();
}
}
void DisplayPagesEnd(uint32 endIndex)
{
Serial.println("Page 0 Bottom Page 1");
for (uint32 idx = EEPROM.PageSize - endIndex; idx < EEPROM.PageSize; idx += 4)
{
Serial.print (EEPROM.PageBase0 + idx, HEX);
Serial.print (" : ");
DisplayHex(*(uint16*)(EEPROM.PageBase0 + idx));
Serial.print (" ");
DisplayHex(*(uint16*)(EEPROM.PageBase0 + idx + 2));
Serial.print (" ");
Serial.print (EEPROM.PageBase1 + idx, HEX);
Serial.print (" : ");
DisplayHex(*(uint16*)(EEPROM.PageBase1 + idx));
Serial.print (" ");
DisplayHex(*(uint16*)(EEPROM.PageBase1 + idx + 2));
Serial.println();
}
}

View File

@ -0,0 +1,160 @@
//#include "libmaple.h"
#include "libmaple/util.h"
#include "libmaple/flash.h"
#include "flash_stm32.h"
#define FLASH_KEY1 ((uint32)0x45670123)
#define FLASH_KEY2 ((uint32)0xCDEF89AB)
/* Delay definition */
#define EraseTimeout ((uint32)0x00000FFF)
#define ProgramTimeout ((uint32)0x0000001F)
/**
* @brief Inserts a time delay.
* @param None
* @retval None
*/
static void delay(void)
{
__io uint32 i = 0;
for(i = 0xFF; i != 0; i--) { }
}
/**
* @brief Returns the FLASH Status.
* @param None
* @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG,
* FLASH_ERROR_WRP or FLASH_COMPLETE
*/
FLASH_Status FLASH_GetStatus(void)
{
if ((FLASH_BASE->SR & FLASH_SR_BSY) == FLASH_SR_BSY)
return FLASH_BUSY;
if ((FLASH_BASE->SR & FLASH_SR_PGERR) != 0)
return FLASH_ERROR_PG;
if ((FLASH_BASE->SR & FLASH_SR_WRPRTERR) != 0 )
return FLASH_ERROR_WRP;
if ((FLASH_BASE->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_WaitForLastOperation(uint32 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 Page_Address)
{
FLASH_Status status = FLASH_COMPLETE;
/* Check the parameters */
ASSERT(IS_FLASH_ADDRESS(Page_Address));
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation(EraseTimeout);
if(status == FLASH_COMPLETE)
{
/* if the previous operation is completed, proceed to erase the page */
FLASH_BASE->CR |= FLASH_CR_PER;
FLASH_BASE->AR = Page_Address;
FLASH_BASE->CR |= FLASH_CR_STRT;
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation(EraseTimeout);
if(status != FLASH_TIMEOUT)
{
/* if the erase operation is completed, disable the PER Bit */
FLASH_BASE->CR &= ~FLASH_CR_PER;
}
FLASH_BASE->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 Address, uint16 Data)
{
FLASH_Status status = FLASH_BAD_ADDRESS;
if (IS_FLASH_ADDRESS(Address))
{
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation(ProgramTimeout);
if(status == FLASH_COMPLETE)
{
/* if the previous operation is completed, proceed to program the new data */
FLASH_BASE->CR |= FLASH_CR_PG;
*(__io uint16*)Address = Data;
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation(ProgramTimeout);
if(status != FLASH_TIMEOUT)
{
/* if the program operation is completed, disable the PG Bit */
FLASH_BASE->CR &= ~FLASH_CR_PG;
}
FLASH_BASE->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_BASE->KEYR = FLASH_KEY1;
FLASH_BASE->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_BASE->CR |= FLASH_CR_LOCK;
}

View File

@ -0,0 +1,32 @@
#ifndef __FLASH_STM32_H
#define __FLASH_STM32_H
#ifdef __cplusplus
extern "C" {
#endif
typedef enum
{
FLASH_BUSY = 1,
FLASH_ERROR_PG,
FLASH_ERROR_WRP,
FLASH_ERROR_OPT,
FLASH_COMPLETE,
FLASH_TIMEOUT,
FLASH_BAD_ADDRESS
} FLASH_Status;
#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x0807FFFF))
FLASH_Status FLASH_WaitForLastOperation(uint32 Timeout);
FLASH_Status FLASH_ErasePage(uint32 Page_Address);
FLASH_Status FLASH_ProgramHalfWord(uint32 Address, uint16 Data);
void FLASH_Unlock(void);
void FLASH_Lock(void);
#ifdef __cplusplus
}
#endif
#endif /* __FLASH_STM32_H */

View File

@ -0,0 +1,27 @@
#######################################
# Syntax Coloring Map For EEPROM
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
EEPROM KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
init KEYWORD2
format KEYWORD2
erases KEYWORD2
read KEYWORD2
write KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################
PageBase0
PageBase1
PageSize
Status

View File

@ -0,0 +1,76 @@
/**
SPI_1 and SPI_2 port example code
Description:
This sketch sends one byte with value 0x55 over the SPI_1 or SPI_2 port.
The received byte (the answer from the SPI slave device) is stored to the <data> variable.
The sketch as it is, works with SPI_1 port. For using the SPI_2 port, just
un-comment all the nessesary code lines marked with <SPI_2> word.
Created on 10 Jun 2015 by Vassilis Serasidis
email: avrsite@yahoo.gr
Using the first SPI port (SPI_1)
SS <--> PA4 <--> BOARD_SPI1_NSS_PIN
SCK <--> PA5 <--> BOARD_SPI1_SCK_PIN
MISO <--> PA6 <--> BOARD_SPI1_MISO_PIN
MOSI <--> PA7 <--> BOARD_SPI1_MOSI_PIN
Using the second SPI port (SPI_2)
SS <--> PB12 <--> BOARD_SPI2_NSS_PIN
SCK <--> PB13 <--> BOARD_SPI2_SCK_PIN
MISO <--> PB14 <--> BOARD_SPI2_MISO_PIN
MOSI <--> PB15 <--> BOARD_SPI2_MOSI_PIN
*/
#include <SPI.h>
#define SPI1_NSS_PIN PA4 //SPI_1 Chip Select pin is PA4. You can change it to the STM32 pin you want.
#define SPI2_NSS_PIN PB12 //SPI_2 Chip Select pin is PB12. You can change it to the STM32 pin you want.
SPIClass SPI_2(2); //Create an instance of the SPI Class called SPI_2 that uses the 2nd SPI Port
byte data;
void setup() {
// Setup SPI 1
SPI.begin(); //Initialize the SPI_1 port.
SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order
SPI.setDataMode(SPI_MODE0); //Set the SPI_2 data mode 0
SPI.setClockDivider(SPI_CLOCK_DIV16); // Slow speed (72 / 16 = 4.5 MHz SPI_1 speed)
pinMode(SPI1_NSS_PIN, OUTPUT);
// Setup SPI 2
SPI_2.begin(); //Initialize the SPI_2 port.
SPI_2.setBitOrder(MSBFIRST); // Set the SPI_2 bit order
SPI_2.setDataMode(SPI_MODE0); //Set the SPI_2 data mode 0
SPI_2.setClockDivider(SPI_CLOCK_DIV16); // Use a different speed to SPI 1
pinMode(SPI2_NSS_PIN, OUTPUT);
}
void loop() {
sendSPI();
sendSPI2();
delayMicroseconds(10); //Delay 10 micro seconds.
}
void sendSPI()
{
digitalWrite(SPI1_NSS_PIN, LOW); // manually take CSN low for SPI_1 transmission
data = SPI.transfer(0x55); //Send the HEX data 0x55 over SPI-1 port and store the received byte to the <data> variable.
digitalWrite(SPI1_NSS_PIN, HIGH); // manually take CSN high between spi transmissions
}
void sendSPI2()
{
digitalWrite(SPI2_NSS_PIN, LOW); // manually take CSN low for SPI_2 transmission
data = SPI_2.transfer(0x55); //Send the HEX data 0x55 over SPI-2 port and store the received byte to the <data> variable.
digitalWrite(SPI2_NSS_PIN, HIGH); // manually take CSN high between spi transmissions
}

View File

@ -0,0 +1,31 @@
#######################################
# Syntax Coloring Map SPI
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
SPI KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
begin KEYWORD2
end KEYWORD2
transfer KEYWORD2
#setBitOrder KEYWORD2
setDataMode KEYWORD2
setClockDivider KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################
SPI_MODE0 LITERAL1
SPI_MODE1 LITERAL1
SPI_MODE2 LITERAL1
SPI_MODE3 LITERAL1
SPI_CONTINUE LITERAL1
SPI_LAST LITERAL1

View File

@ -0,0 +1,10 @@
name=SPI
version=1.0
author=Roger Clark
email=
sentence=Serial Peripheral Interface
paragraph=SPI for STM32F1
url=
architectures=STM32F1
maintainer=
category=Communication

View File

@ -0,0 +1,776 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Wirish SPI implementation.
*/
#include "SPI.h"
#include <libmaple/timer.h>
#include <libmaple/util.h>
#include <libmaple/rcc.h>
#include "wirish.h"
#include "boards.h"
//#include "HardwareSerial.h"
/** Time in ms for DMA receive timeout */
#define DMA_TIMEOUT 100
#if CYCLES_PER_MICROSECOND != 72
/* TODO [0.2.0?] something smarter than this */
#warning "Unexpected clock speed; SPI frequency calculation will be incorrect"
#endif
struct spi_pins {
uint8 nss;
uint8 sck;
uint8 miso;
uint8 mosi;
};
static const spi_pins* dev_to_spi_pins(spi_dev *dev);
static void configure_gpios(spi_dev *dev, bool as_master);
static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq);
#if (BOARD_NR_SPI >= 3) && !defined(STM32_HIGH_DENSITY)
#error "The SPI library is misconfigured: 3 SPI ports only available on high density STM32 devices"
#endif
static const spi_pins board_spi_pins[] __FLASH__ = {
#if BOARD_NR_SPI >= 1
{BOARD_SPI1_NSS_PIN,
BOARD_SPI1_SCK_PIN,
BOARD_SPI1_MISO_PIN,
BOARD_SPI1_MOSI_PIN},
#endif
#if BOARD_NR_SPI >= 2
{BOARD_SPI2_NSS_PIN,
BOARD_SPI2_SCK_PIN,
BOARD_SPI2_MISO_PIN,
BOARD_SPI2_MOSI_PIN},
#endif
#if BOARD_NR_SPI >= 3
{BOARD_SPI3_NSS_PIN,
BOARD_SPI3_SCK_PIN,
BOARD_SPI3_MISO_PIN,
BOARD_SPI3_MOSI_PIN},
#endif
};
/*
* Constructor
*/
SPIClass::SPIClass(uint32 spi_num)
{
_currentSetting=&_settings[spi_num-1];// SPI channels are called 1 2 and 3 but the array is zero indexed
switch (spi_num) {
#if BOARD_NR_SPI >= 1
case 1:
_currentSetting->spi_d = SPI1;
_spi1_this = (void*) this;
break;
#endif
#if BOARD_NR_SPI >= 2
case 2:
_currentSetting->spi_d = SPI2;
_spi2_this = (void*) this;
break;
#endif
#if BOARD_NR_SPI >= 3
case 3:
_currentSetting->spi_d = SPI3;
_spi3_this = (void*) this;
break;
#endif
default:
ASSERT(0);
}
// Init things specific to each SPI device
// clock divider setup is a bit of hack, and needs to be improved at a later date.
_settings[0].spi_d = SPI1;
_settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock);
_settings[0].spiDmaDev = DMA1;
_settings[0].spiTxDmaChannel = DMA_CH3;
_settings[0].spiRxDmaChannel = DMA_CH2;
_settings[1].spi_d = SPI2;
_settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock);
_settings[1].spiDmaDev = DMA1;
_settings[1].spiTxDmaChannel = DMA_CH5;
_settings[1].spiRxDmaChannel = DMA_CH4;
#if BOARD_NR_SPI >= 3
_settings[2].spi_d = SPI3;
_settings[2].clockDivider = determine_baud_rate(_settings[2].spi_d, _settings[2].clock);
_settings[2].spiDmaDev = DMA2;
_settings[2].spiTxDmaChannel = DMA_CH2;
_settings[2].spiRxDmaChannel = DMA_CH1;
#endif
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_IDLE;
}
/*
* Set up/tear down
*/
void SPIClass::updateSettings(void) {
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_SW_SLAVE | SPI_SOFT_SS);
spi_master_enable(_currentSetting->spi_d, (spi_baud_rate)_currentSetting->clockDivider, (spi_mode)_currentSetting->dataMode, flags);
}
void SPIClass::begin(void) {
spi_init(_currentSetting->spi_d);
configure_gpios(_currentSetting->spi_d, 1);
updateSettings();
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_READY;
}
void SPIClass::beginSlave(void) {
spi_init(_currentSetting->spi_d);
configure_gpios(_currentSetting->spi_d, 0);
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_RX_ONLY);
spi_slave_enable(_currentSetting->spi_d, (spi_mode)_currentSetting->dataMode, flags);
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_READY;
}
void SPIClass::end(void) {
if (!spi_is_enabled(_currentSetting->spi_d)) {
return;
}
// Follows RM0008's sequence for disabling a SPI in master/slave
// full duplex mode.
while (spi_is_rx_nonempty(_currentSetting->spi_d)) {
// FIXME [0.1.0] remove this once you have an interrupt based driver
volatile uint16 rx __attribute__((unused)) = spi_rx_reg(_currentSetting->spi_d);
}
while (!spi_is_tx_empty(_currentSetting->spi_d))
;
while (spi_is_busy(_currentSetting->spi_d))
;
spi_peripheral_disable(_currentSetting->spi_d);
// added for DMA callbacks.
// Need to add unsetting the callbacks for the DMA channels.
_currentSetting->state = SPI_STATE_IDLE;
}
/* Roger Clark added 3 functions */
void SPIClass::setClockDivider(uint32_t clockDivider)
{
_currentSetting->clockDivider = clockDivider;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_BR);
_currentSetting->spi_d->regs->CR1 = cr1 | (clockDivider & SPI_CR1_BR);
}
void SPIClass::setBitOrder(BitOrder bitOrder)
{
_currentSetting->bitOrder = bitOrder;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_LSBFIRST);
if ( bitOrder==LSBFIRST ) cr1 |= SPI_CR1_LSBFIRST;
_currentSetting->spi_d->regs->CR1 = cr1;
}
/* Victor Perez. Added to test changing datasize from 8 to 16 bit modes on the fly.
* Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word.
*
*/
void SPIClass::setDataSize(uint32 datasize)
{
_currentSetting->dataSize = datasize;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_DFF);
uint8 en = spi_is_enabled(_currentSetting->spi_d);
spi_peripheral_disable(_currentSetting->spi_d);
_currentSetting->spi_d->regs->CR1 = cr1 | (datasize & SPI_CR1_DFF) | en;
}
void SPIClass::setDataMode(uint8_t dataMode)
{
/* Notes. As far as I can tell, the AVR numbers for dataMode appear to match the numbers required by the STM32
From the AVR doc http://www.atmel.com/images/doc2585.pdf section 2.4
SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge
0 0 0 Falling Rising
1 0 1 Rising Falling
2 1 0 Rising Falling
3 1 1 Falling Rising
On the STM32 it appears to be
bit 1 - CPOL : Clock polarity
(This bit should not be changed when communication is ongoing)
0 : CLK to 0 when idle
1 : CLK to 1 when idle
bit 0 - CPHA : Clock phase
(This bit should not be changed when communication is ongoing)
0 : The first clock transition is the first data capture edge
1 : The second clock transition is the first data capture edge
If someone finds this is not the case or sees a logic error with this let me know ;-)
*/
_currentSetting->dataMode = dataMode;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_CPOL|SPI_CR1_CPHA);
_currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL|SPI_CR1_CPHA));
}
void SPIClass::beginTransaction(uint8_t pin, SPISettings settings)
{
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
setClockDivider(determine_baud_rate(_currentSetting->spi_d, settings.clock));
begin();
}
void SPIClass::beginTransactionSlave(SPISettings settings)
{
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
beginSlave();
}
void SPIClass::endTransaction(void)
{
//digitalWrite(_SSPin,HIGH);
#if false
// code from SAM core
uint8_t mode = interruptMode;
if (mode > 0) {
if (mode < 16) {
if (mode & 1) PIOA->PIO_IER = interruptMask[0];
if (mode & 2) PIOB->PIO_IER = interruptMask[1];
if (mode & 4) PIOC->PIO_IER = interruptMask[2];
if (mode & 8) PIOD->PIO_IER = interruptMask[3];
} else {
if (interruptSave) interrupts();
}
}
#endif
}
/*
* I/O
*/
uint16 SPIClass::read(void)
{
while ( spi_is_rx_nonempty(_currentSetting->spi_d)==0 ) ;
return (uint16)spi_rx_reg(_currentSetting->spi_d);
}
void SPIClass::read(uint8 *buf, uint32 len)
{
if ( len == 0 ) return;
spi_rx_reg(_currentSetting->spi_d); // clear the RX buffer in case a byte is waiting on it.
spi_reg_map * regs = _currentSetting->spi_d->regs;
// start sequence: write byte 0
regs->DR = 0x00FF; // write the first byte
// main loop
while ( (--len) ) {
while( !(regs->SR & SPI_SR_TXE) ); // wait for TXE flag
noInterrupts(); // go atomic level - avoid interrupts to surely get the previously received data
regs->DR = 0x00FF; // write the next data item to be transmitted into the SPI_DR register. This clears the TXE flag.
while ( !(regs->SR & SPI_SR_RXNE) ); // wait till data is available in the DR register
*buf++ = (uint8)(regs->DR); // read and store the received byte. This clears the RXNE flag.
interrupts(); // let systick do its job
}
// read remaining last byte
while ( !(regs->SR & SPI_SR_RXNE) ); // wait till data is available in the Rx register
*buf++ = (uint8)(regs->DR); // read and store the received byte
}
void SPIClass::write(uint16 data)
{
/* Added for 16bit data Victor Perez. Roger Clark
* Improved speed by just directly writing the single byte to the SPI data reg and wait for completion,
* by taking the Tx code from transfer(byte)
* This almost doubles the speed of this function.
*/
spi_tx_reg(_currentSetting->spi_d, data); // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
}
void SPIClass::write16(uint16 data)
{
// Added by stevestrong: write two consecutive bytes in 8 bit mode (DFF=0)
spi_tx_reg(_currentSetting->spi_d, data>>8); // write high byte
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // Wait until TXE=1
spi_tx_reg(_currentSetting->spi_d, data); // write low byte
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // Wait until TXE=1
while (spi_is_busy(_currentSetting->spi_d) != 0); // wait until BSY=0
}
void SPIClass::write(uint16 data, uint32 n)
{
// Added by stevstrong: Repeatedly send same data by the specified number of times
spi_reg_map * regs = _currentSetting->spi_d->regs;
while ( (n--)>0 ) {
regs->DR = data; // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
while ( (regs->SR & SPI_SR_TXE)==0 ) ; // wait till Tx empty
}
while ( (regs->SR & SPI_SR_BSY) != 0); // wait until BSY=0 before returning
}
void SPIClass::write(const void *data, uint32 length)
{
spi_dev * spi_d = _currentSetting->spi_d;
spi_tx(spi_d, data, length); // data can be array of bytes or words
while (spi_is_tx_empty(spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
}
uint8 SPIClass::transfer(uint8 byte) const
{
spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, byte); // Write the data item to be transmitted into the SPI_DR register
while (spi_is_tx_empty(spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
return (uint8)spi_rx_reg(spi_d); // "... and read the last received data."
}
uint16_t SPIClass::transfer16(uint16_t data) const
{
// Modified by stevestrong: write & read two consecutive bytes in 8 bit mode (DFF=0)
// This is more effective than two distinct byte transfers
spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, data>>8); // write high byte
while (spi_is_tx_empty(spi_d) == 0); // wait until TXE=1
while (spi_is_busy(spi_d) != 0); // wait until BSY=0
uint16_t ret = spi_rx_reg(spi_d)<<8; // read and shift high byte
spi_tx_reg(spi_d, data); // write low byte
while (spi_is_tx_empty(spi_d) == 0); // wait until TXE=1
while (spi_is_busy(spi_d) != 0); // wait until BSY=0
ret += spi_rx_reg(spi_d); // read low byte
return ret;
}
/* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer.
* If a TX buffer is not provided, FF is sent over and over for the lenght of the transfer.
* On exit TX buffer is not modified, and RX buffer cotains the received data.
* Still in progress.
*/
void SPIClass::dmaTransferSet(const void *transmitBuf, void *receiveBuf) {
dma_init(_currentSetting->spiDmaDev);
//spi_rx_dma_enable(_currentSetting->spi_d);
//spi_tx_dma_enable(_currentSetting->spi_d);
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
receiveBuf, dma_bit_size, (DMA_MINC_MODE | DMA_TRNS_CMPLT ));// receive buffer DMA
if (!transmitBuf) {
transmitBuf = &ff;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, (DMA_FROM_MEM));// Transmit FF repeatedly
}
else {
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, (DMA_MINC_MODE | DMA_FROM_MEM ));// Transmit buffer DMA
}
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW);
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, DMA_PRIORITY_VERY_HIGH);
}
uint8 SPIClass::dmaTransferRepeat(uint16 length) {
if (length == 0) return 0;
if (spi_is_rx_nonempty(_currentSetting->spi_d) == 1) spi_rx_reg(_currentSetting->spi_d);
_currentSetting->state = SPI_STATE_TRANSFER;
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, length);
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);// enable receive
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_rx_dma_enable(_currentSetting->spi_d);
spi_tx_dma_enable(_currentSetting->spi_d);
if (_currentSetting->receiveCallback){
return 0;
}
//uint32_t m = millis();
uint8 b = 0;
uint32_t m = millis();
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) {
//Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
return b;
}
/* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer.
* If a TX buffer is not provided, FF is sent over and over for the length of the transfer.
* On exit TX buffer is not modified, and RX buffer contains the received data.
* Still in progress.
*/
uint8 SPIClass::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16 length) {
dmaTransferSet(transmitBuf, receiveBuf);
return dmaTransferRepeat(length);
}
/* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI send using a TX buffer.
* On exit TX buffer is not modified.
* Still in progress.
* 2016 - stevstrong - reworked to automatically detect bit size from SPI setting
*/
void SPIClass::dmaSendSet(const void * transmitBuf, bool minc) {
uint32 flags = ( (DMA_MINC_MODE*minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
dma_init(_currentSetting->spiDmaDev);
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, flags);// Transmit buffer DMA
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW);
}
uint8 SPIClass::dmaSendRepeat(uint16 length) {
if (length == 0) return 0;
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
_currentSetting->state = SPI_STATE_TRANSMIT;
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_tx_dma_enable(_currentSetting->spi_d);
if (_currentSetting->transmitCallback)
{
return 0;
}
uint32_t m = millis();
uint8 b = 0;
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) {
//Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
return b;
}
uint8 SPIClass::dmaSend(const void * transmitBuf, uint16 length, bool minc) {
dmaSendSet(transmitBuf, minc);
return dmaSendRepeat(length);
}
uint8 SPIClass::dmaSendAsync(const void * transmitBuf, uint16 length, bool minc) {
uint8 b = 0;
if (_currentSetting->state != SPI_STATE_READY)
{
uint32_t m = millis();
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) {//Avoid interrupts and just loop waiting for the flag to be set.
//delayMicroseconds(10);
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
}
if (length == 0) return 0;
uint32 flags = ( (DMA_MINC_MODE*minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
dma_init(_currentSetting->spiDmaDev);
// TX
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, flags);// Transmit buffer DMA
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_tx_dma_enable(_currentSetting->spi_d);
_currentSetting->state = SPI_STATE_TRANSMIT;
return b;
}
/*
New functions added to manage callbacks.
Victor Perez 2017
*/
void SPIClass::onReceive(void(*callback)(void)) {
_currentSetting->receiveCallback = callback;
if (callback){
switch (_currentSetting->spi_d->clk_id) {
case RCC_SPI1:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback);
break;
case RCC_SPI2:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback);
break;
#if BOARD_NR_SPI >= 3
case RCC_SPI3:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback);
break;
#endif
default:
ASSERT(0);
}
}
else {
dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
}
}
void SPIClass::onTransmit(void(*callback)(void)) {
_currentSetting->transmitCallback = callback;
if (callback){
switch (_currentSetting->spi_d->clk_id) {
case RCC_SPI1:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback);
break;
case RCC_SPI2:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback);
break;
#if BOARD_NR_SPI >= 3
case RCC_SPI3:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback);
break;
#endif
default:
ASSERT(0);
}
}
else {
dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
}
}
/*
TODO: check if better to first call the customer code, next disable the DMA requests.
Also see if we need to check whether callbacks are set or not, may be better to be checked during the initial setup and only set the callback to EventCallback if they are set.
*/
void SPIClass::EventCallback() {
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0"
switch (_currentSetting->state) {
case SPI_STATE_TRANSFER:
while (spi_is_rx_nonempty(_currentSetting->spi_d));
_currentSetting->state = SPI_STATE_READY;
spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
if (_currentSetting->receiveCallback)
{
_currentSetting->receiveCallback();
}
break;
case SPI_STATE_TRANSMIT:
_currentSetting->state = SPI_STATE_READY;
spi_tx_dma_disable(_currentSetting->spi_d);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
if (_currentSetting->transmitCallback)
{
_currentSetting->transmitCallback();
}
break;
default:
// we shouldn't get here, so better to add an assert and fail.
return;
}
}
void SPIClass::attachInterrupt(void) {
// Should be enableInterrupt()
}
void SPIClass::detachInterrupt(void) {
// Should be disableInterrupt()
}
/*
* Pin accessors
*/
uint8 SPIClass::misoPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->miso;
}
uint8 SPIClass::mosiPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->mosi;
}
uint8 SPIClass::sckPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->sck;
}
uint8 SPIClass::nssPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->nss;
}
/*
* Deprecated functions
*/
uint8 SPIClass::send(uint8 data) {
this->write(data);
return 1;
}
uint8 SPIClass::send(uint8 *buf, uint32 len) {
this->write(buf, len);
return len;
}
uint8 SPIClass::recv(void) {
return this->read();
}
/*
DMA call back functions, one per port.
*/
void SPIClass::_spi1EventCallback()
{
reinterpret_cast<class SPIClass*>(_spi1_this)->EventCallback();
}
void SPIClass::_spi2EventCallback() {
reinterpret_cast<class SPIClass*>(_spi2_this)->EventCallback();
}
#if BOARD_NR_SPI >= 3
void SPIClass::_spi3EventCallback() {
reinterpret_cast<class SPIClass*>(_spi3_this)->EventCallback();
}
#endif
/*
* Auxiliary functions
*/
static const spi_pins* dev_to_spi_pins(spi_dev *dev) {
switch (dev->clk_id) {
#if BOARD_NR_SPI >= 1
case RCC_SPI1: return board_spi_pins;
#endif
#if BOARD_NR_SPI >= 2
case RCC_SPI2: return board_spi_pins + 1;
#endif
#if BOARD_NR_SPI >= 3
case RCC_SPI3: return board_spi_pins + 2;
#endif
default: return NULL;
}
}
static void disable_pwm(const stm32_pin_info *i) {
if (i->timer_device) {
timer_set_mode(i->timer_device, i->timer_channel, TIMER_DISABLED);
}
}
static void configure_gpios(spi_dev *dev, bool as_master) {
const spi_pins *pins = dev_to_spi_pins(dev);
if (!pins) {
return;
}
const stm32_pin_info *nssi = &PIN_MAP[pins->nss];
const stm32_pin_info *scki = &PIN_MAP[pins->sck];
const stm32_pin_info *misoi = &PIN_MAP[pins->miso];
const stm32_pin_info *mosii = &PIN_MAP[pins->mosi];
disable_pwm(nssi);
disable_pwm(scki);
disable_pwm(misoi);
disable_pwm(mosii);
spi_config_gpios(dev, as_master, nssi->gpio_device, nssi->gpio_bit,
scki->gpio_device, scki->gpio_bit, misoi->gpio_bit,
mosii->gpio_bit);
}
static const spi_baud_rate baud_rates[8] __FLASH__ = {
SPI_BAUD_PCLK_DIV_2,
SPI_BAUD_PCLK_DIV_4,
SPI_BAUD_PCLK_DIV_8,
SPI_BAUD_PCLK_DIV_16,
SPI_BAUD_PCLK_DIV_32,
SPI_BAUD_PCLK_DIV_64,
SPI_BAUD_PCLK_DIV_128,
SPI_BAUD_PCLK_DIV_256,
};
/*
* Note: This assumes you're on a LeafLabs-style board
* (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz).
*/
static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq) {
uint32_t clock = 0, i;
switch (rcc_dev_clk(dev->clk_id))
{
case RCC_APB2: clock = STM32_PCLK2; break; // 72 Mhz
case RCC_APB1: clock = STM32_PCLK1; break; // 36 Mhz
}
clock /= 2;
i = 0;
while (i < 7 && freq < clock) {
clock /= 2;
i++;
}
return baud_rates[i];
}
SPIClass SPI(1);

View File

@ -0,0 +1,430 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file wirish/include/wirish/HardwareSPI.h
* @brief High-level SPI interface
*
* This is a "bare essentials" polling driver for now.
*/
/* TODO [0.1.0] Remove deprecated methods. */
#ifndef _SPI_H_INCLUDED
#define _SPI_H_INCLUDED
#include <libmaple/libmaple_types.h>
#include <libmaple/spi.h>
#include <libmaple/dma.h>
#include <boards.h>
#include <stdint.h>
#include <wirish.h>
// SPI_HAS_TRANSACTION means SPI has
// - beginTransaction()
// - endTransaction()
// - usingInterrupt()
// - SPISetting(clock, bitOrder, dataMode)
//#define SPI_HAS_TRANSACTION
#define SPI_CLOCK_DIV2 SPI_BAUD_PCLK_DIV_2
#define SPI_CLOCK_DIV4 SPI_BAUD_PCLK_DIV_4
#define SPI_CLOCK_DIV8 SPI_BAUD_PCLK_DIV_8
#define SPI_CLOCK_DIV16 SPI_BAUD_PCLK_DIV_16
#define SPI_CLOCK_DIV32 SPI_BAUD_PCLK_DIV_32
#define SPI_CLOCK_DIV64 SPI_BAUD_PCLK_DIV_64
#define SPI_CLOCK_DIV128 SPI_BAUD_PCLK_DIV_128
#define SPI_CLOCK_DIV256 SPI_BAUD_PCLK_DIV_256
/*
* Roger Clark. 20150106
* Commented out redundant AVR defined
*
#define SPI_MODE_MASK 0x0C // CPOL = bit 3, CPHA = bit 2 on SPCR
#define SPI_CLOCK_MASK 0x03 // SPR1 = bit 1, SPR0 = bit 0 on SPCR
#define SPI_2XCLOCK_MASK 0x01 // SPI2X = bit 0 on SPSR
// define SPI_AVR_EIMSK for AVR boards with external interrupt pins
#if defined(EIMSK)
#define SPI_AVR_EIMSK EIMSK
#elif defined(GICR)
#define SPI_AVR_EIMSK GICR
#elif defined(GIMSK)
#define SPI_AVR_EIMSK GIMSK
#endif
*/
#ifndef STM32_LSBFIRST
#define STM32_LSBFIRST 0
#endif
#ifndef STM32_MSBFIRST
#define STM32_MSBFIRST 1
#endif
// PC13 or PA4
#define BOARD_SPI_DEFAULT_SS PA4
//#define BOARD_SPI_DEFAULT_SS PC13
#define SPI_MODE0 SPI_MODE_0
#define SPI_MODE1 SPI_MODE_1
#define SPI_MODE2 SPI_MODE_2
#define SPI_MODE3 SPI_MODE_3
#define DATA_SIZE_8BIT SPI_CR1_DFF_8_BIT
#define DATA_SIZE_16BIT SPI_CR1_DFF_16_BIT
typedef enum {
SPI_STATE_IDLE,
SPI_STATE_READY,
SPI_STATE_RECEIVE,
SPI_STATE_TRANSMIT,
SPI_STATE_TRANSFER
} spi_mode_t;
class SPISettings {
public:
SPISettings(uint32_t clock, BitOrder bitOrder, uint8_t dataMode) {
if (__builtin_constant_p(clock)) {
init_AlwaysInline(clock, bitOrder, dataMode, DATA_SIZE_8BIT);
} else {
init_MightInline(clock, bitOrder, dataMode, DATA_SIZE_8BIT);
}
}
SPISettings(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) {
if (__builtin_constant_p(clock)) {
init_AlwaysInline(clock, bitOrder, dataMode, dataSize);
} else {
init_MightInline(clock, bitOrder, dataMode, dataSize);
}
}
SPISettings(uint32_t clock) {
if (__builtin_constant_p(clock)) {
init_AlwaysInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
} else {
init_MightInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
}
}
SPISettings() { init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); }
private:
void init_MightInline(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) {
init_AlwaysInline(clock, bitOrder, dataMode, dataSize);
}
void init_AlwaysInline(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) __attribute__((__always_inline__)) {
this->clock = clock;
this->bitOrder = bitOrder;
this->dataMode = dataMode;
this->dataSize = dataSize;
}
uint32_t clock;
uint32_t dataSize;
uint32_t clockDivider;
BitOrder bitOrder;
uint8_t dataMode;
uint8_t _SSPin;
volatile spi_mode_t state;
spi_dev *spi_d;
dma_channel spiRxDmaChannel, spiTxDmaChannel;
dma_dev* spiDmaDev;
void (*receiveCallback)(void) = NULL;
void (*transmitCallback)(void) = NULL;
friend class SPIClass;
};
/*
Should move this to within the class once tested out, just for tidyness
*/
static uint8_t ff = 0XFF;
static void (*_spi1_this);
static void (*_spi2_this);
#if BOARD_NR_SPI >= 3
static void (*_spi3_this);
#endif
/**
* @brief Wirish SPI interface.
*
* This implementation uses software slave management, so the caller
* is responsible for controlling the slave select line.
*/
class SPIClass {
public:
/**
* @param spiPortNumber Number of the SPI port to manage.
*/
SPIClass(uint32 spiPortNumber);
/*
* Set up/tear down
*/
/**
* @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0).
*/
void begin(void);
/**
* @brief Turn on a SPI port and set its GPIO pin modes for use as a slave.
*
* SPI port is enabled in full duplex mode, with software slave management.
*
* @param bitOrder Either LSBFIRST (little-endian) or MSBFIRST(big-endian)
* @param mode SPI mode to use
*/
void beginSlave(uint32 bitOrder, uint32 mode);
/**
* @brief Equivalent to beginSlave(MSBFIRST, 0).
*/
void beginSlave(void);
/**
* @brief Disables the SPI port, but leaves its GPIO pin modes unchanged.
*/
void end(void);
void beginTransaction(SPISettings settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); }
void beginTransaction(uint8_t pin, SPISettings settings);
void endTransaction(void);
void beginTransactionSlave(SPISettings settings);
void setClockDivider(uint32_t clockDivider);
void setBitOrder(BitOrder bitOrder);
void setDataMode(uint8_t dataMode);
// SPI Configuration methods
void attachInterrupt(void);
void detachInterrupt(void);
/* Victor Perez. Added to change datasize from 8 to 16 bit modes on the fly.
* Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word.
* Requires an added function spi_data_size on STM32F1 / cores / maple / libmaple / spi.c
*/
void setDataSize(uint32 ds);
/* Victor Perez 2017. Added to set and clear callback functions for callback
* on DMA transfer completion.
* onReceive used to set the callback in case of dmaTransfer (tx/rx), once rx is completed
* onTransmit used to set the callback in case of dmaSend (tx only). That function
* will NOT be called in case of TX/RX
*/
void onReceive(void(*)(void));
void onTransmit(void(*)(void));
/*
* I/O
*/
/**
* @brief Return the next unread byte/word.
*
* If there is no unread byte/word waiting, this function will block
* until one is received.
*/
uint16 read(void);
/**
* @brief Read length bytes, storing them into buffer.
* @param buffer Buffer to store received bytes into.
* @param length Number of bytes to store in buffer. This
* function will block until the desired number of
* bytes have been read.
*/
void read(uint8 *buffer, uint32 length);
/**
* @brief Transmit one byte/word.
* @param data to transmit.
*/
void write(uint16 data);
void write16(uint16 data); // write 2 bytes in 8 bit mode (DFF=0)
/**
* @brief Transmit one byte/word a specified number of times.
* @param data to transmit.
*/
void write(uint16 data, uint32 n);
/**
* @brief Transmit multiple bytes/words.
* @param buffer Bytes/words to transmit.
* @param length Number of bytes/words in buffer to transmit.
*/
void write(const void * buffer, uint32 length);
/**
* @brief Transmit a byte, then return the next unread byte.
*
* This function transmits before receiving.
*
* @param data Byte to transmit.
* @return Next unread byte.
*/
uint8 transfer(uint8 data) const;
uint16_t transfer16(uint16_t data) const;
/**
* @brief Sets up a DMA Transfer for "length" bytes.
* The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting.
*
* This function transmits and receives to buffers.
*
* @param transmitBuf buffer Bytes to transmit. If passed as 0, it sends FF repeatedly for "length" bytes
* @param receiveBuf buffer Bytes to save received data.
* @param length Number of bytes in buffer to transmit.
*/
uint8 dmaTransfer(const void * transmitBuf, void * receiveBuf, uint16 length);
void dmaTransferSet(const void *transmitBuf, void *receiveBuf);
uint8 dmaTransferRepeat(uint16 length);
/**
* @brief Sets up a DMA Transmit for SPI 8 or 16 bit transfer mode.
* The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting.
*
* This function only transmits and does not care about the RX fifo.
*
* @param data buffer half words to transmit,
* @param length Number of bytes in buffer to transmit.
* @param minc Set to use Memory Increment mode, clear to use Circular mode.
*/
uint8 dmaSend(const void * transmitBuf, uint16 length, bool minc = 1);
void dmaSendSet(const void * transmitBuf, bool minc);
uint8 dmaSendRepeat(uint16 length);
uint8 dmaSendAsync(const void * transmitBuf, uint16 length, bool minc = 1);
/*
* Pin accessors
*/
/**
* @brief Return the number of the MISO (master in, slave out) pin
*/
uint8 misoPin(void);
/**
* @brief Return the number of the MOSI (master out, slave in) pin
*/
uint8 mosiPin(void);
/**
* @brief Return the number of the SCK (serial clock) pin
*/
uint8 sckPin(void);
/**
* @brief Return the number of the NSS (slave select) pin
*/
uint8 nssPin(void);
/* Escape hatch */
/**
* @brief Get a pointer to the underlying libmaple spi_dev for
* this HardwareSPI instance.
*/
spi_dev* c_dev(void) { return _currentSetting->spi_d; }
spi_dev *dev(){ return _currentSetting->spi_d;}
/**
* @brief Sets the number of the SPI peripheral to be used by
* this HardwareSPI instance.
*
* @param spi_num Number of the SPI port. 1-2 in low density devices
* or 1-3 in high density devices.
*/
void setModule(int spi_num)
{
_currentSetting=&_settings[spi_num-1];// SPI channels are called 1 2 and 3 but the array is zero indexed
}
/* -- The following methods are deprecated --------------------------- */
/**
* @brief Deprecated.
*
* Use HardwareSPI::transfer() instead.
*
* @see HardwareSPI::transfer()
*/
uint8 send(uint8 data);
/**
* @brief Deprecated.
*
* Use HardwareSPI::write() in combination with
* HardwareSPI::read() (or HardwareSPI::transfer()) instead.
*
* @see HardwareSPI::write()
* @see HardwareSPI::read()
* @see HardwareSPI::transfer()
*/
uint8 send(uint8 *data, uint32 length);
/**
* @brief Deprecated.
*
* Use HardwareSPI::read() instead.
*
* @see HardwareSPI::read()
*/
uint8 recv(void);
private:
SPISettings _settings[BOARD_NR_SPI];
SPISettings *_currentSetting;
void updateSettings(void);
/*
* Functions added for DMA transfers with Callback.
* Experimental.
*/
void EventCallback(void);
static void _spi1EventCallback(void);
static void _spi2EventCallback(void);
#if BOARD_NR_SPI >= 3
static void _spi3EventCallback(void);
#endif
/*
spi_dev *spi_d;
uint8_t _SSPin;
uint32_t clockDivider;
uint8_t dataMode;
BitOrder bitOrder;
*/
};
extern SPIClass SPI;//(1);// dummy params
#endif

View File

@ -0,0 +1,139 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* &file wirish/boards/maple_mini/board.cpp
* &author Marti Bolivar <mbolivar&leaflabs.com>
* &brief Maple Mini board file.
*/
#include <board/board.h>
#include <libmaple/gpio.h>
#include <libmaple/timer.h>
/* Roger Clark. Added next to includes for changes to Serial */
#include <libmaple/usart.h>
#include <HardwareSerial.h>
#include <wirish_debug.h>
#include <wirish_types.h>
/* Since we want the Serial Wire/JTAG pins as GPIOs, disable both SW
* and JTAG debug support, unless configured otherwise. */
void boardInit(void) {
#ifndef CONFIG_MAPLE_MINI_NO_DISABLE_DEBUG
disableDebugPorts();
#endif
}
// Note. See the enum of pin names in board.h
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = {
{&gpioa, &timer2, &adc1, 0, 1, 0}, /* PA0 */
{&gpioa, &timer2, &adc1, 1, 2, 1}, /* PA1 */
{&gpioa, &timer2, &adc1, 2, 3, 2}, /* PA2 */
{&gpioa, &timer2, &adc1, 3, 4, 3}, /* PA3 */
{&gpioa, NULL, &adc1, 4, 0, 4}, /* PA4 */
{&gpioa, NULL, &adc1, 5, 0, 5}, /* PA5 */
{&gpioa, &timer3, &adc1, 6, 1, 6}, /* PA6 */
{&gpioa, &timer3, &adc1, 7, 2, 7}, /* PA7 */
{&gpioa, &timer1, NULL, 8, 1, ADCx}, /* PA8 */
{&gpioa, &timer1, NULL, 9, 2, ADCx}, /* PA9 */
{&gpioa, &timer1, NULL, 10, 3, ADCx}, /* PA10 */
{&gpioa, &timer1, NULL, 11, 4, ADCx}, /* PA11 */
{&gpioa, NULL, NULL, 12, 0, ADCx}, /* PA12 */
{&gpioa, NULL, NULL, 13, 0, ADCx}, /* PA13 */
{&gpioa, NULL, NULL, 14, 0, ADCx}, /* PA14 */
{&gpioa, NULL, NULL, 15, 0, ADCx}, /* PA15 */
{&gpiob, &timer3, &adc1, 0, 3, 8}, /* PB0 */
{&gpiob, &timer3, &adc1, 1, 4, 9}, /* PB1 */
{&gpiob, NULL, NULL, 2, 0, ADCx}, /* PB2 */
{&gpiob, NULL, NULL, 3, 0, ADCx}, /* PB3 */
{&gpiob, NULL, NULL, 4, 0, ADCx}, /* PB4 */
{&gpiob, NULL, NULL, 5, 0, ADCx}, /* PB5 */
{&gpiob, &timer4, NULL, 6, 1, ADCx}, /* PB6 */
{&gpiob, &timer4, NULL, 7, 2, ADCx}, /* PB7 */
{&gpiob, &timer4, NULL, 8, 3, ADCx}, /* PB8 */
{&gpiob, &timer4, NULL, 9, 4, ADCx}, /* PB9 */
{&gpiob, NULL, NULL, 10, 0, ADCx}, /* PB10 */
{&gpiob, NULL, NULL, 11, 0, ADCx}, /* PB11 */
{&gpiob, NULL, NULL, 12, 0, ADCx}, /* PB12 */
{&gpiob, NULL, NULL, 13, 0, ADCx}, /* PB13 */
{&gpiob, NULL, NULL, 14, 0, ADCx}, /* PB14 */
{&gpiob, NULL, NULL, 15, 0, ADCx}, /* PB15 */
{&gpioc, NULL, NULL, 13, 0, ADCx}, /* PC13 */
{&gpioc, NULL, NULL, 14, 0, ADCx}, /* PC14 */
{&gpioc, NULL, NULL, 15, 0, ADCx}, /* PC15 */
};
extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = {
PB0, PA7, PA6, PA3, PA2, PA1, PA0, PB7, PB6, PA10, PA9, PA8
};
extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = {
PB0, PA7, PA6 , PA5 , PA4 , PA3 , PA2 , PA1 , PA0
};
// Note. These defines are not really used by generic boards. They are for Maple Serial USB
#define USB_DP PA12
#define USB_DM PA11
// NOte. These definitions are not really used for generic boards, they only relate to boards modified to behave like Maple boards
extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = {
USB_DP, USB_DM
};
/*
* Roger Clark
*
* 2015/05/28
*
* Moved definitions for Hardware Serial devices from HardwareSerial.cpp so that each board can define which Arduino "Serial" instance
* Maps to which hardware serial port on the microprocessor
*/
#ifdef SERIAL_USB
DEFINE_HWSERIAL(Serial1, 1);
DEFINE_HWSERIAL(Serial2, 2);
DEFINE_HWSERIAL(Serial3, 3);
#else
DEFINE_HWSERIAL(Serial, 1);
DEFINE_HWSERIAL(Serial1, 2);
DEFINE_HWSERIAL(Serial2, 3);
#endif

View File

@ -0,0 +1,85 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file wirish/boards/maple_mini/include/board/board.h
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Maple Mini board header.
*
* See wirish/boards/maple/include/board/board.h for more information
* on these definitions.
*/
#ifndef _BOARD_GENERIC_STM32F103C_H_
#define _BOARD_GENERIC_STM32F103C_H_
#define CYCLES_PER_MICROSECOND (F_CPU / 1000000U)
#define SYSTICK_RELOAD_VAL (F_CPU/1000) - 1 /* takes a cycle to reload */
#define BOARD_NR_USARTS 3
#define BOARD_USART1_TX_PIN PA9
#define BOARD_USART1_RX_PIN PA10
#define BOARD_USART2_TX_PIN PA2
#define BOARD_USART2_RX_PIN PA3
#define BOARD_USART3_TX_PIN PB10
#define BOARD_USART3_RX_PIN PB11
#define BOARD_NR_SPI 2
#define BOARD_SPI1_NSS_PIN PA4
#define BOARD_SPI1_MOSI_PIN PA7
#define BOARD_SPI1_MISO_PIN PA6
#define BOARD_SPI1_SCK_PIN PA5
#define BOARD_SPI2_NSS_PIN PB12
#define BOARD_SPI2_MOSI_PIN PB15
#define BOARD_SPI2_MISO_PIN PB14
#define BOARD_SPI2_SCK_PIN PB13
#define BOARD_NR_GPIO_PINS 35
#define BOARD_NR_PWM_PINS 12
#define BOARD_NR_ADC_PINS 9
#define BOARD_NR_USED_PINS 4
#define BOARD_JTMS_SWDIO_PIN 22
#define BOARD_JTCK_SWCLK_PIN 21
#define BOARD_JTDI_PIN 20
#define BOARD_JTDO_PIN 19
#define BOARD_NJTRST_PIN 18
#define BOARD_USB_DISC_DEV NULL
#define BOARD_USB_DISC_BIT NULL
#define LED_BUILTIN PC13
// Note this needs to match with the PIN_MAP array in board.cpp
enum {
PA0, PA1, PA2, PA3, PA4, PA5, PA6, PA7, PA8, PA9, PA10, PA11, PA12, PA13,PA14,PA15,
PB0, PB1, PB2, PB3, PB4, PB5, PB6, PB7, PB8, PB9, PB10, PB11, PB12, PB13,PB14,PB15,
PC13, PC14,PC15
};
#endif

View File

@ -0,0 +1,30 @@
/*
* libmaple linker script for "Flash" builds.
*
* A Flash build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but offsets the sections by
* enough space to store the Maple bootloader, which lives in low
* Flash and uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08002000, LENGTH = 120K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,220 @@
/*
* Linker script for libmaple.
*
* Original author "lanchon" from ST forums, with modifications by LeafLabs.
*/
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
/*
* Configure other libraries we want in the link.
*
* libgcc, libc, and libm are common across supported toolchains.
* However, some toolchains require additional archives which aren't
* present everywhere (e.g. ARM's gcc-arm-embedded releases).
*
* To hack around this, we let the build system specify additional
* archives by putting the right extra_libs.inc (in a directory under
* toolchains/) in our search path.
*/
GROUP(libgcc.a libc.a libm.a)
INCLUDE extra_libs.inc
/*
* These force the linker to search for vector table symbols.
*
* These symbols vary by STM32 family (and also within families).
* It's up to the build system to configure the link's search path
* properly for the target MCU.
*/
INCLUDE vector_symbols.inc
/* STM32 vector table. */
EXTERN(__stm32_vector_table)
/* C runtime initialization function. */
EXTERN(start_c)
/* main entry point */
EXTERN(main)
/* Initial stack pointer value. */
EXTERN(__msp_init)
PROVIDE(__msp_init = ORIGIN(ram) + LENGTH(ram));
/* Reset vector and chip reset entry point */
EXTERN(__start__)
ENTRY(__start__)
PROVIDE(__exc_reset = __start__);
/* Heap boundaries, for libmaple */
EXTERN(_lm_heap_start);
EXTERN(_lm_heap_end);
SECTIONS
{
.text :
{
__text_start__ = .;
/*
* STM32 vector table. Leave this here. Yes, really.
*/
*(.stm32.interrupt_vector)
/*
* Program code and vague linking
*/
*(.text .text.* .gnu.linkonce.t.*)
*(.plt)
*(.gnu.warning)
*(.glue_7t) *(.glue_7) *(.vfp11_veneer)
*(.ARM.extab* .gnu.linkonce.armextab.*)
*(.gcc_except_table)
*(.eh_frame_hdr)
*(.eh_frame)
. = ALIGN(4);
KEEP(*(.init))
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
. = ALIGN(0x4);
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*crtend.o(.ctors))
. = ALIGN(4);
KEEP(*(.fini))
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*crtend.o(.dtors))
} > REGION_TEXT
/*
* End of text
*/
.text.align :
{
. = ALIGN(8);
__text_end__ = .;
} > REGION_TEXT
/*
* .ARM.exidx exception unwinding; mandated by ARM's C++ ABI
*/
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > REGION_RODATA
__exidx_end = .;
/*
* .data
*/
.data :
{
__data_start__ = .;
LONG(0)
. = ALIGN(8);
*(.got.plt) *(.got)
*(.data .data.* .gnu.linkonce.d.*)
. = ALIGN(8);
__data_end__ = .;
} > REGION_DATA AT> REGION_RODATA
/*
* Read-only data
*/
.rodata :
{
*(.rodata .rodata.* .gnu.linkonce.r.*)
/* .USER_FLASH: We allow users to allocate into Flash here */
*(.USER_FLASH)
/* ROM image configuration; for C startup */
. = ALIGN(4);
_lm_rom_img_cfgp = .;
LONG(LOADADDR(.data));
/*
* Heap: Linker scripts may choose a custom heap by overriding
* _lm_heap_start and _lm_heap_end. Otherwise, the heap is in
* internal SRAM, beginning after .bss, and growing towards
* the stack.
*
* I'm shoving these here naively; there's probably a cleaner way
* to go about this. [mbolivar]
*/
_lm_heap_start = DEFINED(_lm_heap_start) ? _lm_heap_start : _end;
_lm_heap_end = DEFINED(_lm_heap_end) ? _lm_heap_end : __msp_init;
} > REGION_RODATA
/*
* .bss
*/
.bss :
{
. = ALIGN(8);
__bss_start__ = .;
*(.bss .bss.* .gnu.linkonce.b.*)
*(COMMON)
. = ALIGN (8);
__bss_end__ = .;
_end = __bss_end__;
} > REGION_BSS
/*
* Debugging sections
*/
.stab 0 (NOLOAD) : { *(.stab) }
.stabstr 0 (NOLOAD) : { *(.stabstr) }
/* DWARF debug sections.
* Symbols in the DWARF debugging sections are relative to the beginning
* of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
.note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
.ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
/DISCARD/ : { *(.note.GNU-stack) }
}

View File

@ -0,0 +1,7 @@
/*
* Extra archives needed by ARM's GCC ARM Embedded arm-none-eabi-
* releases (https://launchpad.net/gcc-arm-embedded/).
*/
/* This is for the provided newlib. */
GROUP(libnosys.a)

View File

@ -0,0 +1,26 @@
/*
* libmaple linker script for "Flash" builds.
*
* A Flash build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but offsets the sections by
* enough space to store the Maple bootloader, which lives in low
* Flash and uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
INCLUDE mem-flash.inc
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,33 @@
/*
* libmaple linker script for "Flash" builds.
*
* A Flash build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but offsets the sections by
* enough space to store the Maple bootloader, which lives in low
* Flash and uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
/*INCLUDE mem-flash.inc*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 44K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,31 @@
/*
* libmaple linker script for "JTAG" builds.
*
* A "JTAG" build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but links starting at the
* Flash and SRAM starting addresses (0x08000000 and 0x20000000
* respectively). This will wipe out a Maple bootloader if there's one
* on the board, so only use this if you know what you're doing.
*
* Of course, a "JTAG" build is perfectly usable for upload over SWD,
* the system memory bootloader, etc. The name is just a historical
* artifact.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
INCLUDE mem-jtag.inc
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,36 @@
/*
* libmaple linker script for "JTAG" builds.
*
* A "JTAG" build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but links starting at the
* Flash and SRAM starting addresses (0x08000000 and 0x20000000
* respectively). This will wipe out a Maple bootloader if there's one
* on the board, so only use this if you know what you're doing.
*
* Of course, a "JTAG" build is perfectly usable for upload over SWD,
* the system memory bootloader, etc. The name is just a historical
* artifact.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,5 @@
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08005000, LENGTH = 108K
}

View File

@ -0,0 +1,5 @@
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
}

View File

@ -0,0 +1,5 @@
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08005000, LENGTH = 0K
}

View File

@ -0,0 +1,25 @@
/*
* libmaple linker script for RAM builds.
*
* A Flash build puts .text, .rodata, and .data/.bss/heap (of course)
* in SRAM, but offsets the sections by enough space to store the
* Maple bootloader, which uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
INCLUDE mem-ram.inc
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", ram);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", ram);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,31 @@
/*
* libmaple linker script for RAM builds.
*
* A Flash build puts .text, .rodata, and .data/.bss/heap (of course)
* in SRAM, but offsets the sections by enough space to store the
* Maple bootloader, which uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
/*INCLUDE mem-ram.inc*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08005000, LENGTH = 0
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", ram);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", ram);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,78 @@
EXTERN(__msp_init)
EXTERN(__exc_reset)
EXTERN(__exc_nmi)
EXTERN(__exc_hardfault)
EXTERN(__exc_memmanage)
EXTERN(__exc_busfault)
EXTERN(__exc_usagefault)
EXTERN(__stm32reservedexception7)
EXTERN(__stm32reservedexception8)
EXTERN(__stm32reservedexception9)
EXTERN(__stm32reservedexception10)
EXTERN(__exc_svc)
EXTERN(__exc_debug_monitor)
EXTERN(__stm32reservedexception13)
EXTERN(__exc_pendsv)
EXTERN(__exc_systick)
EXTERN(__irq_wwdg)
EXTERN(__irq_pvd)
EXTERN(__irq_tamper)
EXTERN(__irq_rtc)
EXTERN(__irq_flash)
EXTERN(__irq_rcc)
EXTERN(__irq_exti0)
EXTERN(__irq_exti1)
EXTERN(__irq_exti2)
EXTERN(__irq_exti3)
EXTERN(__irq_exti4)
EXTERN(__irq_dma1_channel1)
EXTERN(__irq_dma1_channel2)
EXTERN(__irq_dma1_channel3)
EXTERN(__irq_dma1_channel4)
EXTERN(__irq_dma1_channel5)
EXTERN(__irq_dma1_channel6)
EXTERN(__irq_dma1_channel7)
EXTERN(__irq_adc)
EXTERN(__irq_usb_hp_can_tx)
EXTERN(__irq_usb_lp_can_rx0)
EXTERN(__irq_can_rx1)
EXTERN(__irq_can_sce)
EXTERN(__irq_exti9_5)
EXTERN(__irq_tim1_brk)
EXTERN(__irq_tim1_up)
EXTERN(__irq_tim1_trg_com)
EXTERN(__irq_tim1_cc)
EXTERN(__irq_tim2)
EXTERN(__irq_tim3)
EXTERN(__irq_tim4)
EXTERN(__irq_i2c1_ev)
EXTERN(__irq_i2c1_er)
EXTERN(__irq_i2c2_ev)
EXTERN(__irq_i2c2_er)
EXTERN(__irq_spi1)
EXTERN(__irq_spi2)
EXTERN(__irq_usart1)
EXTERN(__irq_usart2)
EXTERN(__irq_usart3)
EXTERN(__irq_exti15_10)
EXTERN(__irq_rtcalarm)
EXTERN(__irq_usbwakeup)
EXTERN(__irq_tim8_brk)
EXTERN(__irq_tim8_up)
EXTERN(__irq_tim8_trg_com)
EXTERN(__irq_tim8_cc)
EXTERN(__irq_adc3)
EXTERN(__irq_fsmc)
EXTERN(__irq_sdio)
EXTERN(__irq_tim5)
EXTERN(__irq_spi3)
EXTERN(__irq_uart4)
EXTERN(__irq_uart5)
EXTERN(__irq_tim6)
EXTERN(__irq_tim7)
EXTERN(__irq_dma2_channel1)
EXTERN(__irq_dma2_channel2)
EXTERN(__irq_dma2_channel3)
EXTERN(__irq_dma2_channel4_5)

View File

@ -0,0 +1,6 @@
// API compatibility
#include "variant.h"

View File

@ -0,0 +1,22 @@
#ifndef _VARIANT_ARDUINO_STM32_
#define _VARIANT_ARDUINO_STM32_
#define digitalPinToPort(P) ( PIN_MAP[P].gpio_device )
#define digitalPinToBitMask(P) ( BIT(PIN_MAP[P].gpio_bit) )
#define portOutputRegister(port) ( &(port->regs->ODR) )
#define portInputRegister(port) ( &(port->regs->IDR) )
#define portSetRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BSRR) )
#define portClearRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BRR) )
#define portConfigRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->CRL) )
static const uint8_t SS = BOARD_SPI1_NSS_PIN;
static const uint8_t SS1 = BOARD_SPI2_NSS_PIN;
static const uint8_t MOSI = BOARD_SPI1_MOSI_PIN;
static const uint8_t MISO = BOARD_SPI1_MISO_PIN;
static const uint8_t SCK = BOARD_SPI1_SCK_PIN;
#define LED_BUILTIN PC13
#endif /* _VARIANT_ARDUINO_STM32_ */

View File

@ -0,0 +1,229 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
* Copyright (c) 2011, 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file wirish/boards.cpp
* @brief init() and board routines.
*
* This file is mostly interesting for the init() function, which
* configures Flash, the core clocks, and a variety of other available
* peripherals on the board so the rest of Wirish doesn't have to turn
* things on before using them.
*
* Prior to returning, init() calls boardInit(), which allows boards
* to perform any initialization they need to. This file includes a
* weak no-op definition of boardInit(), so boards that don't need any
* special initialization don't have to define their own.
*
* How init() works is chip-specific. See the boards_setup.cpp files
* under e.g. wirish/stm32f1/, wirish/stmf32f2 for the details, but be
* advised: their contents are unstable, and can/will change without
* notice.
*/
#include <boards.h>
#include <libmaple/libmaple_types.h>
#include <libmaple/flash.h>
#include <libmaple/nvic.h>
#include <libmaple/systick.h>
#include "boards_private.h"
static void setup_flash(void);
static void setup_clocks(void);
static void setup_nvic(void);
static void setup_adcs(void);
static void setup_timers(void);
/*
* Exported functions
*/
void init(void) {
setup_flash();
setup_clocks();
setup_nvic();
systick_init(SYSTICK_RELOAD_VAL);
wirish::priv::board_setup_gpio();
setup_adcs();
setup_timers();
wirish::priv::board_setup_usb();
wirish::priv::series_init();
boardInit();
}
/* Provide a default no-op boardInit(). */
__weak void boardInit(void) {
}
/* You could farm this out to the files in boards/ if e.g. it takes
* too long to test on boards with lots of pins. */
bool boardUsesPin(uint8 pin) {
for (int i = 0; i < BOARD_NR_USED_PINS; i++) {
if (pin == boardUsedPins[i]) {
return true;
}
}
return false;
}
/*
* Auxiliary routines
*/
static void setup_flash(void) {
// Turn on as many Flash "go faster" features as
// possible. flash_enable_features() just ignores any flags it
// can't support.
flash_enable_features(FLASH_PREFETCH | FLASH_ICACHE | FLASH_DCACHE);
// Configure the wait states, assuming we're operating at "close
// enough" to 3.3V.
flash_set_latency(FLASH_SAFE_WAIT_STATES);
}
static void setup_clocks(void) {
// Turn on HSI. We'll switch to and run off of this while we're
// setting up the main PLL.
rcc_turn_on_clk(RCC_CLK_HSI);
// Turn off and reset the clock subsystems we'll be using, as well
// as the clock security subsystem (CSS). Note that resetting CFGR
// to its default value of 0 implies a switch to HSI for SYSCLK.
RCC_BASE->CFGR = 0x00000000;
rcc_disable_css();
rcc_turn_off_clk(RCC_CLK_PLL);
rcc_turn_off_clk(RCC_CLK_HSE);
wirish::priv::board_reset_pll();
// Clear clock readiness interrupt flags and turn off clock
// readiness interrupts.
RCC_BASE->CIR = 0x00000000;
// Enable HSE, and wait until it's ready.
rcc_turn_on_clk(RCC_CLK_HSE);
while (!rcc_is_clk_ready(RCC_CLK_HSE))
;
// Configure AHBx, APBx, etc. prescalers and the main PLL.
wirish::priv::board_setup_clock_prescalers();
rcc_configure_pll(&wirish::priv::w_board_pll_cfg);
// Enable the PLL, and wait until it's ready.
rcc_turn_on_clk(RCC_CLK_PLL);
while(!rcc_is_clk_ready(RCC_CLK_PLL))
;
// Finally, switch to the now-ready PLL as the main clock source.
rcc_switch_sysclk(RCC_CLKSRC_PLL);
}
/*
* These addresses are where usercode starts when a bootloader is
* present. If no bootloader is present, the user NVIC usually starts
* at the Flash base address, 0x08000000.
*/
#if defined(BOOTLOADER_maple)
#define USER_ADDR_ROM 0x08005000
#else
#if defined(BOOTLOADER_robotis)
#define USER_ADDR_ROM 0x08003000
#else
#define USER_ADDR_ROM 0x08000000
#endif
#endif
#define USER_ADDR_RAM 0x20000C00
extern char __text_start__;
static void setup_nvic(void) {
nvic_init((uint32)VECT_TAB_ADDR, 0);
/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect paramater
#ifdef VECT_TAB_FLASH
nvic_init(USER_ADDR_ROM, 0);
#elif defined VECT_TAB_RAM
nvic_init(USER_ADDR_RAM, 0);
#elif defined VECT_TAB_BASE
nvic_init((uint32)0x08000000, 0);
#elif defined VECT_TAB_ADDR
// A numerically supplied value
nvic_init((uint32)VECT_TAB_ADDR, 0);
#else
// Use the __text_start__ value from the linker script; this
// should be the start of the vector table.
nvic_init((uint32)&__text_start__, 0);
#endif
*/
}
static void adc_default_config( adc_dev *dev) {
adc_enable_single_swstart(dev);
adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
}
static void setup_adcs(void) {
adc_set_prescaler(wirish::priv::w_adc_pre);
adc_foreach(adc_default_config);
}
static void timer_default_config(timer_dev *dev) {
timer_adv_reg_map *regs = (dev->regs).adv;
const uint16 full_overflow = 0xFFFF;
const uint16 half_duty = 0x8FFF;
timer_init(dev);
timer_pause(dev);
regs->CR1 = TIMER_CR1_ARPE;
regs->PSC = 1;
regs->SR = 0;
regs->DIER = 0;
regs->EGR = TIMER_EGR_UG;
switch (dev->type) {
case TIMER_ADVANCED:
regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF;
// fall-through
case TIMER_GENERAL:
timer_set_reload(dev, full_overflow);
for (uint8 channel = 1; channel <= 4; channel++) {
if (timer_has_cc_channel(dev, channel)) {
timer_set_compare(dev, channel, half_duty);
timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1,
TIMER_OC_PE);
}
}
// fall-through
case TIMER_BASIC:
break;
}
timer_generate_update(dev);
timer_resume(dev);
}
static void setup_timers(void) {
timer_foreach(timer_default_config);
}

View File

@ -0,0 +1,110 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file wirish/stm32f1/boards_setup.cpp
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief STM32F1 chip setup.
*
* This file controls how init() behaves on the STM32F1. Be very
* careful when changing anything here. Many of these values depend
* upon each other.
*/
#include "boards_private.h"
#include <libmaple/gpio.h>
#include <libmaple/timer.h>
#include <boards.h>
#include <usb_serial.h>
// Allow boards to provide a PLL multiplier. This is useful for
// e.g. STM32F100 value line MCUs, which use slower multipliers.
// (We're leaving the default to RCC_PLLMUL_9 for now, since that
// works for F103 performance line MCUs, which is all that LeafLabs
// currently officially supports).
#ifndef BOARD_RCC_PLLMUL
#if F_CPU==128000000
#define BOARD_RCC_PLLMUL RCC_PLLMUL_16
#elif F_CPU==72000000
#define BOARD_RCC_PLLMUL RCC_PLLMUL_9
#elif F_CPU==48000000
#define BOARD_RCC_PLLMUL RCC_PLLMUL_6
#endif
#endif
namespace wirish {
namespace priv {
static stm32f1_rcc_pll_data pll_data = {BOARD_RCC_PLLMUL};
__weak rcc_pll_cfg w_board_pll_cfg = {RCC_PLLSRC_HSE, &pll_data};
__weak adc_prescaler w_adc_pre = ADC_PRE_PCLK2_DIV_6;
__weak adc_smp_rate w_adc_smp = ADC_SMPR_55_5;
__weak void board_reset_pll(void) {
// TODO
}
__weak void board_setup_clock_prescalers(void) {
rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1);
rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2);
rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1);
rcc_clk_disable(RCC_USB);
#if F_CPU == 72000000
rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1_5);
#elif F_CPU == 48000000
rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1);
#endif
}
__weak void board_setup_gpio(void) {
gpio_init_all();
}
__weak void board_setup_usb(void) {
#ifdef SERIAL_USB
#ifdef GENERIC_BOOTLOADER
//Reset the USB interface on generic boards - developed by Victor PV
gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_OUTPUT_PP);
gpio_write_bit(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit,0);
for(volatile unsigned int i=0;i<512;i++);// Only small delay seems to be needed, and USB pins will get configured in Serial.begin
gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_INPUT_FLOATING);
#endif
Serial.begin();// Roger Clark. Changed SerialUSB to Serial for Arduino sketch compatibility
#endif
}
__weak void series_init(void) {
// Initialize AFIO here, too, so peripheral remaps and external
// interrupts work out of the box.
afio_init();
}
}
}

View File

@ -0,0 +1,57 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/*
* This file is a modified version of a file obtained from
* CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the
* following text appeared:
*
* The authors hereby grant permission to use, copy, modify, distribute,
* and license this software and its documentation for any purpose, provided
* that existing copyright notices are retained in all copies and that this
* notice is included verbatim in any distributions. No written agreement,
* license, or royalty fee is required for any of the authorized uses.
* Modifications to this software may be copyrighted by their authors
* and need not follow the licensing terms described here, provided that
* the new terms are clearly indicated on the first page of each file where
* they apply.
*/
.text
.code 16
.thumb_func
.globl __start__
.type __start__, %function
__start__:
.fnstart
ldr r1,=__msp_init
mov sp,r1
ldr r1,=start_c
bx r1
.pool
.cantunwind
.fnend

View File

@ -0,0 +1,95 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/*
* This file is a modified version of a file obtained from
* CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the
* following text appeared:
*
* Copyright (c) 2006, 2007 CodeSourcery Inc
*
* The authors hereby grant permission to use, copy, modify, distribute,
* and license this software and its documentation for any purpose, provided
* that existing copyright notices are retained in all copies and that this
* notice is included verbatim in any distributions. No written agreement,
* license, or royalty fee is required for any of the authorized uses.
* Modifications to this software may be copyrighted by their authors
* and need not follow the licensing terms described here, provided that
* the new terms are clearly indicated on the first page of each file where
* they apply.
*/
#include <stddef.h>
extern void __libc_init_array(void);
extern int main(int, char**, char**);
extern void exit(int) __attribute__((noreturn, weak));
/* The linker must ensure that these are at least 4-byte aligned. */
extern char __data_start__, __data_end__;
extern char __bss_start__, __bss_end__;
struct rom_img_cfg {
int *img_start;
};
extern char _lm_rom_img_cfgp;
void __attribute__((noreturn)) start_c(void) {
struct rom_img_cfg *img_cfg = (struct rom_img_cfg*)&_lm_rom_img_cfgp;
int *src = img_cfg->img_start;
int *dst = (int*)&__data_start__;
int exit_code;
/* Initialize .data, if necessary. */
if (src != dst) {
int *end = (int*)&__data_end__;
while (dst < end) {
*dst++ = *src++;
}
}
/* Zero .bss. */
dst = (int*)&__bss_start__;
while (dst < (int*)&__bss_end__) {
*dst++ = 0;
}
/* Run initializers. */
__libc_init_array();
/* Jump to main. */
exit_code = main(0, 0, 0);
if (exit) {
exit(exit_code);
}
/* If exit is NULL, make sure we don't return. */
for (;;)
continue;
}

View File

@ -0,0 +1,176 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
* Copyright (c) 2011, 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file wirish/syscalls.c
* @brief newlib stubs
*
* Low level system routines used by newlib for basic I/O and memory
* allocation. You can override most of these.
*/
#include <libmaple/libmaple.h>
#include <sys/stat.h>
#include <errno.h>
#include <stddef.h>
/* If CONFIG_HEAP_START (or CONFIG_HEAP_END) isn't defined, then
* assume _lm_heap_start (resp. _lm_heap_end) is appropriately set by
* the linker */
#ifndef CONFIG_HEAP_START
extern char _lm_heap_start;
#define CONFIG_HEAP_START ((void *)&_lm_heap_start)
#endif
#ifndef CONFIG_HEAP_END
extern char _lm_heap_end;
#define CONFIG_HEAP_END ((void *)&_lm_heap_end)
#endif
/*
* _sbrk -- Increment the program break.
*
* Get incr bytes more RAM (for use by the heap). malloc() and
* friends call this function behind the scenes.
*/
void *_sbrk(int incr) {
static void * pbreak = NULL; /* current program break */
void * ret;
if (pbreak == NULL) {
pbreak = CONFIG_HEAP_START;
}
if ((CONFIG_HEAP_END - pbreak < incr) ||
(pbreak - CONFIG_HEAP_START < -incr)) {
errno = ENOMEM;
return (void *)-1;
}
ret = pbreak;
pbreak += incr;
return ret;
}
__weak int _open(const char *path, int flags, ...) {
return 1;
}
__weak int _close(int fd) {
return 0;
}
__weak int _fstat(int fd, struct stat *st) {
st->st_mode = S_IFCHR;
return 0;
}
__weak int _isatty(int fd) {
return 1;
}
__weak int isatty(int fd) {
return 1;
}
__weak int _lseek(int fd, off_t pos, int whence) {
return -1;
}
__weak unsigned char getch(void) {
return 0;
}
__weak int _read(int fd, char *buf, size_t cnt) {
*buf = getch();
return 1;
}
__weak void putch(unsigned char c) {
}
__weak void cgets(char *s, int bufsize) {
char *p;
int c;
int i;
for (i = 0; i < bufsize; i++) {
*(s+i) = 0;
}
// memset(s, 0, bufsize);
p = s;
for (p = s; p < s + bufsize-1;) {
c = getch();
switch (c) {
case '\r' :
case '\n' :
putch('\r');
putch('\n');
*p = '\n';
return;
case '\b' :
if (p > s) {
*p-- = 0;
putch('\b');
putch(' ');
putch('\b');
}
break;
default :
putch(c);
*p++ = c;
break;
}
}
return;
}
__weak int _write(int fd, const char *buf, size_t cnt) {
int i;
for (i = 0; i < cnt; i++)
putch(buf[i]);
return cnt;
}
/* Override fgets() in newlib with a version that does line editing */
__weak char *fgets(char *s, int bufsize, void *f) {
cgets(s, bufsize);
return s;
}
__weak void _exit(int exitcode) {
while (1)
;
}