Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed-dev-f303 FastPWM3
Revision 23:2adf23ee0305, committed 2017-04-05
- Comitter:
- benkatz
- Date:
- Wed Apr 05 20:54:16 2017 +0000
- Parent:
- 22:60276ba87ac6
- Child:
- 24:58c2d7571207
- Commit message:
- Added bayley's flash writer
Changed in this revision
--- a/Calibration/calibration.cpp Fri Mar 31 18:24:46 2017 +0000
+++ b/Calibration/calibration.cpp Wed Apr 05 20:54:16 2017 +0000
@@ -3,43 +3,51 @@
///
#include "calibration.h"
-
+#include "foc.h"
+#include "PreferenceWriter.h"
+#include "user_config.h"
-void order_phases(PositionSensor *ps, GPIOStruct *gpio){
+void order_phases(PositionSensor *ps, GPIOStruct *gpio, ControllerStruct *controller, PreferenceWriter *prefs){
///Checks phase order, to ensure that positive Q current produces
///torque in the positive direction wrt the position sensor.
-
printf("\n\r Checking phase ordering\n\r");
float theta_ref = 0;
float theta_actual = 0;
- float v_d = .2; //Put all volts on the D-Axis
+ float v_d = .2; //Put all volts on the D-Axis
float v_q = 0.0;
float v_u, v_v, v_w = 0;
float dtc_u, dtc_v, dtc_w = .5;
int sample_counter = 0;
///Set voltage angle to zero, wait for rotor position to settle
- abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); //inverse dq0 transform on voltages
- svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); //space vector modulation
+ abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); //inverse dq0 transform on voltages
+ svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); //space vector modulation
for(int i = 0; i<20000; i++){
- TIM1->CCR3 = 0x708*(1.0f-dtc_u); // Set duty cycles
+ TIM1->CCR3 = 0x708*(1.0f-dtc_u); // Set duty cycles
TIM1->CCR2 = 0x708*(1.0f-dtc_v);
TIM1->CCR1 = 0x708*(1.0f-dtc_w);
wait_us(100);
}
//ps->ZeroPosition();
ps->Sample();
- float theta_start = ps->GetMechPosition(); //get initial rotor position
-
+ wait_us(1000);
+ float theta_start = ps->GetMechPosition(); //get initial rotor position
+ controller->i_b = I_SCALE*(float)(controller->adc2_raw - controller->adc2_offset); //Calculate phase currents from ADC readings
+ controller->i_c = I_SCALE*(float)(controller->adc1_raw - controller->adc1_offset);
+ controller->i_a = -controller->i_b - controller->i_c;
+ dq0(controller->theta_elec, controller->i_a, controller->i_b, controller->i_c, &controller->i_d, &controller->i_q); //dq0 transform on currents
+ float current = sqrt(pow(controller->i_d, 2) + pow(controller->i_q, 2));
+ printf("\n\rCurrent\n\r");
+ printf("%f %f %f\n\r\n\r", controller->i_d, controller->i_q, current);
/// Rotate voltage angle
- while(theta_ref < 4*PI){ //rotate for 2 electrical cycles
- abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); //inverse dq0 transform on voltages
- svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); //space vector modulation
+ while(theta_ref < 4*PI){ //rotate for 2 electrical cycles
+ abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); //inverse dq0 transform on voltages
+ svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); //space vector modulation
wait_us(100);
- TIM1->CCR3 = 0x708*(1.0f-dtc_u); //Set duty cycles
+ TIM1->CCR3 = 0x708*(1.0f-dtc_u); //Set duty cycles
TIM1->CCR2 = 0x708*(1.0f-dtc_v);
TIM1->CCR1 = 0x708*(1.0f-dtc_w);
- ps->Sample(); //sample position sensor
+ ps->Sample(); //sample position sensor
theta_actual = ps->GetMechPosition();
if(sample_counter > 200){
sample_counter = 0 ;
@@ -52,41 +60,39 @@
int direction = (theta_end - theta_start)>0;
printf("Theta Start: %f Theta End: %f\n\r", theta_start, theta_end);
printf("Direction: %d\n\r", direction);
- if(direction){printf("Phaseing correct\n\r");}
+ if(direction){printf("Phasing correct\n\r");}
else if(!direction){printf("Phasing incorrect. Swapping phases V and W\n\r");}
gpio->phasing = direction;
-
+ PHASE_ORDER = direction;
}
-
-void calibrate(PositionSensor *ps, GPIOStruct *gpio){
+void calibrate(PositionSensor *ps, GPIOStruct *gpio, ControllerStruct *controller, PreferenceWriter *prefs){
/// Measures the electrical angle offset of the position sensor
/// and (in the future) corrects nonlinearity due to position sensor eccentricity
-
printf("Starting calibration procedure\n\r");
- const int n = 128*NPP; // number of positions to be sampled per mechanical rotation. Multiple of NPP for filtering reasons (see later)
- const int n2 = 10; // increments between saved samples (for smoothing motion)
- float delta = 2*PI*NPP/(n*n2); // change in angle between samples
- float error_f[n] = {0}; // error vector rotating forwards
- float error_b[n] = {0}; // error vector rotating backwards
+ const int n = 128*NPP; // number of positions to be sampled per mechanical rotation. Multiple of NPP for filtering reasons (see later)
+ const int n2 = 10; // increments between saved samples (for smoothing motion)
+ float delta = 2*PI*NPP/(n*n2); // change in angle between samples
+ float error_f[n] = {0}; // error vector rotating forwards
+ float error_b[n] = {0}; // error vector rotating backwards
int raw_f[n] = {0};
int raw_b[n] = {0};
float theta_ref = 0;
float theta_actual = 0;
- float v_d = .2; // Put volts on the D-Axis
+ float v_d = .2; // Put volts on the D-Axis
float v_q = 0.0;
float v_u, v_v, v_w = 0;
float dtc_u, dtc_v, dtc_w = .5;
///Set voltage angle to zero, wait for rotor position to settle
- abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); // inverse dq0 transform on voltages
- svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); // space vector modulation
+ abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); // inverse dq0 transform on voltages
+ svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); // space vector modulation
for(int i = 0; i<40000; i++){
- TIM1->CCR3 = 0x708*(1.0f-dtc_u); // Set duty cycles
- if(gpio->phasing){
+ TIM1->CCR3 = 0x708*(1.0f-dtc_u); // Set duty cycles
+ if(gpio->phasing){
TIM1->CCR2 = 0x708*(1.0f-dtc_v);
TIM1->CCR1 = 0x708*(1.0f-dtc_w);
}
@@ -97,12 +103,16 @@
wait_us(100);
}
ps->Sample();
-
- for(int i = 0; i<n; i++){ // rotate forwards
+ controller->i_b = I_SCALE*(float)(controller->adc2_raw - controller->adc2_offset); //Calculate phase currents from ADC readings
+ controller->i_c = I_SCALE*(float)(controller->adc1_raw - controller->adc1_offset);
+ controller->i_a = -controller->i_b - controller->i_c;
+ dq0(controller->theta_elec, controller->i_a, controller->i_b, controller->i_c, &controller->i_d, &controller->i_q); //dq0 transform on currents
+ float current = sqrt(pow(controller->i_d, 2) + pow(controller->i_q, 2));
+ for(int i = 0; i<n; i++){ // rotate forwards
for(int j = 0; j<n2; j++){
theta_ref += delta;
- abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); // inverse dq0 transform on voltages
- svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); // space vector modulation
+ abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); // inverse dq0 transform on voltages
+ svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); // space vector modulation
TIM1->CCR3 = 0x708*(1.0f-dtc_u);
if(gpio->phasing){
TIM1->CCR2 = 0x708*(1.0f-dtc_v);
@@ -122,11 +132,12 @@
printf("%.4f %.4f %d\n\r", theta_ref/(NPP), theta_actual, raw_f[i]);
//theta_ref += delta;
}
- for(int i = 0; i<n; i++){ // rotate backwards
+ printf(" Current Angle : Rotor Angle : Raw Encoder \n\r\n\r");
+ for(int i = 0; i<n; i++){ // rotate backwards
for(int j = 0; j<n2; j++){
theta_ref -= delta;
- abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); // inverse dq0 transform on voltages
- svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); // space vector modulation
+ abc(theta_ref, v_d, v_q, &v_u, &v_v, &v_w); // inverse dq0 transform on voltages
+ svm(1.0, v_u, v_v, v_w, &dtc_u, &dtc_v, &dtc_w); // space vector modulation
TIM1->CCR3 = 0x708*(1.0f-dtc_u);
if(gpio->phasing){
TIM1->CCR2 = 0x708*(1.0f-dtc_v);
@@ -139,8 +150,8 @@
wait_us(100);
ps->Sample();
}
- ps->Sample(); // sample position sensor
- theta_actual = ps->GetMechPosition(); // get mechanical position
+ ps->Sample(); // sample position sensor
+ theta_actual = ps->GetMechPosition(); // get mechanical position
error_b[i] = theta_ref/NPP - theta_actual;
raw_b[i] = ps->GetRawPosition();
printf("%.4f %.4f %d\n\r", theta_ref/(NPP), theta_actual, raw_b[i]);
@@ -149,53 +160,65 @@
float offset = 0;
for(int i = 0; i<n; i++){
- offset += (error_f[i] + error_b[n-1-i])/(2.0f*n); // calclate average position sensor offset
+ offset += (error_f[i] + error_b[n-1-i])/(2.0f*n); // calclate average position sensor offset
}
- offset = fmod(offset*NPP, 2*PI); // convert mechanical angle to electrical angle
- printf("Encoder Electrical Offset (rad) %f\n\r", offset);
+ offset = fmod(offset*NPP, 2*PI); // convert mechanical angle to electrical angle
+
- ps->SetElecOffset(offset); // Set position sensor offset
+ ps->SetElecOffset(offset); // Set position sensor offset
+ __float_reg[0] = offset;
+ E_OFFSET = offset;
/// Perform filtering to linearize position sensor eccentricity
/// FIR n-sample average, where n = number of samples in one electrical cycle
/// This filter has zero gain at electrical frequency and all integer multiples
- /// So cogging should also be completely filtered out.
+ /// So cogging should be completely filtered out.
float error[n] = {0};
- int window = 128;
+ const int window = 128;
float error_filt[n] = {0};
+ float cogging_current[window] = {0};
float mean = 0;
- for (int i = 0; i<n; i++){ //Average the forward and back directions
+ for (int i = 0; i<n; i++){ //Average the forward and back directions
error[i] = 0.5f*(error_f[i] + error_b[n-i-1]);
}
for (int i = 0; i<n; i++){
for(int j = 0; j<window; j++){
- int ind = -window/2 + j + i; // Indexes from -window/2 to + window/2
+ int ind = -window/2 + j + i; // Indexes from -window/2 to + window/2
if(ind<0){
- ind += n;} // Moving average wraps around
+ ind += n;} // Moving average wraps around
else if(ind > n-1) {
ind -= n;}
error_filt[i] += error[ind]/(float)window;
}
+ if(i<window){
+ cogging_current[i] = current*sinf((error[i] - error_filt[i])*NPP);
+ }
//printf("%.4f %4f %.4f %.4f\n\r", error[i], error_filt[i], error_f[i], error_b[i]);
mean += error_filt[i]/n;
}
- int raw_offset = (raw_f[0] + raw_b[n-1])/2; //Insensitive to errors in this direction, so 2 points is plenty
+ int raw_offset = (raw_f[0] + raw_b[n-1])/2; //Insensitive to errors in this direction, so 2 points is plenty
const int n_lut = 128;
int lut[n_lut];
- for (int i = 0; i<n_lut; i++){ // build lookup table
+ printf("\n\r Encoder non-linearity compensation table\n\r");
+ printf(" Sample Number : Lookup Index : Lookup Value : Cogging Current Lookup\n\r\n\r");
+ for (int i = 0; i<n_lut; i++){ // build lookup table
int ind = (raw_offset>>7) + i;
if(ind > (n_lut-1)){
ind -= n_lut;
}
lut[ind] = (int) ((error_filt[i*NPP] - mean)*(float)(ps->GetCPR())/(2.0f*PI));
- printf("%d %d %d %d\n\r", raw_offset>>7, i, ind, lut[ind]);
+ printf("%d %d %d %f\n\r", i, ind, lut[ind], cogging_current[i]);
}
- ps->WriteLUT(lut); // write lookup table to position sensor object
-
+
+ ps->WriteLUT(lut); // write lookup table to position sensor object
+ //memcpy(controller->cogging, cogging_current, sizeof(controller->cogging)); //compensation doesn't actually work yet....
+ memcpy(&ENCODER_LUT, lut, sizeof(lut));
+ printf("\n\rEncoder Electrical Offset (rad) %f\n\r", offset);
-
-
-
-
+ if (!prefs->ready()) prefs->open();
+ prefs->flush();
+ //prefs->close();
+
+
}
\ No newline at end of file
--- a/Calibration/calibration.h Fri Mar 31 18:24:46 2017 +0000 +++ b/Calibration/calibration.h Wed Apr 05 20:54:16 2017 +0000 @@ -4,9 +4,10 @@ #include "foc.h" #include "mbed.h" #include "PositionSensor.h" - +#include "PreferenceWriter.h" +#include "user_config.h" -void order_phases(PositionSensor *ps, GPIOStruct *gpio); -void calibrate(PositionSensor *ps, GPIOStruct *gpio); +void order_phases(PositionSensor *ps, GPIOStruct *gpio, ControllerStruct *controller, PreferenceWriter *prefs); +void calibrate(PositionSensor *ps, GPIOStruct *gpio, ControllerStruct *controller, PreferenceWriter *prefs); #endif
--- a/Config/current_controller_config.h Fri Mar 31 18:24:46 2017 +0000 +++ b/Config/current_controller_config.h Wed Apr 05 20:54:16 2017 +0000 @@ -1,11 +1,11 @@ #ifndef CURRENT_CONTROLLER_CONFIG_H #define CURRENT_CONTROLLER_CONFIG_H -#define K_D .02f // Volts/Amp -#define K_Q .02f // Volts/Amp +#define K_D .05f // Volts/Amp +#define K_Q .05f // Volts/Amp #define KI_D 0.04f // 1/samples #define KI_Q 0.04f // 1/samples -#define V_BUS 14.0f // Volts +#define V_BUS 24.0f // Volts #define D_INT_LIM V_BUS/(K_D*KI_D) // Amps*samples #define Q_INT_LIM V_BUS/(K_Q*KI_Q) // Amps*samples
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Config/user_config.h Wed Apr 05 20:54:16 2017 +0000 @@ -0,0 +1,19 @@ +/// Values stored in flash, which are modifieable by user actions /// + +#ifndef USER_CONFIG_H +#define USER_CONFIG_H + + +#define E_OFFSET __float_reg[0] +#define M_OFFSET __float_reg[1] +#define I_BW __float_reg[2] +#define I_LIMIT __float_reg[3] + +#define PHASE_ORDER __int_reg[0] +#define CAN_ID __int_reg[1] +#define ENCODER_LUT __int_reg[4] + +extern float __float_reg[]; +extern int __int_reg[]; + +#endif
--- a/FOC/foc.cpp Fri Mar 31 18:24:46 2017 +0000
+++ b/FOC/foc.cpp Wed Apr 05 20:54:16 2017 +0000
@@ -26,9 +26,9 @@
///u,v,w amplitude = v_bus for full modulation depth///
float v_offset = (fminf3(u, v, w) + fmaxf3(u, v, w))/2.0f;
- *dtc_u = fminf(fmaxf(((u - v_offset)*0.5f/v_bus + 0.5f), DTC_MIN), DTC_MAX);
- *dtc_v = fminf(fmaxf(((v - v_offset)*0.5f/v_bus + 0.5f), DTC_MIN), DTC_MAX);
- *dtc_w = fminf(fmaxf(((w - v_offset)*0.5f/v_bus + 0.5f), DTC_MIN), DTC_MAX);
+ *dtc_u = fminf(fmaxf(((u - v_offset)*0.5f/v_bus + ((DTC_MAX-DTC_MIN)/2)), DTC_MIN), DTC_MAX);
+ *dtc_v = fminf(fmaxf(((v - v_offset)*0.5f/v_bus + ((DTC_MAX-DTC_MIN)/2)), DTC_MIN), DTC_MAX);
+ *dtc_w = fminf(fmaxf(((w - v_offset)*0.5f/v_bus + ((DTC_MAX-DTC_MIN)/2)), DTC_MIN), DTC_MAX);
}
@@ -68,9 +68,13 @@
dq0(controller->theta_elec, controller->i_a, controller->i_b, controller->i_c, &controller->i_d, &controller->i_q); //dq0 transform on currents
+ ///Cogging Compensation Lookup///
+ //int ind = theta * (128.0f/(2.0f*PI));
+ //float cogging_current = controller->cogging[ind];
+ //float cogging_current = 1.0f*cos(6*theta);
///Controller///
float i_d_error = controller->i_d_ref - controller->i_d;
- float i_q_error = controller->i_q_ref - controller->i_q;
+ float i_q_error = controller->i_q_ref - controller->i_q;// + cogging_current;
float v_d_ff = 2.0f*(2*controller->i_d_ref*R_PHASE); //feed-forward voltage
float v_q_ff = 2.0f*(2*controller->i_q_ref*R_PHASE + controller->dtheta_elec*WB*0.8165f);
controller->d_int += i_d_error;
@@ -118,11 +122,11 @@
controller->theta_elec = theta; //For some reason putting this at the front breaks thins
- if(controller->loop_count >1000){
+ if(controller->loop_count >400){
//controller->i_q_ref = -controller->i_q_ref;
controller->loop_count = 0;
- //printf("%f\n\r", controller->dtheta_elec);
+ //printf("%d %f\n\r", ind, cogging_current);
//printf("%f\n\r", controller->theta_elec);
//pc.printf("%f %f %f\n\r", controller->i_a, controller->i_b, controller->i_c);
//pc.printf("%f %f\n\r", controller->i_d, controller->i_q);
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/FlashWriter/FlashWriter.cpp Wed Apr 05 20:54:16 2017 +0000
@@ -0,0 +1,53 @@
+#include "stm32f4xx_flash.h"
+#include "FlashWriter.h"
+
+FlashWriter::FlashWriter(int sector) {
+ if (sector > 7) sector = 7;
+ __sector = sector;
+ __base = __SECTOR_ADDRS[sector];
+ __ready = false;
+}
+
+bool FlashWriter::ready() {
+ return __ready;
+}
+
+void FlashWriter::open() {
+ FLASH_Unlock();
+ FLASH_ClearFlag( FLASH_FLAG_EOP | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
+ FLASH_EraseSector(__SECTORS[__sector], VoltageRange_3);
+ __ready = true;
+}
+
+void FlashWriter::write(uint32_t index, int x) {
+ union {int a; uint32_t b;};
+ a = x;
+ FLASH_ProgramWord(__base + 4 * index, b);
+}
+
+void FlashWriter::write(uint32_t index, unsigned int x) {
+ FLASH_ProgramWord(__base + 4 * index, x);
+}
+
+void FlashWriter::write(uint32_t index, float x) {
+ union {float a; uint32_t b;};
+ a = x;
+ FLASH_ProgramWord(__base + 4 * index, b);
+}
+
+void FlashWriter::close() {
+ FLASH_Lock();
+ __ready = false;
+}
+
+int flashReadInt(uint32_t sector, uint32_t index) {
+ return *(int*) (__SECTOR_ADDRS[sector] + 4 * index);
+}
+
+uint32_t flashReadUint(uint32_t sector, uint32_t index) {
+ return *(uint32_t*) (__SECTOR_ADDRS[sector] + 4 * index);
+}
+
+float flashReadFloat(uint32_t sector, uint32_t index) {
+ return *(float*) (__SECTOR_ADDRS[sector] + 4 * index);
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/FlashWriter/FlashWriter.h Wed Apr 05 20:54:16 2017 +0000
@@ -0,0 +1,39 @@
+#ifndef __FLASHWRITER_H
+#define __FLASHWRITER_H
+
+#include "stm32f4xx_flash.h"
+
+/* Base address of the Flash sectors */
+#define ADDR_FLASH_SECTOR_0 ((uint32_t)0x08000000) /* Base @ of Sector 0, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_1 ((uint32_t)0x08004000) /* Base @ of Sector 1, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_2 ((uint32_t)0x08008000) /* Base @ of Sector 2, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_3 ((uint32_t)0x0800C000) /* Base @ of Sector 3, 16 Kbytes */
+#define ADDR_FLASH_SECTOR_4 ((uint32_t)0x08010000) /* Base @ of Sector 4, 64 Kbytes */
+#define ADDR_FLASH_SECTOR_5 ((uint32_t)0x08020000) /* Base @ of Sector 5, 128 Kbytes */
+#define ADDR_FLASH_SECTOR_6 ((uint32_t)0x08040000) /* Base @ of Sector 6, 128 Kbytes */
+#define ADDR_FLASH_SECTOR_7 ((uint32_t)0x08060000) /* Base @ of Sector 7, 128 Kbytes */
+
+static uint32_t __SECTOR_ADDRS[] = {ADDR_FLASH_SECTOR_0, ADDR_FLASH_SECTOR_1, ADDR_FLASH_SECTOR_2, ADDR_FLASH_SECTOR_3,
+ ADDR_FLASH_SECTOR_4, ADDR_FLASH_SECTOR_5, ADDR_FLASH_SECTOR_6, ADDR_FLASH_SECTOR_7};
+static uint32_t __SECTORS[] = {FLASH_Sector_0, FLASH_Sector_1, FLASH_Sector_2, FLASH_Sector_3,
+ FLASH_Sector_4, FLASH_Sector_6, FLASH_Sector_6, FLASH_Sector_7};
+class FlashWriter {
+public:
+ FlashWriter(int sector);
+ void open();
+ bool ready();
+ void write(uint32_t index, int x);
+ void write(uint32_t index, unsigned int x);
+ void write(uint32_t index, float x);
+ void close();
+private:
+ uint32_t __base;
+ uint32_t __sector;
+ bool __ready;
+};
+
+int flashReadInt(uint32_t sector, uint32_t index);
+uint32_t flashReadUint(uint32_t sector, uint32_t index);
+float flashReadFloat(uint32_t sector, uint32_t index);
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/FlashWriter/stm32f4xx_flash.c Wed Apr 05 20:54:16 2017 +0000
@@ -0,0 +1,1616 @@
+/**
+ ******************************************************************************
+ * @file stm32f4xx_flash.c
+ * @author MCD Application Team
+ * @version V1.7.1
+ * @date 20-May-2016
+ * @brief This file provides firmware functions to manage the following
+ * functionalities of the FLASH peripheral:
+ * + FLASH Interface configuration
+ * + FLASH Memory Programming
+ * + Option Bytes Programming
+ * + Interrupts and flags management
+ *
+ @verbatim
+ ===============================================================================
+ ##### How to use this driver #####
+ ===============================================================================
+ [..]
+ This driver provides functions to configure and program the FLASH memory
+ of all STM32F4xx devices. These functions are split in 4 groups:
+
+ (#) FLASH Interface configuration functions: this group includes the
+ management of the following features:
+ (++) Set the latency
+ (++) Enable/Disable the prefetch buffer
+ (++) Enable/Disable the Instruction cache and the Data cache
+ (++) Reset the Instruction cache and the Data cache
+
+ (#) FLASH Memory Programming functions: this group includes all needed
+ functions to erase and program the main memory:
+ (++) Lock and Unlock the FLASH interface
+ (++) Erase function: Erase sector, erase all sectors
+ (++) Program functions: byte, half word, word and double word
+
+ (#) Option Bytes Programming functions: this group includes all needed
+ functions to manage the Option Bytes:
+ (++) Set/Reset the write protection
+ (++) Set the Read protection Level
+ (++) Set the BOR level
+ (++) Program the user Option Bytes
+ (++) Launch the Option Bytes loader
+
+ (#) Interrupts and flags management functions: this group
+ includes all needed functions to:
+ (++) Enable/Disable the FLASH interrupt sources
+ (++) Get flags status
+ (++) Clear flags
+ (++) Get FLASH operation status
+ (++) Wait for last FLASH operation
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_flash.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+ * @{
+ */
+
+/** @defgroup FLASH
+ * @brief FLASH driver modules
+ * @{
+ */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define SECTOR_MASK ((uint32_t)0xFFFFFF07)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup FLASH_Private_Functions
+ * @{
+ */
+
+/** @defgroup FLASH_Group1 FLASH Interface configuration functions
+ * @brief FLASH Interface configuration functions
+ *
+
+@verbatim
+ ===============================================================================
+ ##### FLASH Interface configuration functions #####
+ ===============================================================================
+ [..]
+ This group includes the following functions:
+ (+) void FLASH_SetLatency(uint32_t FLASH_Latency)
+ To correctly read data from FLASH memory, the number of wait states (LATENCY)
+ must be correctly programmed according to the frequency of the CPU clock
+ (HCLK) and the supply voltage of the device.
+ [..]
+ For STM32F405xx/07xx and STM32F415xx/17xx devices
+ +-------------------------------------------------------------------------------------+
+ | Latency | HCLK clock frequency (MHz) |
+ | |---------------------------------------------------------------------|
+ | | voltage range | voltage range | voltage range | voltage range |
+ | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |0WS(1CPU cycle)|0 < HCLK <= 30 |0 < HCLK <= 24 |0 < HCLK <= 22 |0 < HCLK <= 20 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44 |20 < HCLK <= 40 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |44 < HCLK <= 66 |40 < HCLK <= 60 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |66 < HCLK <= 88 |60 < HCLK <= 80 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|88 < HCLK <= 110 |80 < HCLK <= 100 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |5WS(6CPU cycle)|150< HCLK <= 168|120< HCLK <= 144|110 < HCLK <= 132|100 < HCLK <= 120|
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |6WS(7CPU cycle)| NA |144< HCLK <= 168|132 < HCLK <= 154|120 < HCLK <= 140|
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |7WS(8CPU cycle)| NA | NA |154 < HCLK <= 168|140 < HCLK <= 160|
+ +---------------|----------------|----------------|-----------------|-----------------+
+
+ [..]
+ For STM32F42xxx/43xxx devices
+ +-------------------------------------------------------------------------------------+
+ | Latency | HCLK clock frequency (MHz) |
+ | |---------------------------------------------------------------------|
+ | | voltage range | voltage range | voltage range | voltage range |
+ | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |0WS(1CPU cycle)|0 < HCLK <= 30 |0 < HCLK <= 24 |0 < HCLK <= 22 |0 < HCLK <= 20 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44 |20 < HCLK <= 40 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |44 < HCLK <= 66 |40 < HCLK <= 60 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |66 < HCLK <= 88 |60 < HCLK <= 80 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|88 < HCLK <= 110 |80 < HCLK <= 100 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |5WS(6CPU cycle)|120< HCLK <= 180|120< HCLK <= 144|110 < HCLK <= 132|100 < HCLK <= 120|
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |6WS(7CPU cycle)| NA |144< HCLK <= 168|132 < HCLK <= 154|120 < HCLK <= 140|
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |7WS(8CPU cycle)| NA |168< HCLK <= 180|154 < HCLK <= 176|140 < HCLK <= 160|
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |8WS(9CPU cycle)| NA | NA |176 < HCLK <= 180|160 < HCLK <= 168|
+ +-------------------------------------------------------------------------------------+
+
+ [..]
+ For STM32F401x devices
+ +-------------------------------------------------------------------------------------+
+ | Latency | HCLK clock frequency (MHz) |
+ | |---------------------------------------------------------------------|
+ | | voltage range | voltage range | voltage range | voltage range |
+ | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |0WS(1CPU cycle)|0 < HCLK <= 30 |0 < HCLK <= 24 |0 < HCLK <= 22 |0 < HCLK <= 20 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44 |20 < HCLK <= 40 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |2WS(3CPU cycle)|60 < HCLK <= 84 |48 < HCLK <= 72 |44 < HCLK <= 66 |40 < HCLK <= 60 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |3WS(4CPU cycle)| NA |72 < HCLK <= 84 |66 < HCLK <= 84 |60 < HCLK <= 80 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |4WS(5CPU cycle)| NA | NA | NA |80 < HCLK <= 84 |
+ +-------------------------------------------------------------------------------------+
+
+ [..]
+ For STM32F410xx/STM32F411xE devices
+ +-------------------------------------------------------------------------------------+
+ | Latency | HCLK clock frequency (MHz) |
+ | |---------------------------------------------------------------------|
+ | | voltage range | voltage range | voltage range | voltage range |
+ | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |0WS(1CPU cycle)|0 < HCLK <= 30 |0 < HCLK <= 24 |0 < HCLK <= 18 |0 < HCLK <= 16 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |1WS(2CPU cycle)|30 < HCLK <= 64 |24 < HCLK <= 48 |18 < HCLK <= 36 |16 < HCLK <= 32 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |2WS(3CPU cycle)|64 < HCLK <= 90 |48 < HCLK <= 72 |36 < HCLK <= 54 |32 < HCLK <= 48 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |3WS(4CPU cycle)|90 < HCLK <= 100|72 < HCLK <= 96 |54 < HCLK <= 72 |48 < HCLK <= 64 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |4WS(5CPU cycle)| NA |96 < HCLK <= 100|72 < HCLK <= 90 |64 < HCLK <= 80 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |5WS(6CPU cycle)| NA | NA |90 < HCLK <= 100 |80 < HCLK <= 96 |
+ |---------------|----------------|----------------|-----------------|-----------------|
+ |6WS(7CPU cycle)| NA | NA | NA |96 < HCLK <= 100 |
+ +-------------------------------------------------------------------------------------+
+
+ [..]
+ +-------------------------------------------------------------------------------------------------------------------+
+ | | voltage range | voltage range | voltage range | voltage range | voltage range 2.7 V - 3.6 V |
+ | | 2.7 V - 3.6 V | 2.4 V - 2.7 V | 2.1 V - 2.4 V | 1.8 V - 2.1 V | with External Vpp = 9V |
+ |---------------|----------------|----------------|-----------------|-----------------|-----------------------------|
+ |Max Parallelism| x32 | x16 | x8 | x64 |
+ |---------------|----------------|----------------|-----------------|-----------------|-----------------------------|
+ |PSIZE[1:0] | 10 | 01 | 00 | 11 |
+ +-------------------------------------------------------------------------------------------------------------------+
+
+ -@- On STM32F405xx/407xx and STM32F415xx/417xx devices:
+ (++) when VOS = '0' Scale 2 mode, the maximum value of fHCLK = 144MHz.
+ (++) when VOS = '1' Scale 1 mode, the maximum value of fHCLK = 168MHz.
+ [..]
+ On STM32F42xxx/43xxx devices:
+ (++) when VOS[1:0] = '0x01' Scale 3 mode, the maximum value of fHCLK is 120MHz.
+ (++) when VOS[1:0] = '0x10' Scale 2 mode, the maximum value of fHCLK is 144MHz if OverDrive OFF and 168MHz if OverDrive ON.
+ (++) when VOS[1:0] = '0x11' Scale 1 mode, the maximum value of fHCLK is 168MHz if OverDrive OFF and 180MHz if OverDrive ON.
+ [..]
+ On STM32F401x devices:
+ (++) when VOS[1:0] = '0x01' Scale 3 mode, the maximum value of fHCLK is 60MHz.
+ (++) when VOS[1:0] = '0x10' Scale 2 mode, the maximum value of fHCLK is 84MHz.
+ [..]
+ On STM32F410xx/STM32F411xE devices:
+ (++) when VOS[1:0] = '0x01' Scale 3 mode, the maximum value of fHCLK is 64MHz.
+ (++) when VOS[1:0] = '0x10' Scale 2 mode, the maximum value of fHCLK is 84MHz.
+ (++) when VOS[1:0] = '0x11' Scale 1 mode, the maximum value of fHCLK is 100MHz.
+
+ For more details please refer product DataSheet
+ You can use PWR_MainRegulatorModeConfig() function to control VOS bits.
+
+ (+) void FLASH_PrefetchBufferCmd(FunctionalState NewState)
+ (+) void FLASH_InstructionCacheCmd(FunctionalState NewState)
+ (+) void FLASH_DataCacheCmd(FunctionalState NewState)
+ (+) void FLASH_InstructionCacheReset(void)
+ (+) void FLASH_DataCacheReset(void)
+
+ [..]
+ The unlock sequence is not needed for these functions.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Sets the code latency value.
+ * @param FLASH_Latency: specifies the FLASH Latency value.
+ * This parameter can be one of the following values:
+ * @arg FLASH_Latency_0: FLASH Zero Latency cycle
+ * @arg FLASH_Latency_1: FLASH One Latency cycle
+ * @arg FLASH_Latency_2: FLASH Two Latency cycles
+ * @arg FLASH_Latency_3: FLASH Three Latency cycles
+ * @arg FLASH_Latency_4: FLASH Four Latency cycles
+ * @arg FLASH_Latency_5: FLASH Five Latency cycles
+ * @arg FLASH_Latency_6: FLASH Six Latency cycles
+ * @arg FLASH_Latency_7: FLASH Seven Latency cycles
+ * @arg FLASH_Latency_8: FLASH Eight Latency cycles
+ * @arg FLASH_Latency_9: FLASH Nine Latency cycles
+ * @arg FLASH_Latency_10: FLASH Teen Latency cycles
+ * @arg FLASH_Latency_11: FLASH Eleven Latency cycles
+ * @arg FLASH_Latency_12: FLASH Twelve Latency cycles
+ * @arg FLASH_Latency_13: FLASH Thirteen Latency cycles
+ * @arg FLASH_Latency_14: FLASH Fourteen Latency cycles
+ * @arg FLASH_Latency_15: FLASH Fifteen Latency cycles
+ *
+ * @note For STM32F405xx/407xx, STM32F415xx/417xx, STM32F401xx/411xE and STM32F412xG devices
+ * this parameter can be a value between FLASH_Latency_0 and FLASH_Latency_7.
+ *
+ * @note For STM32F42xxx/43xxx devices this parameter can be a value between
+ * FLASH_Latency_0 and FLASH_Latency_15.
+ *
+ * @retval None
+ */
+void FLASH_SetLatency(uint32_t FLASH_Latency)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_LATENCY(FLASH_Latency));
+
+ /* Perform Byte access to FLASH_ACR[8:0] to set the Latency value */
+ *(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)FLASH_Latency;
+}
+
+/**
+ * @brief Enables or disables the Prefetch Buffer.
+ * @param NewState: new state of the Prefetch Buffer.
+ * This parameter can be: ENABLE or DISABLE.
+ * @retval None
+ */
+void FLASH_PrefetchBufferCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ /* Enable or disable the Prefetch Buffer */
+ if(NewState != DISABLE)
+ {
+ FLASH->ACR |= FLASH_ACR_PRFTEN;
+ }
+ else
+ {
+ FLASH->ACR &= (~FLASH_ACR_PRFTEN);
+ }
+}
+
+/**
+ * @brief Enables or disables the Instruction Cache feature.
+ * @param NewState: new state of the Instruction Cache.
+ * This parameter can be: ENABLE or DISABLE.
+ * @retval None
+ */
+void FLASH_InstructionCacheCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if(NewState != DISABLE)
+ {
+ FLASH->ACR |= FLASH_ACR_ICEN;
+ }
+ else
+ {
+ FLASH->ACR &= (~FLASH_ACR_ICEN);
+ }
+}
+
+/**
+ * @brief Enables or disables the Data Cache feature.
+ * @param NewState: new state of the Data Cache.
+ * This parameter can be: ENABLE or DISABLE.
+ * @retval None
+ */
+void FLASH_DataCacheCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if(NewState != DISABLE)
+ {
+ FLASH->ACR |= FLASH_ACR_DCEN;
+ }
+ else
+ {
+ FLASH->ACR &= (~FLASH_ACR_DCEN);
+ }
+}
+
+/**
+ * @brief Resets the Instruction Cache.
+ * @note This function must be used only when the Instruction Cache is disabled.
+ * @param None
+ * @retval None
+ */
+void FLASH_InstructionCacheReset(void)
+{
+ FLASH->ACR |= FLASH_ACR_ICRST;
+}
+
+/**
+ * @brief Resets the Data Cache.
+ * @note This function must be used only when the Data Cache is disabled.
+ * @param None
+ * @retval None
+ */
+void FLASH_DataCacheReset(void)
+{
+ FLASH->ACR |= FLASH_ACR_DCRST;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Group2 FLASH Memory Programming functions
+ * @brief FLASH Memory Programming functions
+ *
+@verbatim
+ ===============================================================================
+ ##### FLASH Memory Programming functions #####
+ ===============================================================================
+ [..]
+ This group includes the following functions:
+ (+) void FLASH_Unlock(void)
+ (+) void FLASH_Lock(void)
+ (+) FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange)
+ (+) FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange)
+ (+) FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data)
+ (+) FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data)
+ (+) FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data)
+ (+) FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data)
+ The following functions can be used only for STM32F42xxx/43xxx devices.
+ (+) FLASH_Status FLASH_EraseAllBank1Sectors(uint8_t VoltageRange)
+ (+) FLASH_Status FLASH_EraseAllBank2Sectors(uint8_t VoltageRange)
+ [..]
+ Any operation of erase or program should follow these steps:
+ (#) Call the FLASH_Unlock() function to enable the FLASH control register access
+
+ (#) Call the desired function to erase sector(s) or program data
+
+ (#) Call the FLASH_Lock() function to disable the FLASH control register access
+ (recommended to protect the FLASH memory against possible unwanted operation)
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Unlocks the FLASH control register access
+ * @param None
+ * @retval None
+ */
+void FLASH_Unlock(void)
+{
+ if((FLASH->CR & FLASH_CR_LOCK) != RESET)
+ {
+ /* Authorize the FLASH Registers access */
+ FLASH->KEYR = FLASH_KEY1;
+ FLASH->KEYR = FLASH_KEY2;
+ }
+}
+
+/**
+ * @brief Locks the FLASH control register access
+ * @param None
+ * @retval None
+ */
+void FLASH_Lock(void)
+{
+ /* Set the LOCK Bit to lock the FLASH Registers access */
+ FLASH->CR |= FLASH_CR_LOCK;
+}
+
+/**
+ * @brief Erases a specified FLASH Sector.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param FLASH_Sector: The Sector number to be erased.
+ *
+ * @note For STM32F405xx/407xx and STM32F415xx/417xx devices this parameter can
+ * be a value between FLASH_Sector_0 and FLASH_Sector_11.
+ *
+ * For STM32F42xxx/43xxx devices this parameter can be a value between
+ * FLASH_Sector_0 and FLASH_Sector_23.
+ *
+ * For STM32F401xx devices this parameter can be a value between
+ * FLASH_Sector_0 and FLASH_Sector_5.
+ *
+ * For STM32F411xE and STM32F412xG devices this parameter can be a value between
+ * FLASH_Sector_0 and FLASH_Sector_7.
+ *
+ * For STM32F410xx devices this parameter can be a value between
+ * FLASH_Sector_0 and FLASH_Sector_4.
+ *
+ * @param VoltageRange: The device voltage range which defines the erase parallelism.
+ * This parameter can be one of the following values:
+ * @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V,
+ * the operation will be done by byte (8-bit)
+ * @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+ * the operation will be done by half word (16-bit)
+ * @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+ * the operation will be done by word (32-bit)
+ * @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp,
+ * the operation will be done by double word (64-bit)
+ *
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange)
+{
+ uint32_t tmp_psize = 0x0;
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_SECTOR(FLASH_Sector));
+ assert_param(IS_VOLTAGERANGE(VoltageRange));
+
+ if(VoltageRange == VoltageRange_1)
+ {
+ tmp_psize = FLASH_PSIZE_BYTE;
+ }
+ else if(VoltageRange == VoltageRange_2)
+ {
+ tmp_psize = FLASH_PSIZE_HALF_WORD;
+ }
+ else if(VoltageRange == VoltageRange_3)
+ {
+ tmp_psize = FLASH_PSIZE_WORD;
+ }
+ else
+ {
+ tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+ }
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to erase the sector */
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= tmp_psize;
+ FLASH->CR &= SECTOR_MASK;
+ FLASH->CR |= FLASH_CR_SER | FLASH_Sector;
+ FLASH->CR |= FLASH_CR_STRT;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the erase operation is completed, disable the SER Bit */
+ FLASH->CR &= (~FLASH_CR_SER);
+ FLASH->CR &= SECTOR_MASK;
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/**
+ * @brief Erases all FLASH Sectors.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param VoltageRange: The device voltage range which defines the erase parallelism.
+ * This parameter can be one of the following values:
+ * @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V,
+ * the operation will be done by byte (8-bit)
+ * @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+ * the operation will be done by half word (16-bit)
+ * @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+ * the operation will be done by word (32-bit)
+ * @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp,
+ * the operation will be done by double word (64-bit)
+ *
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange)
+{
+ uint32_t tmp_psize = 0x0;
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+ assert_param(IS_VOLTAGERANGE(VoltageRange));
+
+ if(VoltageRange == VoltageRange_1)
+ {
+ tmp_psize = FLASH_PSIZE_BYTE;
+ }
+ else if(VoltageRange == VoltageRange_2)
+ {
+ tmp_psize = FLASH_PSIZE_HALF_WORD;
+ }
+ else if(VoltageRange == VoltageRange_3)
+ {
+ tmp_psize = FLASH_PSIZE_WORD;
+ }
+ else
+ {
+ tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+ }
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to erase all sectors */
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= tmp_psize;
+ FLASH->CR |= (FLASH_CR_MER1 | FLASH_CR_MER2);
+ FLASH->CR |= FLASH_CR_STRT;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the erase operation is completed, disable the MER Bit */
+ FLASH->CR &= ~(FLASH_CR_MER1 | FLASH_CR_MER2);
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG) || defined(STM32F446xx)
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= tmp_psize;
+ FLASH->CR |= FLASH_CR_MER;
+ FLASH->CR |= FLASH_CR_STRT;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the erase operation is completed, disable the MER Bit */
+ FLASH->CR &= (~FLASH_CR_MER);
+#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG || STM32F446xx */
+
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/**
+ * @brief Erases all FLASH Sectors in Bank 1.
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param VoltageRange: The device voltage range which defines the erase parallelism.
+ * This parameter can be one of the following values:
+ * @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V,
+ * the operation will be done by byte (8-bit)
+ * @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+ * the operation will be done by half word (16-bit)
+ * @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+ * the operation will be done by word (32-bit)
+ * @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp,
+ * the operation will be done by double word (64-bit)
+ *
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_EraseAllBank1Sectors(uint8_t VoltageRange)
+{
+ uint32_t tmp_psize = 0x0;
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+ assert_param(IS_VOLTAGERANGE(VoltageRange));
+
+ if(VoltageRange == VoltageRange_1)
+ {
+ tmp_psize = FLASH_PSIZE_BYTE;
+ }
+ else if(VoltageRange == VoltageRange_2)
+ {
+ tmp_psize = FLASH_PSIZE_HALF_WORD;
+ }
+ else if(VoltageRange == VoltageRange_3)
+ {
+ tmp_psize = FLASH_PSIZE_WORD;
+ }
+ else
+ {
+ tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+ }
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to erase all sectors */
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= tmp_psize;
+ FLASH->CR |= FLASH_CR_MER1;
+ FLASH->CR |= FLASH_CR_STRT;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the erase operation is completed, disable the MER Bit */
+ FLASH->CR &= (~FLASH_CR_MER1);
+
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+
+/**
+ * @brief Erases all FLASH Sectors in Bank 2.
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param VoltageRange: The device voltage range which defines the erase parallelism.
+ * This parameter can be one of the following values:
+ * @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V,
+ * the operation will be done by byte (8-bit)
+ * @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+ * the operation will be done by half word (16-bit)
+ * @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+ * the operation will be done by word (32-bit)
+ * @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp,
+ * the operation will be done by double word (64-bit)
+ *
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_EraseAllBank2Sectors(uint8_t VoltageRange)
+{
+ uint32_t tmp_psize = 0x0;
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+ assert_param(IS_VOLTAGERANGE(VoltageRange));
+
+ if(VoltageRange == VoltageRange_1)
+ {
+ tmp_psize = FLASH_PSIZE_BYTE;
+ }
+ else if(VoltageRange == VoltageRange_2)
+ {
+ tmp_psize = FLASH_PSIZE_HALF_WORD;
+ }
+ else if(VoltageRange == VoltageRange_3)
+ {
+ tmp_psize = FLASH_PSIZE_WORD;
+ }
+ else
+ {
+ tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+ }
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to erase all sectors */
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= tmp_psize;
+ FLASH->CR |= FLASH_CR_MER2;
+ FLASH->CR |= FLASH_CR_STRT;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the erase operation is completed, disable the MER Bit */
+ FLASH->CR &= (~FLASH_CR_MER2);
+
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/**
+ * @brief Programs a double word (64-bit) at a specified address.
+ * @note This function must be used when the device voltage range is from
+ * 2.7V to 3.6V and an External Vpp is present.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @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_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to program the new data */
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD;
+ FLASH->CR |= FLASH_CR_PG;
+
+ *(__IO uint64_t*)Address = Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the program operation is completed, disable the PG Bit */
+ FLASH->CR &= (~FLASH_CR_PG);
+ }
+ /* Return the Program Status */
+ return status;
+}
+
+/**
+ * @brief Programs a word (32-bit) at a specified address.
+ *
+ * @note This function must be used when the device voltage range is from 2.7V to 3.6V.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param Address: specifies the address to be programmed.
+ * This parameter can be any address in Program memory zone or in OTP zone.
+ * @param Data: specifies the data to be programmed.
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to program the new data */
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= FLASH_PSIZE_WORD;
+ FLASH->CR |= FLASH_CR_PG;
+
+ *(__IO uint32_t*)Address = Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the program operation is completed, disable the PG Bit */
+ FLASH->CR &= (~FLASH_CR_PG);
+ }
+ /* Return the Program Status */
+ return status;
+}
+
+/**
+ * @brief Programs a half word (16-bit) at a specified address.
+ * @note This function must be used when the device voltage range is from 2.1V to 3.6V.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param Address: specifies the address to be programmed.
+ * This parameter can be any address in Program memory zone or in OTP zone.
+ * @param Data: specifies the data to be programmed.
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to program the new data */
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= FLASH_PSIZE_HALF_WORD;
+ FLASH->CR |= FLASH_CR_PG;
+
+ *(__IO uint16_t*)Address = Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the program operation is completed, disable the PG Bit */
+ FLASH->CR &= (~FLASH_CR_PG);
+ }
+ /* Return the Program Status */
+ return status;
+}
+
+/**
+ * @brief Programs a byte (8-bit) at a specified address.
+ * @note This function can be used within all the device supply voltage ranges.
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param Address: specifies the address to be programmed.
+ * This parameter can be any address in Program memory zone or in OTP zone.
+ * @param Data: specifies the data to be programmed.
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ /* if the previous operation is completed, proceed to program the new data */
+ FLASH->CR &= CR_PSIZE_MASK;
+ FLASH->CR |= FLASH_PSIZE_BYTE;
+ FLASH->CR |= FLASH_CR_PG;
+
+ *(__IO uint8_t*)Address = Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ /* if the program operation is completed, disable the PG Bit */
+ FLASH->CR &= (~FLASH_CR_PG);
+ }
+
+ /* Return the Program Status */
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Group3 Option Bytes Programming functions
+ * @brief Option Bytes Programming functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Option Bytes Programming functions #####
+ ===============================================================================
+ [..]
+ This group includes the following functions:
+ (+) void FLASH_OB_Unlock(void)
+ (+) void FLASH_OB_Lock(void)
+ (+) void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
+ (+) void FLASH_OB_WRP1Config(uint32_t OB_WRP, FunctionalState NewState)
+ (+) void FLASH_OB_PCROPSelectionConfig(uint8_t OB_PCROPSelect)
+ (+) void FLASH_OB_PCROPConfig(uint32_t OB_PCROP, FunctionalState NewState)
+ (+) void FLASH_OB_PCROP1Config(uint32_t OB_PCROP, FunctionalState NewState)
+ (+) void FLASH_OB_RDPConfig(uint8_t OB_RDP)
+ (+) void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY)
+ (+) void FLASH_OB_BORConfig(uint8_t OB_BOR)
+ (+) FLASH_Status FLASH_ProgramOTP(uint32_t Address, uint32_t Data)
+ (+) FLASH_Status FLASH_OB_Launch(void)
+ (+) uint32_t FLASH_OB_GetUser(void)
+ (+) uint8_t FLASH_OB_GetWRP(void)
+ (+) uint8_t FLASH_OB_GetWRP1(void)
+ (+) uint8_t FLASH_OB_GetPCROP(void)
+ (+) uint8_t FLASH_OB_GetPCROP1(void)
+ (+) uint8_t FLASH_OB_GetRDP(void)
+ (+) uint8_t FLASH_OB_GetBOR(void)
+ [..]
+ The following function can be used only for STM32F42xxx/43xxx devices.
+ (+) void FLASH_OB_BootConfig(uint8_t OB_BOOT)
+ [..]
+ Any operation of erase or program should follow these steps:
+ (#) Call the FLASH_OB_Unlock() function to enable the FLASH option control
+ register access
+
+ (#) Call one or several functions to program the desired Option Bytes:
+ (++) void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
+ => to Enable/Disable the desired sector write protection
+ (++) void FLASH_OB_RDPConfig(uint8_t OB_RDP) => to set the desired read
+ Protection Level
+ (++) void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY)
+ => to configure the user Option Bytes.
+ (++) void FLASH_OB_BORConfig(uint8_t OB_BOR) => to set the BOR Level
+
+ (#) Once all needed Option Bytes to be programmed are correctly written,
+ call the FLASH_OB_Launch() function to launch the Option Bytes
+ programming process.
+
+ -@- When changing the IWDG mode from HW to SW or from SW to HW, a system
+ reset is needed to make the change effective.
+
+ (#) Call the FLASH_OB_Lock() function to disable the FLASH option control
+ register access (recommended to protect the Option Bytes against
+ possible unwanted operations)
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Unlocks the FLASH Option Control Registers access.
+ * @param None
+ * @retval None
+ */
+void FLASH_OB_Unlock(void)
+{
+ if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET)
+ {
+ /* Authorizes the Option Byte register programming */
+ FLASH->OPTKEYR = FLASH_OPT_KEY1;
+ FLASH->OPTKEYR = FLASH_OPT_KEY2;
+ }
+}
+
+/**
+ * @brief Locks the FLASH Option Control Registers access.
+ * @param None
+ * @retval None
+ */
+void FLASH_OB_Lock(void)
+{
+ /* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */
+ FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK;
+}
+
+/**
+ * @brief Enables or disables the write protection of the desired sectors, for the first
+ * 1 Mb of the Flash
+ *
+ * @note When the memory read protection level is selected (RDP level = 1),
+ * it is not possible to program or erase the flash sector i if CortexM4
+ * debug features are connected or boot code is executed in RAM, even if nWRPi = 1
+ * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1).
+ *
+ * @param OB_WRP: specifies the sector(s) to be write protected or unprotected.
+ * This parameter can be one of the following values:
+ * @arg OB_WRP: A value between OB_WRP_Sector0 and OB_WRP_Sector11
+ * @arg OB_WRP_Sector_All
+ * @param Newstate: new state of the Write Protection.
+ * This parameter can be: ENABLE or DISABLE.
+ * @retval None
+ */
+void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_OB_WRP(OB_WRP));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ if(NewState != DISABLE)
+ {
+ *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS &= (~OB_WRP);
+ }
+ else
+ {
+ *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS |= (uint16_t)OB_WRP;
+ }
+ }
+}
+
+/**
+ * @brief Enables or disables the write protection of the desired sectors, for the second
+ * 1 Mb of the Flash
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices.
+ *
+ * @note When the memory read out protection is selected (RDP level = 1),
+ * it is not possible to program or erase the flash sector i if CortexM4
+ * debug features are connected or boot code is executed in RAM, even if nWRPi = 1
+ * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1).
+ *
+ * @param OB_WRP: specifies the sector(s) to be write protected or unprotected.
+ * This parameter can be one of the following values:
+ * @arg OB_WRP: A value between OB_WRP_Sector12 and OB_WRP_Sector23
+ * @arg OB_WRP_Sector_All
+ * @param Newstate: new state of the Write Protection.
+ * This parameter can be: ENABLE or DISABLE.
+ * @retval None
+ */
+void FLASH_OB_WRP1Config(uint32_t OB_WRP, FunctionalState NewState)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_OB_WRP(OB_WRP));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ if(NewState != DISABLE)
+ {
+ *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS &= (~OB_WRP);
+ }
+ else
+ {
+ *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS |= (uint16_t)OB_WRP;
+ }
+ }
+}
+
+/**
+ * @brief Select the Protection Mode (SPRMOD).
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx and STM32F401xx/411xE devices.
+ *
+ * @note After PCROP activation, Option Byte modification is not possible.
+ * Exception made for the global Read Out Protection modification level (level1 to level0)
+ * @note Once SPRMOD bit is active unprotection of a protected sector is not possible
+ *
+ * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag
+ *
+ * @note Some Precautions should be taken when activating the PCROP feature :
+ * The active value of nWRPi bits is inverted when PCROP mode is active, this means if SPRMOD = 1
+ * and WRPi = 1 (default value), then the user sector i is read/write protected.
+ * In order to avoid activation of PCROP Mode for undesired sectors, please follow the
+ * below safety sequence :
+ * - Disable PCROP for all Sectors using FLASH_OB_PCROPConfig(OB_PCROP_Sector_All, DISABLE) function
+ * for Bank1 or FLASH_OB_PCROP1Config(OB_PCROP_Sector_All, DISABLE) function for Bank2
+ * - Enable PCROP for the desired Sector i using FLASH_OB_PCROPConfig(Sector i, ENABLE) function
+ * - Activate the PCROP Mode FLASH_OB_PCROPSelectionConfig() function.
+ *
+ * @param OB_PCROP: Select the Protection Mode of nWPRi bits
+ * This parameter can be one of the following values:
+ * @arg OB_PcROP_Disable: nWRPi control the write protection of respective user sectors.
+ * @arg OB_PcROP_Enable: nWRPi control the read&write protection (PCROP) of respective user sectors.
+ * @retval None
+ */
+void FLASH_OB_PCROPSelectionConfig(uint8_t OB_PcROP)
+{
+ uint8_t optiontmp = 0xFF;
+
+ /* Check the parameters */
+ assert_param(IS_OB_PCROP_SELECT(OB_PcROP));
+
+ /* Mask SPRMOD bit */
+ optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F);
+ /* Update Option Byte */
+ *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PcROP | optiontmp);
+
+}
+
+/**
+ * @brief Enables or disables the read/write protection (PCROP) of the desired
+ * sectors, for the first 1 MB of the Flash.
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx , STM32F401xx/411xE
+ * and STM32F412xG devices.
+ *
+ * @param OB_PCROP: specifies the sector(s) to be read/write protected or unprotected.
+ * This parameter can be one of the following values:
+ * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector11 for
+ * STM32F42xxx/43xxx devices and between OB_PCROP_Sector0 and
+ * OB_PCROP_Sector5 for STM32F401xx/411xE devices.
+ * @arg OB_PCROP_Sector_All
+ * @param Newstate: new state of the Write Protection.
+ * This parameter can be: ENABLE or DISABLE.
+ * @retval None
+ */
+void FLASH_OB_PCROPConfig(uint32_t OB_PCROP, FunctionalState NewState)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_OB_PCROP(OB_PCROP));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ if(NewState != DISABLE)
+ {
+ *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS |= (uint16_t)OB_PCROP;
+ }
+ else
+ {
+ *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS &= (~OB_PCROP);
+ }
+ }
+}
+
+/**
+ * @brief Enables or disables the read/write protection (PCROP) of the desired
+ * sectors
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices.
+ *
+ * @param OB_PCROP: specifies the sector(s) to be read/write protected or unprotected.
+ * This parameter can be one of the following values:
+ * @arg OB_PCROP: A value between OB_PCROP_Sector12 and OB_PCROP_Sector23
+ * @arg OB_PCROP_Sector_All
+ * @param Newstate: new state of the Write Protection.
+ * This parameter can be: ENABLE or DISABLE.
+ * @retval None
+ */
+void FLASH_OB_PCROP1Config(uint32_t OB_PCROP, FunctionalState NewState)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_OB_PCROP(OB_PCROP));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ if(NewState != DISABLE)
+ {
+ *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS |= (uint16_t)OB_PCROP;
+ }
+ else
+ {
+ *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS &= (~OB_PCROP);
+ }
+ }
+}
+
+
+/**
+ * @brief Sets the read protection level.
+ * @param OB_RDP: specifies the read protection level.
+ * This parameter can be one of the following values:
+ * @arg OB_RDP_Level_0: No protection
+ * @arg OB_RDP_Level_1: Read protection of the memory
+ * @arg OB_RDP_Level_2: Full chip protection
+ *
+ * /!\ Warning /!\ When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0
+ *
+ * @retval None
+ */
+void FLASH_OB_RDPConfig(uint8_t OB_RDP)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_OB_RDP(OB_RDP));
+
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+ *(__IO uint8_t*)OPTCR_BYTE1_ADDRESS = OB_RDP;
+
+ }
+}
+
+/**
+ * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY.
+ * @param OB_IWDG: Selects the IWDG mode
+ * This parameter can be one of the following values:
+ * @arg OB_IWDG_SW: Software IWDG selected
+ * @arg OB_IWDG_HW: Hardware IWDG selected
+ * @param OB_STOP: Reset event when entering STOP mode.
+ * This parameter can be one of the following values:
+ * @arg OB_STOP_NoRST: No reset generated when entering in STOP
+ * @arg OB_STOP_RST: Reset generated when entering in STOP
+ * @param OB_STDBY: Reset event when entering Standby mode.
+ * This parameter can be one of the following values:
+ * @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY
+ * @arg OB_STDBY_RST: Reset generated when entering in STANDBY
+ * @retval None
+ */
+void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY)
+{
+ uint8_t optiontmp = 0xFF;
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check the parameters */
+ assert_param(IS_OB_IWDG_SOURCE(OB_IWDG));
+ assert_param(IS_OB_STOP_SOURCE(OB_STOP));
+ assert_param(IS_OB_STDBY_SOURCE(OB_STDBY));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ if(status == FLASH_COMPLETE2)
+ {
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
+ /* Mask OPTLOCK, OPTSTRT, BOR_LEV and BFB2 bits */
+ optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x1F);
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F446xx)
+ /* Mask OPTLOCK, OPTSTRT and BOR_LEV bits */
+ optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0F);
+#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F446xx */
+
+ /* Update User Option Byte */
+ *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS = OB_IWDG | (uint8_t)(OB_STDBY | (uint8_t)(OB_STOP | ((uint8_t)optiontmp)));
+ }
+}
+
+/**
+ * @brief Configure the Dual Bank Boot.
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices.
+ *
+ * @param OB_BOOT: specifies the Dual Bank Boot Option byte.
+ * This parameter can be one of the following values:
+ * @arg OB_Dual_BootEnabled: Dual Bank Boot Enable
+ * @arg OB_Dual_BootDisabled: Dual Bank Boot Disabled
+ * @retval None
+ */
+void FLASH_OB_BootConfig(uint8_t OB_BOOT)
+{
+ /* Check the parameters */
+ assert_param(IS_OB_BOOT(OB_BOOT));
+
+ /* Set Dual Bank Boot */
+ *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BFB2);
+ *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= OB_BOOT;
+
+}
+
+/**
+ * @brief Sets the BOR Level.
+ * @param OB_BOR: specifies the Option Bytes BOR Reset Level.
+ * This parameter can be one of the following values:
+ * @arg OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V
+ * @arg OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V
+ * @arg OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V
+ * @arg OB_BOR_OFF: Supply voltage ranges from 1.62 to 2.1 V
+ * @retval None
+ */
+void FLASH_OB_BORConfig(uint8_t OB_BOR)
+{
+ /* Check the parameters */
+ assert_param(IS_OB_BOR(OB_BOR));
+
+ /* Set the BOR Level */
+ *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BOR_LEV);
+ *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= OB_BOR;
+
+}
+
+/**
+ * @brief Launch the option byte loading.
+ * @param None
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_OB_Launch(void)
+{
+ FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Set the OPTSTRT bit in OPTCR register */
+ *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= FLASH_OPTCR_OPTSTRT;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation2();
+
+ return status;
+}
+
+/**
+ * @brief Returns the FLASH User Option Bytes values.
+ * @param None
+ * @retval The FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1)
+ * and RST_STDBY(Bit2).
+ */
+uint8_t FLASH_OB_GetUser(void)
+{
+ /* Return the User Option Byte */
+ return (uint8_t)(FLASH->OPTCR >> 5);
+}
+
+/**
+ * @brief Returns the FLASH Write Protection Option Bytes value.
+ * @param None
+ * @retval The FLASH Write Protection Option Bytes value
+ */
+uint16_t FLASH_OB_GetWRP(void)
+{
+ /* Return the FLASH write protection Register value */
+ return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS));
+}
+
+/**
+ * @brief Returns the FLASH Write Protection Option Bytes value.
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices.
+ *
+ * @param None
+ * @retval The FLASH Write Protection Option Bytes value
+ */
+uint16_t FLASH_OB_GetWRP1(void)
+{
+ /* Return the FLASH write protection Register value */
+ return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS));
+}
+
+/**
+ * @brief Returns the FLASH PC Read/Write Protection Option Bytes value.
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices and STM32F401xx/411xE devices.
+ *
+ * @param None
+ * @retval The FLASH PC Read/Write Protection Option Bytes value
+ */
+uint16_t FLASH_OB_GetPCROP(void)
+{
+ /* Return the FLASH PC Read/write protection Register value */
+ return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS));
+}
+
+/**
+ * @brief Returns the FLASH PC Read/Write Protection Option Bytes value.
+ *
+ * @note This function can be used only for STM32F42xxx/43xxx devices.
+ *
+ * @param None
+ * @retval The FLASH PC Read/Write Protection Option Bytes value
+ */
+uint16_t FLASH_OB_GetPCROP1(void)
+{
+ /* Return the FLASH write protection Register value */
+ return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS));
+}
+
+/**
+ * @brief Returns the FLASH Read Protection level.
+ * @param None
+ * @retval FLASH ReadOut Protection Status:
+ * - SET, when OB_RDP_Level_1 or OB_RDP_Level_2 is set
+ * - RESET, when OB_RDP_Level_0 is set
+ */
+FlagStatus FLASH_OB_GetRDP(void)
+{
+ FlagStatus readstatus = RESET;
+
+ if ((*(__IO uint8_t*)(OPTCR_BYTE1_ADDRESS) != (uint8_t)OB_RDP_Level_0))
+ {
+ readstatus = SET;
+ }
+ else
+ {
+ readstatus = RESET;
+ }
+ return readstatus;
+}
+
+/**
+ * @brief Returns the FLASH BOR level.
+ * @param None
+ * @retval The FLASH BOR level:
+ * - OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V
+ * - OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V
+ * - OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V
+ * - OB_BOR_OFF : Supply voltage ranges from 1.62 to 2.1 V
+ */
+uint8_t FLASH_OB_GetBOR(void)
+{
+ /* Return the FLASH BOR level */
+ return (uint8_t)(*(__IO uint8_t *)(OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0C);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Group4 Interrupts and flags management functions
+ * @brief Interrupts and flags management functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Interrupts and flags management functions #####
+ ===============================================================================
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Enables or disables the specified FLASH interrupts.
+ * @param FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled.
+ * This parameter can be any combination of the following values:
+ * @arg FLASH_IT_ERR: FLASH Error Interrupt
+ * @arg FLASH_IT_EOP: FLASH end of operation Interrupt
+ * @retval None
+ */
+void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_IT(FLASH_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if(NewState != DISABLE)
+ {
+ /* Enable the interrupt sources */
+ FLASH->CR |= FLASH_IT;
+ }
+ else
+ {
+ /* Disable the interrupt sources */
+ FLASH->CR &= ~(uint32_t)FLASH_IT;
+ }
+}
+
+/**
+ * @brief Checks whether the specified FLASH flag is set or not.
+ * @param FLASH_FLAG: specifies the FLASH flag to check.
+ * This parameter can be one of the following values:
+ * @arg FLASH_FLAG_EOP: FLASH End of Operation flag
+ * @arg FLASH_FLAG_OPERR: FLASH operation Error flag
+ * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
+ * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
+ * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
+ * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag
+ * @arg FLASH_FLAG_RDERR: FLASH (PCROP) Read Protection error flag (STM32F42xx/43xxx and STM32F401xx/411xE devices)
+ * @arg FLASH_FLAG_BSY: FLASH Busy flag
+ * @retval The new state of FLASH_FLAG (SET or RESET).
+ */
+FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+ /* Check the parameters */
+ assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG));
+
+ if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ /* Return the new state of FLASH_FLAG (SET or RESET) */
+ return bitstatus;
+}
+
+/**
+ * @brief Clears the FLASH's pending flags.
+ * @param FLASH_FLAG: specifies the FLASH flags to clear.
+ * This parameter can be any combination of the following values:
+ * @arg FLASH_FLAG_EOP: FLASH End of Operation flag
+ * @arg FLASH_FLAG_OPERR: FLASH operation Error flag
+ * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
+ * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
+ * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
+ * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag
+ * @arg FLASH_FLAG_RDERR: FLASH Read Protection error flag (STM32F42xx/43xxx and STM32F401xx/411xE devices)
+ * @retval None
+ */
+void FLASH_ClearFlag(uint32_t FLASH_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG));
+
+ /* Clear the flags */
+ FLASH->SR = FLASH_FLAG;
+}
+
+/**
+ * @brief Returns the FLASH Status.
+ * @param None
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_RD2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_GetStatus(void)
+{
+ FLASH_Status flashstatus = FLASH_COMPLETE2;
+
+ if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY)
+ {
+ flashstatus = FLASH_BUSY2;
+ }
+ else
+ {
+ if((FLASH->SR & FLASH_FLAG_WRPERR) != (uint32_t)0x00)
+ {
+ flashstatus = FLASH_ERROR_WRP2;
+ }
+ else
+ {
+ if((FLASH->SR & FLASH_FLAG_RDERR) != (uint32_t)0x00)
+ {
+ flashstatus = FLASH_ERROR_RD2;
+ }
+ else
+ {
+ if((FLASH->SR & (uint32_t)0xE0) != (uint32_t)0x00)
+ {
+ flashstatus = FLASH_ERROR_PROGRAM2;
+ }
+ else
+ {
+ if((FLASH->SR & FLASH_FLAG_OPERR) != (uint32_t)0x00)
+ {
+ flashstatus = FLASH_ERROR_OPERATION2;
+ }
+ else
+ {
+ flashstatus = FLASH_COMPLETE2;
+ }
+ }
+ }
+ }
+ }
+ /* Return the FLASH Status */
+ return flashstatus;
+}
+
+/**
+ * @brief Waits for a FLASH operation to complete.
+ * @param None
+ * @retval FLASH Status: The returned value can be: FLASH_BUSY2, FLASH_ERROR_PROGRAM2,
+ * FLASH_ERROR_WRP2, FLASH_ERROR_OPERATION2 or FLASH_COMPLETE2.
+ */
+FLASH_Status FLASH_WaitForLastOperation2(void)
+{
+ __IO FLASH_Status status = FLASH_COMPLETE2;
+
+ /* Check for the FLASH Status */
+ status = FLASH_GetStatus();
+
+ /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset.
+ Even if the FLASH operation fails, the BUSY flag will be reset and an error
+ flag will be set */
+ while(status == FLASH_BUSY2)
+ {
+ status = FLASH_GetStatus();
+ }
+ /* Return the operation status */
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/FlashWriter/stm32f4xx_flash.h Wed Apr 05 20:54:16 2017 +0000
@@ -0,0 +1,425 @@
+/**
+ ******************************************************************************
+ * @file stm32f4xx_flash.h
+ * @author MCD Application Team
+ * @version V1.7.1
+ * @date 20-May-2016
+ * @brief This file contains all the functions prototypes for the FLASH
+ * firmware library.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
+ *
+ * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+ * You may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at:
+ *
+ * http://www.st.com/software_license_agreement_liberty_v2
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_FLASH_H
+#define __STM32F4xx_FLASH_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+ * @{
+ */
+
+/** @addtogroup FLASH
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/**
+ * @brief FLASH Status
+ */
+typedef enum
+{
+ FLASH_BUSY2 = 1,
+ FLASH_ERROR_RD2,
+ FLASH_ERROR_PGS2,
+ FLASH_ERROR_PGP2,
+ FLASH_ERROR_PGA2,
+ FLASH_ERROR_WRP2,
+ FLASH_ERROR_PROGRAM2,
+ FLASH_ERROR_OPERATION2,
+ FLASH_COMPLETE2
+}FLASH_Status;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup FLASH_Exported_Constants
+ * @{
+ */
+
+/** @defgroup Flash_Latency
+ * @{
+ */
+#define FLASH_Latency_0 ((uint8_t)0x0000) /*!< FLASH Zero Latency cycle */
+#define FLASH_Latency_1 ((uint8_t)0x0001) /*!< FLASH One Latency cycle */
+#define FLASH_Latency_2 ((uint8_t)0x0002) /*!< FLASH Two Latency cycles */
+#define FLASH_Latency_3 ((uint8_t)0x0003) /*!< FLASH Three Latency cycles */
+#define FLASH_Latency_4 ((uint8_t)0x0004) /*!< FLASH Four Latency cycles */
+#define FLASH_Latency_5 ((uint8_t)0x0005) /*!< FLASH Five Latency cycles */
+#define FLASH_Latency_6 ((uint8_t)0x0006) /*!< FLASH Six Latency cycles */
+#define FLASH_Latency_7 ((uint8_t)0x0007) /*!< FLASH Seven Latency cycles */
+#define FLASH_Latency_8 ((uint8_t)0x0008) /*!< FLASH Eight Latency cycles */
+#define FLASH_Latency_9 ((uint8_t)0x0009) /*!< FLASH Nine Latency cycles */
+#define FLASH_Latency_10 ((uint8_t)0x000A) /*!< FLASH Ten Latency cycles */
+#define FLASH_Latency_11 ((uint8_t)0x000B) /*!< FLASH Eleven Latency cycles */
+#define FLASH_Latency_12 ((uint8_t)0x000C) /*!< FLASH Twelve Latency cycles */
+#define FLASH_Latency_13 ((uint8_t)0x000D) /*!< FLASH Thirteen Latency cycles */
+#define FLASH_Latency_14 ((uint8_t)0x000E) /*!< FLASH Fourteen Latency cycles */
+#define FLASH_Latency_15 ((uint8_t)0x000F) /*!< FLASH Fifteen Latency cycles */
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Voltage_Range
+ * @{
+ */
+#define VoltageRange_1 ((uint8_t)0x00) /*!< Device operating range: 1.8V to 2.1V */
+#define VoltageRange_2 ((uint8_t)0x01) /*!<Device operating range: 2.1V to 2.7V */
+#define VoltageRange_3 ((uint8_t)0x02) /*!<Device operating range: 2.7V to 3.6V */
+#define VoltageRange_4 ((uint8_t)0x03) /*!<Device operating range: 2.7V to 3.6V + External Vpp */
+
+/*
+#define IS_VOLTAGERANGE(RANGE)(((RANGE) == VoltageRange_1) || \
+ ((RANGE) == VoltageRange_2) || \
+ ((RANGE) == VoltageRange_3) || \
+ ((RANGE) == VoltageRange_4))
+*/
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Sectors
+ * @{
+ */
+#define FLASH_Sector_0 ((uint16_t)0x0000) /*!< Sector Number 0 */
+#define FLASH_Sector_1 ((uint16_t)0x0008) /*!< Sector Number 1 */
+#define FLASH_Sector_2 ((uint16_t)0x0010) /*!< Sector Number 2 */
+#define FLASH_Sector_3 ((uint16_t)0x0018) /*!< Sector Number 3 */
+#define FLASH_Sector_4 ((uint16_t)0x0020) /*!< Sector Number 4 */
+#define FLASH_Sector_5 ((uint16_t)0x0028) /*!< Sector Number 5 */
+#define FLASH_Sector_6 ((uint16_t)0x0030) /*!< Sector Number 6 */
+#define FLASH_Sector_7 ((uint16_t)0x0038) /*!< Sector Number 7 */
+#define FLASH_Sector_8 ((uint16_t)0x0040) /*!< Sector Number 8 */
+#define FLASH_Sector_9 ((uint16_t)0x0048) /*!< Sector Number 9 */
+#define FLASH_Sector_10 ((uint16_t)0x0050) /*!< Sector Number 10 */
+#define FLASH_Sector_11 ((uint16_t)0x0058) /*!< Sector Number 11 */
+#define FLASH_Sector_12 ((uint16_t)0x0080) /*!< Sector Number 12 */
+#define FLASH_Sector_13 ((uint16_t)0x0088) /*!< Sector Number 13 */
+#define FLASH_Sector_14 ((uint16_t)0x0090) /*!< Sector Number 14 */
+#define FLASH_Sector_15 ((uint16_t)0x0098) /*!< Sector Number 15 */
+#define FLASH_Sector_16 ((uint16_t)0x00A0) /*!< Sector Number 16 */
+#define FLASH_Sector_17 ((uint16_t)0x00A8) /*!< Sector Number 17 */
+#define FLASH_Sector_18 ((uint16_t)0x00B0) /*!< Sector Number 18 */
+#define FLASH_Sector_19 ((uint16_t)0x00B8) /*!< Sector Number 19 */
+#define FLASH_Sector_20 ((uint16_t)0x00C0) /*!< Sector Number 20 */
+#define FLASH_Sector_21 ((uint16_t)0x00C8) /*!< Sector Number 21 */
+#define FLASH_Sector_22 ((uint16_t)0x00D0) /*!< Sector Number 22 */
+#define FLASH_Sector_23 ((uint16_t)0x00D8) /*!< Sector Number 23 */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx) || defined (STM32F469_479xx)
+#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x081FFFFF)) ||\
+ (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) <= 0x1FFF7A0F)))
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */
+
+#if defined (STM32F40_41xxx) || defined(STM32F412xG)
+#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x080FFFFF)) ||\
+ (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) <= 0x1FFF7A0F)))
+#endif /* STM32F40_41xxx || STM32F412xG */
+
+#if defined (STM32F401xx)
+#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x0803FFFF)) ||\
+ (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) <= 0x1FFF7A0F)))
+#endif /* STM32F401xx */
+
+#if defined (STM32F411xE) || defined (STM32F446xx)
+//#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x0807FFFF)) ||\
+// (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) <= 0x1FFF7A0F)))
+#endif /* STM32F411xE || STM32F446xx */
+
+#if defined (STM32F410xx)
+#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x0801FFFF)) ||\
+ (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) <= 0x1FFF7A0F)))
+#endif /* STM32F410xx */
+
+/**
+ * @}
+ */
+
+/** @defgroup Option_Bytes_Write_Protection
+ * @{
+ */
+#define OB_WRP_Sector_0 ((uint32_t)0x00000001) /*!< Write protection of Sector0 */
+#define OB_WRP_Sector_1 ((uint32_t)0x00000002) /*!< Write protection of Sector1 */
+#define OB_WRP_Sector_2 ((uint32_t)0x00000004) /*!< Write protection of Sector2 */
+#define OB_WRP_Sector_3 ((uint32_t)0x00000008) /*!< Write protection of Sector3 */
+#define OB_WRP_Sector_4 ((uint32_t)0x00000010) /*!< Write protection of Sector4 */
+#define OB_WRP_Sector_5 ((uint32_t)0x00000020) /*!< Write protection of Sector5 */
+#define OB_WRP_Sector_6 ((uint32_t)0x00000040) /*!< Write protection of Sector6 */
+#define OB_WRP_Sector_7 ((uint32_t)0x00000080) /*!< Write protection of Sector7 */
+#define OB_WRP_Sector_8 ((uint32_t)0x00000100) /*!< Write protection of Sector8 */
+#define OB_WRP_Sector_9 ((uint32_t)0x00000200) /*!< Write protection of Sector9 */
+#define OB_WRP_Sector_10 ((uint32_t)0x00000400) /*!< Write protection of Sector10 */
+#define OB_WRP_Sector_11 ((uint32_t)0x00000800) /*!< Write protection of Sector11 */
+#define OB_WRP_Sector_12 ((uint32_t)0x00000001) /*!< Write protection of Sector12 */
+#define OB_WRP_Sector_13 ((uint32_t)0x00000002) /*!< Write protection of Sector13 */
+#define OB_WRP_Sector_14 ((uint32_t)0x00000004) /*!< Write protection of Sector14 */
+#define OB_WRP_Sector_15 ((uint32_t)0x00000008) /*!< Write protection of Sector15 */
+#define OB_WRP_Sector_16 ((uint32_t)0x00000010) /*!< Write protection of Sector16 */
+#define OB_WRP_Sector_17 ((uint32_t)0x00000020) /*!< Write protection of Sector17 */
+#define OB_WRP_Sector_18 ((uint32_t)0x00000040) /*!< Write protection of Sector18 */
+#define OB_WRP_Sector_19 ((uint32_t)0x00000080) /*!< Write protection of Sector19 */
+#define OB_WRP_Sector_20 ((uint32_t)0x00000100) /*!< Write protection of Sector20 */
+#define OB_WRP_Sector_21 ((uint32_t)0x00000200) /*!< Write protection of Sector21 */
+#define OB_WRP_Sector_22 ((uint32_t)0x00000400) /*!< Write protection of Sector22 */
+#define OB_WRP_Sector_23 ((uint32_t)0x00000800) /*!< Write protection of Sector23 */
+#define OB_WRP_Sector_All ((uint32_t)0x00000FFF) /*!< Write protection of all Sectors */
+
+#define IS_OB_WRP(SECTOR)((((SECTOR) & (uint32_t)0xFFFFF000) == 0x00000000) && ((SECTOR) != 0x00000000))
+/**
+ * @}
+ */
+
+/** @defgroup Selection_Protection_Mode
+ * @{
+ */
+#define OB_PcROP_Disable ((uint8_t)0x00) /*!< Disabled PcROP, nWPRi bits used for Write Protection on sector i */
+#define OB_PcROP_Enable ((uint8_t)0x80) /*!< Enable PcROP, nWPRi bits used for PCRoP Protection on sector i */
+
+/**
+ * @}
+ */
+
+/** @defgroup Option_Bytes_PC_ReadWrite_Protection
+ * @{
+ */
+#define OB_PCROP_Sector_0 ((uint32_t)0x00000001) /*!< PC Read/Write protection of Sector0 */
+#define OB_PCROP_Sector_1 ((uint32_t)0x00000002) /*!< PC Read/Write protection of Sector1 */
+#define OB_PCROP_Sector_2 ((uint32_t)0x00000004) /*!< PC Read/Write protection of Sector2 */
+#define OB_PCROP_Sector_3 ((uint32_t)0x00000008) /*!< PC Read/Write protection of Sector3 */
+#define OB_PCROP_Sector_4 ((uint32_t)0x00000010) /*!< PC Read/Write protection of Sector4 */
+#define OB_PCROP_Sector_5 ((uint32_t)0x00000020) /*!< PC Read/Write protection of Sector5 */
+#define OB_PCROP_Sector_6 ((uint32_t)0x00000040) /*!< PC Read/Write protection of Sector6 */
+#define OB_PCROP_Sector_7 ((uint32_t)0x00000080) /*!< PC Read/Write protection of Sector7 */
+#define OB_PCROP_Sector_8 ((uint32_t)0x00000100) /*!< PC Read/Write protection of Sector8 */
+#define OB_PCROP_Sector_9 ((uint32_t)0x00000200) /*!< PC Read/Write protection of Sector9 */
+#define OB_PCROP_Sector_10 ((uint32_t)0x00000400) /*!< PC Read/Write protection of Sector10 */
+#define OB_PCROP_Sector_11 ((uint32_t)0x00000800) /*!< PC Read/Write protection of Sector11 */
+#define OB_PCROP_Sector_12 ((uint32_t)0x00000001) /*!< PC Read/Write protection of Sector12 */
+#define OB_PCROP_Sector_13 ((uint32_t)0x00000002) /*!< PC Read/Write protection of Sector13 */
+#define OB_PCROP_Sector_14 ((uint32_t)0x00000004) /*!< PC Read/Write protection of Sector14 */
+#define OB_PCROP_Sector_15 ((uint32_t)0x00000008) /*!< PC Read/Write protection of Sector15 */
+#define OB_PCROP_Sector_16 ((uint32_t)0x00000010) /*!< PC Read/Write protection of Sector16 */
+#define OB_PCROP_Sector_17 ((uint32_t)0x00000020) /*!< PC Read/Write protection of Sector17 */
+#define OB_PCROP_Sector_18 ((uint32_t)0x00000040) /*!< PC Read/Write protection of Sector18 */
+#define OB_PCROP_Sector_19 ((uint32_t)0x00000080) /*!< PC Read/Write protection of Sector19 */
+#define OB_PCROP_Sector_20 ((uint32_t)0x00000100) /*!< PC Read/Write protection of Sector20 */
+#define OB_PCROP_Sector_21 ((uint32_t)0x00000200) /*!< PC Read/Write protection of Sector21 */
+#define OB_PCROP_Sector_22 ((uint32_t)0x00000400) /*!< PC Read/Write protection of Sector22 */
+#define OB_PCROP_Sector_23 ((uint32_t)0x00000800) /*!< PC Read/Write protection of Sector23 */
+#define OB_PCROP_Sector_All ((uint32_t)0x00000FFF) /*!< PC Read/Write protection of all Sectors */
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Option_Bytes_Read_Protection
+ * @{
+ */
+#define OB_RDP_Level_0 ((uint8_t)0xAA)
+#define OB_RDP_Level_1 ((uint8_t)0x55)
+/*#define OB_RDP_Level_2 ((uint8_t)0xCC)*/ /*!< Warning: When enabling read protection level 2
+ it's no more possible to go back to level 1 or 0 */
+#define IS_OB_RDP(LEVEL) (((LEVEL) == OB_RDP_Level_0)||\
+ ((LEVEL) == OB_RDP_Level_1))/*||\
+ ((LEVEL) == OB_RDP_Level_2))*/
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Option_Bytes_IWatchdog
+ * @{
+ */
+
+#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Option_Bytes_nRST_STOP
+ * @{
+ */
+#define OB_STOP_NoRST ((uint8_t)0x40) /*!< No reset generated when entering in STOP */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup FLASH_Option_Bytes_nRST_STDBY
+ * @{
+ */
+#define OB_STDBY_NoRST ((uint8_t)0x80) /*!< No reset generated when entering in STANDBY */
+//#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */
+//#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_BOR_Reset_Level
+ * @{
+ */
+
+#define IS_OB_BOR(LEVEL) (((LEVEL) == OB_BOR_LEVEL1) || ((LEVEL) == OB_BOR_LEVEL2) ||\
+ ((LEVEL) == OB_BOR_LEVEL3) || ((LEVEL) == OB_BOR_OFF))
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Dual_Boot
+ * @{
+ */
+#define OB_Dual_BootEnabled ((uint8_t)0x10) /*!< Dual Bank Boot Enable */
+#define OB_Dual_BootDisabled ((uint8_t)0x00) /*!< Dual Bank Boot Disable, always boot on User Flash */
+#define IS_OB_BOOT(BOOT) (((BOOT) == OB_Dual_BootEnabled) || ((BOOT) == OB_Dual_BootDisabled))
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Interrupts
+ * @{
+ */
+
+#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFCFFFFFF) == 0x00000000) && ((IT) != 0x00000000))
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Flags
+ * @{
+ */
+
+#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFE0C) == 0x00000000) && ((FLAG) != 0x00000000))
+#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_EOP) || ((FLAG) == FLASH_FLAG_OPERR) || \
+ ((FLAG) == FLASH_FLAG_WRPERR) || ((FLAG) == FLASH_FLAG_PGAERR) || \
+ ((FLAG) == FLASH_FLAG_PGPERR) || ((FLAG) == FLASH_FLAG_PGSERR) || \
+ ((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_RDERR))
+
+/**
+ * @brief ACR register byte 0 (Bits[7:0]) base address
+ */
+//#define ACR_BYTE0_ADDRESS ((uint32_t)0x40023C00)
+/**
+ * @brief OPTCR register byte 0 (Bits[7:0]) base address
+ */
+//#define OPTCR_BYTE0_ADDRESS ((uint32_t)0x40023C14)
+/**
+ * @brief OPTCR register byte 1 (Bits[15:8]) base address
+ */
+//#define OPTCR_BYTE1_ADDRESS ((uint32_t)0x40023C15)
+/**
+ * @brief OPTCR register byte 2 (Bits[23:16]) base address
+ */
+//#define OPTCR_BYTE2_ADDRESS ((uint32_t)0x40023C16)
+/**
+ * @brief OPTCR register byte 3 (Bits[31:24]) base address
+ */
+//#define OPTCR_BYTE3_ADDRESS ((uint32_t)0x40023C17)
+
+/**
+ * @brief OPTCR1 register byte 0 (Bits[7:0]) base address
+ */
+#define OPTCR1_BYTE2_ADDRESS ((uint32_t)0x40023C1A)
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/* FLASH Interface configuration functions ************************************/
+void FLASH_SetLatency(uint32_t FLASH_Latency);
+void FLASH_PrefetchBufferCmd(FunctionalState NewState);
+void FLASH_InstructionCacheCmd(FunctionalState NewState);
+void FLASH_DataCacheCmd(FunctionalState NewState);
+void FLASH_InstructionCacheReset(void);
+void FLASH_DataCacheReset(void);
+
+/* FLASH Memory Programming functions *****************************************/
+void FLASH_Unlock(void);
+void FLASH_Lock(void);
+FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange);
+FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange);
+FLASH_Status FLASH_EraseAllBank1Sectors(uint8_t VoltageRange);
+FLASH_Status FLASH_EraseAllBank2Sectors(uint8_t VoltageRange);
+FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data);
+FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data);
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data);
+FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data);
+
+/* Option Bytes Programming functions *****************************************/
+void FLASH_OB_Unlock(void);
+void FLASH_OB_Lock(void);
+void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState);
+void FLASH_OB_WRP1Config(uint32_t OB_WRP, FunctionalState NewState);
+void FLASH_OB_PCROPSelectionConfig(uint8_t OB_PcROP);
+void FLASH_OB_PCROPConfig(uint32_t OB_PCROP, FunctionalState NewState);
+void FLASH_OB_PCROP1Config(uint32_t OB_PCROP, FunctionalState NewState);
+void FLASH_OB_RDPConfig(uint8_t OB_RDP);
+void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY);
+void FLASH_OB_BORConfig(uint8_t OB_BOR);
+void FLASH_OB_BootConfig(uint8_t OB_BOOT);
+FLASH_Status FLASH_OB_Launch(void);
+uint8_t FLASH_OB_GetUser(void);
+uint16_t FLASH_OB_GetWRP(void);
+uint16_t FLASH_OB_GetWRP1(void);
+uint16_t FLASH_OB_GetPCROP(void);
+uint16_t FLASH_OB_GetPCROP1(void);
+FlagStatus FLASH_OB_GetRDP(void);
+uint8_t FLASH_OB_GetBOR(void);
+
+/* Interrupts and flags management functions **********************************/
+void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState);
+FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG);
+void FLASH_ClearFlag(uint32_t FLASH_FLAG);
+FLASH_Status FLASH_GetStatus(void);
+FLASH_Status FLASH_WaitForLastOperation2(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_FLASH_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
\ No newline at end of file
--- a/PositionSensor/PositionSensor.cpp Fri Mar 31 18:24:46 2017 +0000
+++ b/PositionSensor/PositionSensor.cpp Wed Apr 05 20:54:16 2017 +0000
@@ -43,6 +43,7 @@
MechPosition = position - MechOffset;
float elec = ((6.28318530718f/(float)_CPR) * (float) ((_ppairs*angle)%_CPR)) - ElecOffset;
if(elec < 0) elec += 6.28318530718f;
+ else if(elec > 6.28318530718f) elec -= 6.28318530718f ;
ElecPosition = elec;
float vel;
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/PreferenceWriter/PreferenceWriter.h Wed Apr 05 20:54:16 2017 +0000
@@ -0,0 +1,23 @@
+#ifndef __PREFERENCE_WRITER_H
+#define __PREFERENCE_WRITER_H
+
+#include "mbed.h"
+#include "FlashWriter.h"
+
+class PreferenceWriter {
+public:
+ PreferenceWriter(uint32_t sector);
+ void open();
+ bool ready();
+ void write(int x, int index);
+ void write(float x, int index);
+ void flush();
+ void load();
+ void close();
+private:
+ FlashWriter *writer;
+ uint32_t __sector;
+ bool __ready;
+};
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/PreferenceWriter/PrefrenceWriter.cpp Wed Apr 05 20:54:16 2017 +0000
@@ -0,0 +1,51 @@
+#include "PreferenceWriter.h"
+#include "FlashWriter.h"
+#include "user_config.h"
+#include "mbed.h"
+
+PreferenceWriter::PreferenceWriter(uint32_t sector) {
+ writer = new FlashWriter(sector);
+ __sector = sector;
+ __ready = false;
+}
+
+void PreferenceWriter::open() {
+ writer->open();
+ __ready = true;
+}
+
+bool PreferenceWriter::ready() {
+ return __ready;
+}
+
+void PreferenceWriter::write(int x, int index) {
+ __int_reg[index] = x;
+}
+
+void PreferenceWriter::write(float x, int index) {
+ __float_reg[index] = x;
+}
+
+void PreferenceWriter::flush() {
+ int offs;
+ for (offs = 0; offs < 256; offs++) {
+ writer->write(offs, __int_reg[offs]);
+ }
+ for (; offs < 320; offs++) {
+ writer->write(offs, __float_reg[offs - 256]);
+ }
+}
+
+void PreferenceWriter::load() {
+ int offs;
+ for (offs = 0; offs < 256; offs++) {
+ __int_reg[offs] = flashReadInt(__sector, offs);
+ }
+ for(; offs < 320; offs++) {
+ __float_reg[offs - 256] = flashReadFloat(__sector, offs);
+ }
+}
+
+void PreferenceWriter::close() {
+ writer->close();
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/StateMachine/state_machine.cpp Wed Apr 05 20:54:16 2017 +0000
@@ -0,0 +1,20 @@
+#include "state_machine.h"
+
+/*
+void menu_state(void){
+ printf("\n\r\n\r\n\r");
+ printf(" Comands:\n\r");
+ printf(" t - Torque Mode\n\r");
+ printf(" p - PD Mode\n\r");
+ printf(" c - Calibrate Encoder\n\r");
+ printf(" s - Setup\n\r");
+
+ }
+
+
+void calibration_state(void){
+ printf("Beginning Calibration\n\r");
+
+ }
+
+ */
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/StateMachine/state_machine.h Wed Apr 05 20:54:16 2017 +0000 @@ -0,0 +1,11 @@ +#ifndef STATE_MACHINE_H +#define STATE_MACHINE_H + +#include "structs.h" +#include "mbed.h" +/* +void menu_state(void); +void calibration_state(void); +*/ + +#endif
--- a/main.cpp Fri Mar 31 18:24:46 2017 +0000
+++ b/main.cpp Wed Apr 05 20:54:16 2017 +0000
@@ -4,17 +4,21 @@
/// Written for the STM32F446, but can be implemented on other STM32 MCU's with some further register-diddling
+#define REST_MODE 0
+#define CALIBRATION_MODE 1
+#define TORQUE_MODE 2
+#define PD_MODE 3
+#define SETUP_MODE 4
+#define ENCODER_MODE 5
const unsigned int BOARDNUM = 0x2;
-
//const unsigned int a_id =
-
const unsigned int TX_ID = 0x0100;
-
const unsigned int cmd_ID = (BOARDNUM<<8) + 0x7;
-
+float __float_reg[64];
+int __int_reg[256];
#include "CANnucleo.h"
#include "mbed.h"
@@ -23,10 +27,19 @@
#include "foc.h"
#include "calibration.h"
#include "hw_setup.h"
-#include "math_ops.h"
+#include "math_ops.h"
#include "current_controller_config.h"
#include "hw_config.h"
#include "motor_config.h"
+#include "stm32f4xx_flash.h"
+#include "FlashWriter.h"
+#include "user_config.h"
+#include "PreferenceWriter.h"
+//#include "state_machine.h"
+
+
+
+PreferenceWriter prefs(6);
GPIOStruct gpio;
ControllerStruct controller;
@@ -35,7 +48,7 @@
-CANnucleo::CAN can(PB_8, PB_9); // CAN Rx pin name, CAN Tx pin name
+CANnucleo::CAN can(PB_8, PB_9); // CAN Rx pin name, CAN Tx pin name
CANnucleo::CANMessage rxMsg;
CANnucleo::CANMessage txMsg;
int ledState;
@@ -68,160 +81,218 @@
void readCAN(void){
if(msgAvailable) {
- msgAvailable = false; // reset flag for next use
- can.read(rxMsg); // read message into Rx message storage
+ msgAvailable = false; // reset flag for next use
+ can.read(rxMsg); // read message into Rx message storage
// Filtering performed by software:
- if(rxMsg.id == cmd_ID) { // See comments in CAN.cpp for filtering performed by hardware
- rxMsg >> canCmd;
- } // extract first data item
+ if(rxMsg.id == cmd_ID) { // See comments in CAN.cpp for filtering performed by hardware
+ rxMsg >> canCmd; // extract first data item
+ }
}
- }
+ }
void cancontroller(void){
//printf("%d\n\r", canCmd);
readCAN();
//sendCMD(TX_ID, canCmd);
-
- //sendCMD(TX_ID+b_ID, b1);
- //sendCMD(TX_ID+c_ID, c1);
+
}
Serial pc(PA_2, PA_3);
-PositionSensorAM5147 spi(16384, -0.4658, NPP); ///1 I really need an eeprom or something to store this....
+PositionSensorAM5147 spi(16384, 0.0, NPP);
PositionSensorEncoder encoder(4096, 0, 21);
-int count = 0;
-int mode = 0;
+volatile int count = 0;
+volatile int state = REST_MODE;
+volatile int state_change;
-
-float velocity_estimate(void){
- velocity.vel_2 = encoder.GetMechVelocity();
- velocity.vel_1 = spi.GetMechVelocity();
+void enter_menu_state(void){
+ printf("\n\r\n\r\n\r");
+ printf(" Commands:\n\r");
+ printf(" t - Torque Mode\n\r");
+ printf(" p - PD Mode\n\r");
+ printf(" c - Calibrate Encoder\n\r");
+ printf(" s - Setup\n\r");
+ printf(" e - Display Encoder\n\r");
+ printf(" esc - Exit to Menu\n\r");
+ state_change = 0;
+ }
- velocity.ts = .01f;
- velocity.vel_1_est = velocity.ts*velocity.vel_1 + (1-velocity.ts)*velocity.vel_1_est; //LPF
- velocity.vel_2_est = (1-velocity.ts)*(velocity.vel_2_est + velocity.vel_2 - velocity.vel_2_old); //HPF
- velocity.est = velocity.vel_1_est + velocity.vel_2_est;
+void enter_torque_mode(void){
+ controller.mode = 2;
+ controller.i_d_ref = 0;
+ controller.i_q_ref = 0;
+ reset_foc(&controller); //resets integrators, and other control loop parameters
+ gpio.enable->write(1);
+ GPIOC->ODR ^= (1 << 5); //turn on status LED
+ }
- velocity.vel_1_old = velocity.vel_1;
- velocity.vel_2_old = velocity.vel_2;
- return velocity.est;
+void calibrate(void){
+ gpio.enable->write(1);
+ GPIOC->ODR ^= (1 << 5);
+ order_phases(&spi, &gpio, &controller, &prefs);
+ calibrate(&spi, &gpio, &controller, &prefs);
+ GPIOC->ODR ^= (1 << 5);
+ wait(.2);
+ gpio.enable->write(0);
+ printf("\n\r Calibration complete. Press 'esc' to return to menu\n\r");
+ state_change = 0;
+
+ }
+
+void print_encoder(void){
+ spi.Sample();
+ wait(.001);
+ printf(" Mechanical Angle: %f Electrical Angle: %f Raw: %d\n\r", spi.GetMechPosition(), spi.GetElecPosition(), spi.GetRawPosition());
+ wait(.05);
}
-// Current Sampling Interrupt
+/// Current Sampling Interrupt ///
+/// This runs at 40 kHz, regardless of of the mode the controller is in ///
extern "C" void TIM1_UP_TIM10_IRQHandler(void) {
if (TIM1->SR & TIM_SR_UIF ) {
//toggle = 1;
- count++;
- ADC1->CR2 |= 0x40000000; //Begin sample and conversion
+
+ ///Sample current always ///
+ ADC1->CR2 |= 0x40000000; //Begin sample and conversion
//volatile int delay;
//for (delay = 0; delay < 55; delay++);
+ controller.adc2_raw = ADC2->DR;
+ controller.adc1_raw = ADC1->DR;
+ ///
- if(controller.mode == 2){
- controller.adc2_raw = ADC2->DR;
- controller.adc1_raw = ADC1->DR;
-
- //toggle = 0;
+ /// Check state machine state, and run the appropriate function ///
+ //printf("%d\n\r", state);
+ switch(state){
+ case REST_MODE: // Do nothing until
+ if(state_change){
+ enter_menu_state();
+ }
+ break;
- spi.Sample();
- controller.theta_elec = spi.GetElecPosition();
- commutate(&controller, &gpio, controller.theta_elec);
- }
-
-
- //controller.dtheta_mech = spi.GetMechVelocity();
- //controller.dtheta_elec = encoder.GetElecVelocity();
- //ontroller.dtheta_mech = encoder.GetMechVelocity();
- //controller.i_q_ref = 2.0f*controller.dtheta_mech;
-
-
- //float v1 = encoder.GetMechVelocity();
- //float v2 = spi.GetMechVelocity();
-
-
- if(count > 100){
- count = 0;
- //for (int i = 1; i<16; i++){
- //pc.printf("%d\n\r ", spi.GetRawPosition());
- // }
- //pc.printf("\n\r");
- //pc.printf("%.4f %.4f %.4f\n\r",velocity.vel_1 ,velocity.vel_2, velocity.est );
-
- }
-
+ case CALIBRATION_MODE: // Run encoder calibration procedure
+ if(state_change){
+ calibrate();
+ }
+ break;
+
+ case TORQUE_MODE: // Run torque control
+ count++;
+ controller.theta_elec = spi.GetElecPosition();
+ commutate(&controller, &gpio, controller.theta_elec); // Run current loop
+ spi.Sample(); // Sample position sensor
+ if(count > 100){
+ count = 0;
+ readCAN();
+ controller.i_q_ref = ((float)(canCmd-1000))/100;
+ //pc.printf("%f\n\r ", controller.theta_elec);
+ }
+ break;
+
+ case PD_MODE:
+ break;
+ case SETUP_MODE:
+ if(state_change){
+ printf("\n\r Configuration Menu \n\r\n\n");
+ state_change = 0;
+ }
+ break;
+ case ENCODER_MODE:
+ print_encoder();
+ break;
+ }
+
+
}
- TIM1->SR = 0x0; // reset the status register
+ TIM1->SR = 0x0; // reset the status register
}
-
-void enter_torque_mode(void){
- controller.mode = 2;
- TIM1->CR1 ^= TIM_CR1_UDIS; //enable interrupts
- controller.i_d_ref = 0;
- controller.i_q_ref = 1;
- reset_foc(&controller); //resets integrators, and other control loop parameters
- gpio.enable->write(1);
- GPIOC->ODR ^= (1 << 5); //turn on LED
+/// Manage state machine with commands from serial terminal or configurator gui ///
+void serial_interrupt(void){
+ while(pc.readable()){
+ char c = pc.getc();
+ if(c == 27){
+ state = REST_MODE;
+ state_change = 1;
+ }
+ else if(state == REST_MODE){
+ switch (c){
+ case 'c':
+ state = CALIBRATION_MODE;
+ state_change = 1;
+ break;
+ case 't':
+ state = TORQUE_MODE;
+ state_change = 1;
+ break;
+ case 'e':
+ state = ENCODER_MODE;
+ state_change = 1;
+ break;
+ case 's':
+ state = SETUP_MODE;
+ state_change = 1;
+ break;
+
+ }
+ }
}
-
-void enter_calibration_mode(void){
- controller.mode = 1;
- TIM1->CR1 ^= TIM_CR1_UDIS;
- gpio.enable->write(1);
- GPIOC->ODR ^= (1 << 5);
- //calibrate_encoder(&spi);
- order_phases(&spi, &gpio);
- calibrate(&spi, &gpio);
- GPIOC->ODR ^= (1 << 5);
- wait(.2);
- gpio.enable->write(0);
- TIM1->CR1 ^= TIM_CR1_UDIS;
- controller.mode = 0;
}
-
int main() {
+
+
controller.v_bus = V_BUS;
controller.mode = 0;
//spi.ZeroPosition();
- Init_All_HW(&gpio); // Setup PWM, ADC, GPIO
+ Init_All_HW(&gpio); // Setup PWM, ADC, GPIO
wait(.1);
//TIM1->CR1 |= TIM_CR1_UDIS;
- gpio.enable->write(1);
- gpio.pwm_u->write(1.0f); //write duty cycles
+ gpio.enable->write(1); // Enable gate drive
+ gpio.pwm_u->write(1.0f); // Write duty cycles
gpio.pwm_v->write(1.0f);
gpio.pwm_w->write(1.0f);
- zero_current(&controller.adc1_offset, &controller.adc2_offset); //Measure current sensor zero-offset
+ zero_current(&controller.adc1_offset, &controller.adc2_offset); // Measure current sensor zero-offset
//gpio.enable->write(0);
- reset_foc(&controller);
+ reset_foc(&controller); // Reset current controller
- //TIM1->CR1 ^= TIM_CR1_UDIS; //enable interrupt
- //gpio.enable->write(1);
- //gpio.pwm_u->write(1.0f - .05f); //write duty cycles
- //gpio.pwm_v->write(1.0f - .05f);
- //gpio.pwm_w->write(1.0f - .1f);
+ TIM1->CR1 ^= TIM_CR1_UDIS; //enable interrupt
wait(.1);
- NVIC_SetPriority(TIM5_IRQn, 2); // set interrupt priority
+ NVIC_SetPriority(TIM5_IRQn, 2); // set interrupt priority
- can.frequency(1000000); // set bit rate to 1Mbps
- can.attach(&onMsgReceived); // attach 'CAN receive-complete' interrupt handler
+ can.frequency(1000000); // set bit rate to 1Mbps
+ can.attach(&onMsgReceived); // attach 'CAN receive-complete' interrupt handler
can.filter(0x020 << 25, 0xF0000004, CANAny, 0);
- pc.baud(115200);
+
+ prefs.load();
+ spi.SetElecOffset(E_OFFSET);
+ int lut[128] = {0};
+ memcpy(&lut, &ENCODER_LUT, sizeof(lut));
+ spi.WriteLUT(lut);
+
+ pc.baud(115200); // set serial baud rate
wait(.01);
- pc.printf("HobbyKing Cheetah v1.1\n\r");
- pc.printf("ADC1 Offset: %d ADC2 Offset: %d", controller.adc1_offset, controller.adc2_offset);
+ pc.printf("\n\r\n\r HobbyKing Cheetah\n\r\n\r");
wait(.01);
-
+ printf("\n\r Debug Info:\n\r");
+ printf(" ADC1 Offset: %d ADC2 Offset: %d\n\r", controller.adc1_offset, controller.adc2_offset);
+ printf(" Position Sensor Electrical Offset: %.4f\n\r", E_OFFSET);
+ printf(" CAN ID: %d\n\r", BOARDNUM);
+
+ pc.attach(&serial_interrupt); // attach serial interrupt
- enter_calibration_mode();
- enter_torque_mode();
+ state_change = 1;
+ //enter_menu_state(); //Print available commands, wait for command
+ //enter_calibration_mode();
+ //wait_us(100);
+
+ //enter_torque_mode();
while(1) {
--- a/structs.h Fri Mar 31 18:24:46 2017 +0000
+++ b/structs.h Wed Apr 05 20:54:16 2017 +0000
@@ -31,6 +31,7 @@
float i_d_ref, i_q_ref;
int loop_count;
int mode;
+ float cogging[128];
} ControllerStruct;
typedef struct{