Merge branch 'master' into master

This commit is contained in:
EmanuelFeru 2020-12-09 18:44:37 +01:00 committed by GitHub
commit 31f0f915cf
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
14 changed files with 236 additions and 203 deletions

View File

@ -292,13 +292,13 @@
#define CONTROL_SERIAL_USART3 // right sensor board cable, disable if I2C (nunchuk or lcd) is used! For Arduino control check the hoverSerial.ino #define CONTROL_SERIAL_USART3 // right sensor board cable, disable if I2C (nunchuk or lcd) is used! For Arduino control check the hoverSerial.ino
#define FEEDBACK_SERIAL_USART3 // right sensor board cable, disable if I2C (nunchuk or lcd) is used! #define FEEDBACK_SERIAL_USART3 // right sensor board cable, disable if I2C (nunchuk or lcd) is used!
// Min / Max values of each channel (use DEBUG to determine these values) // Min / Max values of each channel (use DEBUG to determine these values)
#define INPUT1_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_TYPE 1 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect
#define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MIN -1000 // (-1000 - 0)
#define INPUT1_MID 0 #define INPUT1_MID 0
#define INPUT1_MAX 1000 // (0 - 1000) #define INPUT1_MAX 1000 // (0 - 1000)
#define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0)
#define INPUT2_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_TYPE 1 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect
#define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MIN -1000 // (-1000 - 0)
#define INPUT2_MID 0 #define INPUT2_MID 0
#define INPUT2_MAX 1000 // (0 - 1000) #define INPUT2_MAX 1000 // (0 - 1000)
@ -425,8 +425,8 @@
#undef USART3_BAUD #undef USART3_BAUD
#define USART3_BAUD 115200 #define USART3_BAUD 115200
#define CONTROL_SERIAL_USART3 // left sensor board cable, disable if ADC or PPM is used! #define CONTROL_SERIAL_USART3 // right sensor board cable, disable if ADC or PPM is used!
#define FEEDBACK_SERIAL_USART3 // left sensor board cable, disable if ADC or PPM is used! #define FEEDBACK_SERIAL_USART3 // right sensor board cable, disable if ADC or PPM is used!
#ifdef CONTROL_SERIAL_USART3 #ifdef CONTROL_SERIAL_USART3
#define DEBUG_SERIAL_USART2 // left sensor cable debug #define DEBUG_SERIAL_USART2 // left sensor cable debug
#else #else
@ -577,13 +577,13 @@
#endif #endif
#if defined(FEEDBACK_SERIAL_USART2) || defined(CONTROL_SERIAL_USART2) || defined(DEBUG_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART2) #if defined(FEEDBACK_SERIAL_USART2) || defined(CONTROL_SERIAL_USART2) || defined(DEBUG_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART2)
#ifndef USART2_BAUD #ifndef USART2_BAUD
#define USART2_BAUD 38400 // UART2 baud rate (long wired cable) #define USART2_BAUD 115200 // UART2 baud rate (long wired cable)
#endif #endif
#define USART2_WORDLENGTH UART_WORDLENGTH_8B // UART_WORDLENGTH_8B or UART_WORDLENGTH_9B #define USART2_WORDLENGTH UART_WORDLENGTH_8B // UART_WORDLENGTH_8B or UART_WORDLENGTH_9B
#endif #endif
#if defined(FEEDBACK_SERIAL_USART3) || defined(CONTROL_SERIAL_USART3) || defined(DEBUG_SERIAL_USART3) || defined(SIDEBOARD_SERIAL_USART3) #if defined(FEEDBACK_SERIAL_USART3) || defined(CONTROL_SERIAL_USART3) || defined(DEBUG_SERIAL_USART3) || defined(SIDEBOARD_SERIAL_USART3)
#ifndef USART3_BAUD #ifndef USART3_BAUD
#define USART3_BAUD 38400 // UART3 baud rate (short wired cable) #define USART3_BAUD 115200 // UART3 baud rate (short wired cable)
#endif #endif
#define USART3_WORDLENGTH UART_WORDLENGTH_8B // UART_WORDLENGTH_8B or UART_WORDLENGTH_9B #define USART3_WORDLENGTH UART_WORDLENGTH_8B // UART_WORDLENGTH_8B or UART_WORDLENGTH_9B
#endif #endif

View File

@ -218,5 +218,14 @@ void PWM_ISR_CH2_Callback(void);
#define SENSOR2_SET (0x02) #define SENSOR2_SET (0x02)
#define SENSOR_MPU (0x04) #define SENSOR_MPU (0x04)
// RC iBUS switch definitions. Flysky FS-i6S has SW1, SW4 - 2 positions; SW2, SW3 - 3 positions
#define SW1_SET (0x0100) // 0000 0001 0000 0000
#define SW2_SET1 (0x0200) // 0000 0010 0000 0000
#define SW2_SET2 (0x0400) // 0000 0100 0000 0000
#define SW3_SET1 (0x0800) // 0000 1000 0000 0000
#define SW3_SET2 (0x1000) // 0001 0000 0000 0000
#define SW4_SET (0x2000) // 0010 0000 0000 0000
#endif // DEFINES_H #endif // DEFINES_H

View File

@ -46,10 +46,11 @@
#if defined(SIDEBOARD_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART3) #if defined(SIDEBOARD_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART3)
typedef struct{ typedef struct{
uint16_t start; uint16_t start;
int16_t roll; int16_t pitch; // Angle
int16_t pitch; int16_t dPitch; // Angle derivative
int16_t yaw; int16_t cmd1; // RC Channel 1
uint16_t sensors; int16_t cmd2; // RC Channel 2
uint16_t sensors; // RC Switches and Optical sideboard sensors
uint16_t checksum; uint16_t checksum;
} SerialSideboard; } SerialSideboard;
#endif #endif
@ -62,9 +63,10 @@ void UART_DisableRxErrors(UART_HandleTypeDef *huart);
// General Functions // General Functions
void poweronMelody(void); void poweronMelody(void);
void shortBeep(uint8_t freq); void beepCount(uint8_t cnt, uint8_t freq, uint8_t pattern);
void shortBeepMany(uint8_t cnt, int8_t dir); void beepLong(uint8_t freq);
void longBeep(uint8_t freq); void beepShort(uint8_t freq);
void beepShortMany(uint8_t cnt, int8_t dir);
void calcAvgSpeed(void); void calcAvgSpeed(void);
int addDeadBand(int16_t u, int16_t type, int16_t deadBand, int16_t in_min, int16_t in_mid, int16_t in_max, int16_t out_min, int16_t out_max); int addDeadBand(int16_t u, int16_t type, int16_t deadBand, int16_t in_min, int16_t in_mid, int16_t in_max, int16_t out_min, int16_t out_max);
int checkInputType(int16_t min, int16_t mid, int16_t max); int checkInputType(int16_t min, int16_t mid, int16_t max);

View File

@ -8,6 +8,19 @@ This repository implements Field Oriented Control (FOC) for stock hoverboards. C
- smooth torque output and improved motor efficiency. Thus, lower energy consumption - smooth torque output and improved motor efficiency. Thus, lower energy consumption
- field weakening to increase maximum speed range - field weakening to increase maximum speed range
Table of Contents
=======================
* [Hardware](#hardware)
* [FOC Firmware](#foc-firmware)
* [Example Variants ](#example-variants)
* [Flashing](#flashing)
* [Troubleshooting](#troubleshooting)
* [Diagnostics](#diagnostics)
* [Projects and Links](#projects-and-links)
* [Contributions](#contributions)
#### For the hoverboard sideboard firmware, see the following repositories: #### For the hoverboard sideboard firmware, see the following repositories:
- [hoverboard-sideboard-hack-GD](https://github.com/EmanuelFeru/hoverboard-sideboard-hack-GD) - [hoverboard-sideboard-hack-GD](https://github.com/EmanuelFeru/hoverboard-sideboard-hack-GD)
- [hoverboard-sideboard-hack-STM](https://github.com/EmanuelFeru/hoverboard-sideboard-hack-STM) - [hoverboard-sideboard-hack-STM](https://github.com/EmanuelFeru/hoverboard-sideboard-hack-STM)
@ -15,6 +28,20 @@ This repository implements Field Oriented Control (FOC) for stock hoverboards. C
#### For the FOC controller design, see the following repository: #### For the FOC controller design, see the following repository:
- [bldc-motor-control-FOC](https://github.com/EmanuelFeru/bldc-motor-control-FOC) - [bldc-motor-control-FOC](https://github.com/EmanuelFeru/bldc-motor-control-FOC)
#### Videos:
<table>
<tr>
<td><a href="https://youtu.be/IgHCcj0NgWQ" title="Hovercar" rel="noopener"><img src="/docs/pictures/videos_preview/hovercar_intro.png"></a></td>
<td><a href="https://youtu.be/gtyqtc37r10" title="Cruise Control functionality" rel="noopener"><img src="/docs/pictures/videos_preview/cruise_control.png"></a></td>
<td><a href="https://youtu.be/jadD0M1VBoc" title="Hovercar pedal functionality" rel="noopener"><img src="/docs/pictures/videos_preview/hovercar_pedals.png"></a></td>
</tr>
<tr>
<td><a href="https://youtu.be/UnlbMrCkjnE" title="Commutation vs. FOC (constant speed)" rel="noopener"><img src="/docs/pictures/videos_preview/com_foc_const.png"></a></td>
<td><a href="https://youtu.be/V-_L2w10wZk" title="Commutation vs. FOC (variable speed)" rel="noopener"><img src="/docs/pictures/videos_preview/com_foc_var.png"></a></td>
<td><a href="https://youtu.be/tVj_lpsRirA" title="Reliable Serial Communication" rel="noopener"><img src="/docs/pictures/videos_preview/serial_com.png"></a></td>
</tr>
</table>
--- ---
## Hardware ## Hardware
@ -74,39 +101,19 @@ In all FOC control modes, the controller features maximum motor speed and maximu
- The controller parameters are given in [this table](https://github.com/EmanuelFeru/bldc-motor-control-FOC/blob/master/02_Figures/paramTable.png) - The controller parameters are given in [this table](https://github.com/EmanuelFeru/bldc-motor-control-FOC/blob/master/02_Figures/paramTable.png)
### Diagnostics
Each motor is constantly monitored for errors. These errors are:
- **Error 001**: Hall sensor not connected
- **Error 002**: Hall sensor short circuit
- **Error 004**: Motor NOT able to spin (Possible causes: motor phase disconnected, MOSFET defective, operational Amplifier defective, motor blocked)
The error codes above are reported for each motor in the variables **rtY_Left.z_errCode** and **rtY_Right.z_errCode** for Left motor (long wired motor) and Right motor (short wired motor), respectively. In case of error, the motor power is reduced to 0, while an audible (fast beep) can be heard to notify the user.
### Demo Videos
[►Video: HOVERCAR](https://www.youtube.com/watch?v=IgHCcj0NgWQ&t=)
[►Video: Commutation vs Advanced control (constant speed)](https://drive.google.com/open?id=1vC_kEkp2LE2lAaMCJcmK4z2m3jrPUoBD)
[►Video: Commutation vs Advanced control (variable speed)](https://drive.google.com/open?id=1rrQ4k5VLhhAWXQzDSCar_SmEdsbM-hq2)
[►Video: Reliable Serial Communication demo](https://drive.google.com/open?id=1mUM-p7SE6gmyTH7zhDHy5DUyczXvmy5d)
--- ---
## Example Variants ## Example Variants
This firmware offers currently these variants (selectable in [platformio.ini](/platformio.ini) or [config.h](/Inc/config.h)): This firmware offers currently these variants (selectable in [platformio.ini](/platformio.ini) or [config.h](/Inc/config.h)):
- **VARIANT_ADC**: In this variant the motors are controlled by two potentiometers connected to the Left sensor cable (long wired) - **VARIANT_ADC**: The motors are controlled by two potentiometers connected to the Left sensor cable (long wired)
- **VARIANT_USART**: In this variant the motors are controlled via serial protocol (e.g. on USART3 right sensor cable, the short wired cable). The commands can be sent from an Arduino. Check out the [hoverserial.ino](/Arduino/hoverserial) as an example sketch. - **VARIANT_USART**: The motors are controlled via serial protocol (e.g. on USART3 right sensor cable, the short wired cable). The commands can be sent from an Arduino. Check out the [hoverserial.ino](/Arduino/hoverserial) as an example sketch.
- **VARIANT_NUNCHUK**: Wii Nunchuk offers one hand control for throttle, braking and steering. This was one of the first input device used for electric armchairs or bottle crates. - **VARIANT_NUNCHUK**: Wii Nunchuk offers one hand control for throttle, braking and steering. This was one of the first input device used for electric armchairs or bottle crates.
- **VARIANT_PPM**: This is when you want to use an RC remote control with PPM Sum signal. - **VARIANT_PPM**: RC remote control with PPM Sum signal.
- **VARIANT_PWM**: This is when you want to use an RC remote control with PWM signal. - **VARIANT_PWM**: RC remote control with PWM signal.
- **VARIANT_IBUS**: This is when you want to use an RC remote control with Flysky IBUS protocol connected to the Left sensor cable. - **VARIANT_IBUS**: RC remote control with Flysky iBUS protocol connected to the Left sensor cable.
- **VARIANT_HOVERCAR**: In this variant the motors are controlled by two pedals brake and throttle. Reverse is engaged by double tapping on the brake pedal at standstill. See [HOVERCAR video](https://www.youtube.com/watch?v=IgHCcj0NgWQ&t=). - **VARIANT_HOVERCAR**: The motors are controlled by two pedals brake and throttle. Reverse is engaged by double tapping on the brake pedal at standstill. See [HOVERCAR video](https://www.youtube.com/watch?v=IgHCcj0NgWQ&t=).
- **VARIANT_HOVERBOARD**: In this variant the mainboard reads the sideboards data. The sideboards need to be flashed with the hacked version. Only balancing controller is still to be implemented. - **VARIANT_HOVERBOARD**: The mainboard reads the two sideboards data. The sideboards need to be flashed with the hacked version. The balancing controller is **not** yet implemented.
- **VARIANT_TRANSPOTTER**: This build is for transpotter which is a hoverboard based transportation system. For more details on how to build it check [here](https://github.com/NiklasFauth/hoverboard-firmware-hack/wiki/Build-Instruction:-TranspOtter) and [here](https://hackaday.io/project/161891-transpotter-ng). - **VARIANT_TRANSPOTTER**: This is for transpotter build, which is a hoverboard based transportation system. For more details on how to build it check [here](https://github.com/NiklasFauth/hoverboard-firmware-hack/wiki/Build-Instruction:-TranspOtter) and [here](https://hackaday.io/project/161891-transpotter-ng).
- **VARIANT_SKATEBOARD**: This is for skateboard build, controlled using an RC remote with PWM signal connected to the right sensor cable. - **VARIANT_SKATEBOARD**: This is for skateboard build, controlled using an RC remote with PWM signal connected to the right sensor cable.
Of course the firmware can be further customized for other needs or projects. Of course the firmware can be further customized for other needs or projects.
@ -193,6 +200,7 @@ platformio run target upload -e VARIANT_####
``` ```
If you have set default_envs in [platformio.ini](/platformio.ini) you can ommit -e parameter If you have set default_envs in [platformio.ini](/platformio.ini) you can ommit -e parameter
--- ---
## Troubleshooting ## Troubleshooting
First, check that power is connected and voltage is >36V while flashing. First, check that power is connected and voltage is >36V while flashing.
@ -209,10 +217,25 @@ Recommendation: Nunchuk Breakout Board https://github.com/Jan--Henrik/hoverboard
Most robust way for input is to use the ADC and potis. It works well even on 1m unshielded cable. Solder ~100k Ohm resistors between ADC-inputs and gnd directly on the mainboard. Use potis as pullups to 3.3V. Most robust way for input is to use the ADC and potis. It works well even on 1m unshielded cable. Solder ~100k Ohm resistors between ADC-inputs and gnd directly on the mainboard. Use potis as pullups to 3.3V.
---
## Diagnostics
The errors reported by the board are in the form of audible beeps:
- **1 beep (low pitch)**: Motor error (see [possible causes](https://github.com/EmanuelFeru/bldc-motor-control-FOC#diagnostics))
- **2 beeps (low pitch)**: ADC timeout
- **3 beeps (low pitch)**: Serial communication timeout
- **4 beeps (low pitch)**: General timeout (PPM, PWM, Nunchuck)
- **5 beeps (low pitch)**: Mainboard temperature warning
- **1 beep slow (medium pitch)**: Low battery voltage < 36V
- **1 beep fast (medium pitch)**: Low battery voltage < 35V
- **1 beep fast (high pitch)**: Backward spinning motors
For a more detailed troubleshooting connect an [FTDI Serial adapter](https://s.click.aliexpress.com/e/_AqPOBr) or a [Bluetooth module](https://s.click.aliexpress.com/e/_A4gkMD) to the DEBUG_SERIAL cable (Left or Right) and monitor the output data using the [Hoverboard Web Serial Control](https://candas1.github.io/Hoverboard-Web-Serial-Control/) tool developed by [Candas](https://github.com/Candas1/).
--- ---
## Projects and Links ## Projects and Links
- **Original firmware:** [https://github.com/NiklasFauth/hoverboard-firmware-hack](https://github.com/NiklasFauth/hoverboard-firmware-hack) - **Original firmware:** [https://github.com/NiklasFauth/hoverboard-firmware-hack](https://github.com/NiklasFauth/hoverboard-firmware-hack)
- **[Candas](https://github.com/Candas1/) Hoverboard Web Serial Control:** [https://candas1.github.io/Hoverboard-Web-Serial-Control/](https://candas1.github.io/Hoverboard-Web-Serial-Control/)
- **[RoboDurden's](https://github.com/RoboDurden) online compiler:** [https://pionierland.de/hoverhack/](https://pionierland.de/hoverhack/) - **[RoboDurden's](https://github.com/RoboDurden) online compiler:** [https://pionierland.de/hoverhack/](https://pionierland.de/hoverhack/)
- **Hoverboard hack for AT32F403RCT6 mainboards:** [https://github.com/cloidnerux/hoverboard-firmware-hack](https://github.com/cloidnerux/hoverboard-firmware-hack) - **Hoverboard hack for AT32F403RCT6 mainboards:** [https://github.com/cloidnerux/hoverboard-firmware-hack](https://github.com/cloidnerux/hoverboard-firmware-hack)
- **Hoverboard hack for split mainboards:** [https://github.com/flo199213/Hoverboard-Firmware-Hack-Gen2](https://github.com/flo199213/Hoverboard-Firmware-Hack-Gen2) - **Hoverboard hack for split mainboards:** [https://github.com/flo199213/Hoverboard-Firmware-Hack-Gen2](https://github.com/flo199213/Hoverboard-Firmware-Hack-Gen2)

View File

@ -59,7 +59,10 @@ extern volatile adc_buf_t adc_buffer;
uint8_t buzzerFreq = 0; uint8_t buzzerFreq = 0;
uint8_t buzzerPattern = 0; uint8_t buzzerPattern = 0;
uint8_t buzzerCount = 0;
static uint32_t buzzerTimer = 0; static uint32_t buzzerTimer = 0;
static uint8_t buzzerPrev = 0;
static uint8_t buzzerIdx = 0;
uint8_t enable = 0; // initially motors are disabled for SAFETY uint8_t enable = 0; // initially motors are disabled for SAFETY
static uint8_t enableFin = 0; static uint8_t enableFin = 0;
@ -97,7 +100,7 @@ void DMA1_Channel1_IRQHandler(void) {
return; return;
} }
if (buzzerTimer % 1000 == 0) { // because you get float rounding errors if it would run every time -> not any more, everything converted to fixed-point if (buzzerTimer % 1000 == 0) { // Filter battery voltage at a slower sampling rate
filtLowPass32(adc_buffer.batt1, BAT_FILT_COEF, &batVoltageFixdt); filtLowPass32(adc_buffer.batt1, BAT_FILT_COEF, &batVoltageFixdt);
batVoltage = (int16_t)(batVoltageFixdt >> 16); // convert fixed-point to integer batVoltage = (int16_t)(batVoltageFixdt >> 16); // convert fixed-point to integer
} }
@ -126,14 +129,21 @@ void DMA1_Channel1_IRQHandler(void) {
RIGHT_TIM->BDTR |= TIM_BDTR_MOE; RIGHT_TIM->BDTR |= TIM_BDTR_MOE;
} }
//create square wave for buzzer // Create square wave for buzzer
buzzerTimer++; buzzerTimer++;
if (buzzerFreq != 0 && (buzzerTimer / 5000) % (buzzerPattern + 1) == 0) { if (buzzerFreq != 0 && (buzzerTimer / 5000) % (buzzerPattern + 1) == 0) {
if (buzzerTimer % buzzerFreq == 0) { if (buzzerPrev == 0) {
buzzerPrev = 1;
if (++buzzerIdx > (buzzerCount + 2)) { // pause 2 periods
buzzerIdx = 1;
}
}
if (buzzerTimer % buzzerFreq == 0 && (buzzerIdx <= buzzerCount || buzzerCount == 0)) {
HAL_GPIO_TogglePin(BUZZER_PORT, BUZZER_PIN); HAL_GPIO_TogglePin(BUZZER_PORT, BUZZER_PIN);
} }
} else { } else if (buzzerPrev) {
HAL_GPIO_WritePin(BUZZER_PORT, BUZZER_PIN, GPIO_PIN_RESET); HAL_GPIO_WritePin(BUZZER_PORT, BUZZER_PIN, GPIO_PIN_RESET);
buzzerPrev = 0;
} }
// ############################### MOTOR CONTROL ############################### // ############################### MOTOR CONTROL ###############################

View File

@ -75,9 +75,6 @@ extern uint8_t timeoutFlagSerial; // Timeout Flag for Rx Serial command: 0
extern volatile int pwml; // global variable for pwm left. -1000 to 1000 extern volatile int pwml; // global variable for pwm left. -1000 to 1000
extern volatile int pwmr; // global variable for pwm right. -1000 to 1000 extern volatile int pwmr; // global variable for pwm right. -1000 to 1000
extern uint8_t buzzerFreq; // global variable for the buzzer pitch. can be 1, 2, 3, 4, 5, 6, 7...
extern uint8_t buzzerPattern; // global variable for the buzzer pattern. can be 1, 2, 3, 4, 5, 6, 7...
extern uint8_t enable; // global variable for motor enable extern uint8_t enable; // global variable for motor enable
extern int16_t batVoltage; // global variable for battery voltage extern int16_t batVoltage; // global variable for battery voltage
@ -181,11 +178,11 @@ int main(void) {
MX_ADC1_Init(); MX_ADC1_Init();
MX_ADC2_Init(); MX_ADC2_Init();
BLDC_Init(); // BLDC Controller Init BLDC_Init(); // BLDC Controller Init
HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, GPIO_PIN_SET); // Activate Latch
Input_Lim_Init(); // Input Limitations Init Input_Lim_Init(); // Input Limitations Init
Input_Init(); // Input Init Input_Init(); // Input Init
HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, GPIO_PIN_SET);
HAL_ADC_Start(&hadc1); HAL_ADC_Start(&hadc1);
HAL_ADC_Start(&hadc2); HAL_ADC_Start(&hadc2);
@ -213,8 +210,8 @@ int main(void) {
#ifndef VARIANT_TRANSPOTTER #ifndef VARIANT_TRANSPOTTER
// ####### MOTOR ENABLING: Only if the initial input is very small (for SAFETY) ####### // ####### MOTOR ENABLING: Only if the initial input is very small (for SAFETY) #######
if (enable == 0 && (!rtY_Left.z_errCode && !rtY_Right.z_errCode) && (cmd1 > -50 && cmd1 < 50) && (cmd2 > -50 && cmd2 < 50)){ if (enable == 0 && (!rtY_Left.z_errCode && !rtY_Right.z_errCode) && (cmd1 > -50 && cmd1 < 50) && (cmd2 > -50 && cmd2 < 50)){
shortBeep(6); // make 2 beeps indicating the motor enable beepShort(6); // make 2 beeps indicating the motor enable
shortBeep(4); HAL_Delay(100); beepShort(4); HAL_Delay(100);
steerFixdt = speedFixdt = 0; // reset filters steerFixdt = speedFixdt = 0; // reset filters
enable = 1; // enable motors enable = 1; // enable motors
printf("# -- Motors enabled --\n"); printf("# -- Motors enabled --\n");
@ -353,7 +350,7 @@ int main(void) {
if ((distance / 1345.0) - setDistance > 0.5 && (lastDistance / 1345.0) - setDistance > 0.5) { // Error, robot too far away! if ((distance / 1345.0) - setDistance > 0.5 && (lastDistance / 1345.0) - setDistance > 0.5) { // Error, robot too far away!
enable = 0; enable = 0;
longBeep(5); beepLong(5);
#ifdef SUPPORT_LCD #ifdef SUPPORT_LCD
LCD_ClearDisplay(&lcd); LCD_ClearDisplay(&lcd);
HAL_Delay(5); HAL_Delay(5);
@ -467,37 +464,33 @@ int main(void) {
if (board_temp_deg_c >= TEMP_POWEROFF) printf("# Error: STM32 overtemp: %4.1f°C: power off\n", board_temp_deg_c / 10.0); if (board_temp_deg_c >= TEMP_POWEROFF) printf("# Error: STM32 overtemp: %4.1f°C: power off\n", board_temp_deg_c / 10.0);
if (batVoltage < BAT_DEAD) printf("# Battery empty: %4.2fV: power off\n", batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC / 100.0); if (batVoltage < BAT_DEAD) printf("# Battery empty: %4.2fV: power off\n", batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC / 100.0);
poweroff(); poweroff();
} else if (rtY_Left.z_errCode || rtY_Right.z_errCode) { // disable motors and beep in case of Motor error - fast beep } else if (rtY_Left.z_errCode || rtY_Right.z_errCode) { // 1 beep (low pitch): Motor error, disable motors
enable = 0; enable = 0;
if (rtY_Left.z_errCode && main_loop_counter % 50 == 0) printf("# Warning: rtY_Left.z_errCode: %i\n", rtY_Left.z_errCode); beepCount(1, 24, 1);
if (rtY_Right.z_errCode && main_loop_counter % 50 == 0) printf("# Warning: rtY_Right.z_errCode: %i\n", rtY_Right.z_errCode); printf("# Warning: Left_err: %i Right_err: %i\n", rtY_Left.z_errCode);
buzzerFreq = 8; } else if (timeoutFlagADC) { // 2 beeps (low pitch): ADC timeout
buzzerPattern = 1; beepCount(2, 24, 1);
} else if (timeoutFlagADC || timeoutFlagSerial || timeoutCnt > TIMEOUT) { // beep in case of ADC timeout, Serial timeout or General timeout - fast beep printf("# Warning: ADC timeout\n");
if (timeoutFlagADC && main_loop_counter % 50 == 0) printf("# Warning: ADC timeout\n"); } else if (timeoutFlagSerial) { // 3 beeps (low pitch): Serial timeout
if (timeoutFlagSerial && main_loop_counter % 50 == 0) printf("# Warning: Serial timeout\n"); beepCount(3, 24, 1);
if (timeoutCnt > TIMEOUT && main_loop_counter % 50 == 0) printf("# Warning: General timeout\n"); printf("# Warning: Serial timeout\n");
buzzerFreq = 24; } else if (timeoutCnt > TIMEOUT) { // 4 beeps (low pitch): General timeout (PPM, PWM, Nunchuck)
buzzerPattern = 1; beepCount(4, 24, 1);
} else if (TEMP_WARNING_ENABLE && board_temp_deg_c >= TEMP_WARNING) { // beep if mainboard gets hot printf("# Warning: General timeout\n");
if (main_loop_counter % 50 == 0) printf("# Warning: STM32 is getting hot: %4.1f°C\n", board_temp_deg_c / 10.0); } else if (TEMP_WARNING_ENABLE && board_temp_deg_c >= TEMP_WARNING) { // 5 beeps (low pitch): Mainboard temperature warning
buzzerFreq = 4; beepCount(5, 24, 1);
buzzerPattern = 1; printf("# Warning: STM32 is getting hot: %4.1f°C\n", board_temp_deg_c / 10.0);
} else if (BAT_LVL1_ENABLE && batVoltage < BAT_LVL1) { // low bat 1: fast beep } else if (BAT_LVL1_ENABLE && batVoltage < BAT_LVL1) { // 1 beep fast (medium pitch): Low bat 1
if (main_loop_counter % 50 == 0) printf("# Warning: Battery is getting empty 1: %4.2fV\n", batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC / 100.0); beepCount(0, 10, 6);
buzzerFreq = 5; printf("# Warning: Battery is getting empty 1: %4.2fV\n", batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC / 100.0);
buzzerPattern = 6; } else if (BAT_LVL2_ENABLE && batVoltage < BAT_LVL2) { // 1 beep slow (medium pitch): Low bat 2
} else if (BAT_LVL2_ENABLE && batVoltage < BAT_LVL2) { // low bat 2: slow beep beepCount(0, 10, 30);
if (main_loop_counter % 50 == 0) printf("# Warning: Battery is getting empty 2: %4.2fV\n", batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC / 100.0); printf("# Warning: Battery is getting empty 2: %4.2fV\n", batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC / 100.0);
buzzerFreq = 5; } else if (BEEPS_BACKWARD && ((speed < -50 && speedAvg < 0) || MultipleTapBrake.b_multipleTap)) { // 1 beep fast (high pitch): Backward spinning motors
buzzerPattern = 42; beepCount(0, 5, 1);
} else if (BEEPS_BACKWARD && ((speed < -50 && speedAvg < 0) || MultipleTapBrake.b_multipleTap)) { // backward beep
buzzerFreq = 5;
buzzerPattern = 1;
backwardDrive = 1; backwardDrive = 1;
} else { // do not beep } else { // do not beep
buzzerFreq = 0; beepCount(0, 0, 0);
buzzerPattern = 0;
backwardDrive = 0; backwardDrive = 0;
} }

View File

@ -45,6 +45,7 @@ extern UART_HandleTypeDef huart3;
extern int16_t batVoltage; extern int16_t batVoltage;
extern uint8_t backwardDrive; extern uint8_t backwardDrive;
extern uint8_t buzzerCount; // global variable for the buzzer counts. can be 1, 2, 3, 4, 5, 6, 7...
extern uint8_t buzzerFreq; // global variable for the buzzer pitch. can be 1, 2, 3, 4, 5, 6, 7... extern uint8_t buzzerFreq; // global variable for the buzzer pitch. can be 1, 2, 3, 4, 5, 6, 7...
extern uint8_t buzzerPattern; // global variable for the buzzer pattern. can be 1, 2, 3, 4, 5, 6, 7... extern uint8_t buzzerPattern; // global variable for the buzzer pattern. can be 1, 2, 3, 4, 5, 6, 7...
@ -368,6 +369,7 @@ void UART_DisableRxErrors(UART_HandleTypeDef *huart)
/* =========================== General Functions =========================== */ /* =========================== General Functions =========================== */
void poweronMelody(void) { void poweronMelody(void) {
buzzerCount = 0; // prevent interraction with beep counter
for (int i = 8; i >= 0; i--) { for (int i = 8; i >= 0; i--) {
buzzerFreq = (uint8_t)i; buzzerFreq = (uint8_t)i;
HAL_Delay(100); HAL_Delay(100);
@ -375,30 +377,38 @@ void poweronMelody(void) {
buzzerFreq = 0; buzzerFreq = 0;
} }
void shortBeep(uint8_t freq) { void beepCount(uint8_t cnt, uint8_t freq, uint8_t pattern) {
buzzerCount = cnt;
buzzerFreq = freq;
buzzerPattern = pattern;
}
void beepLong(uint8_t freq) {
buzzerCount = 0; // prevent interraction with beep counter
buzzerFreq = freq;
HAL_Delay(500);
buzzerFreq = 0;
}
void beepShort(uint8_t freq) {
buzzerCount = 0; // prevent interraction with beep counter
buzzerFreq = freq; buzzerFreq = freq;
HAL_Delay(100); HAL_Delay(100);
buzzerFreq = 0; buzzerFreq = 0;
} }
void shortBeepMany(uint8_t cnt, int8_t dir) { void beepShortMany(uint8_t cnt, int8_t dir) {
if (dir >= 0) { // increasing tone if (dir >= 0) { // increasing tone
for(uint8_t i = 2*cnt; i >= 2; i=i-2) { for(uint8_t i = 2*cnt; i >= 2; i=i-2) {
shortBeep(i + 3); beepShort(i + 3);
} }
} else { // decreasing tone } else { // decreasing tone
for(uint8_t i = 2; i <= 2*cnt; i=i+2) { for(uint8_t i = 2; i <= 2*cnt; i=i+2) {
shortBeep(i + 3); beepShort(i + 3);
} }
} }
} }
void longBeep(uint8_t freq) {
buzzerFreq = freq;
HAL_Delay(500);
buzzerFreq = 0;
}
void calcAvgSpeed(void) { void calcAvgSpeed(void) {
// Calculate measured average speed. The minus sign (-) is because motors spin in opposite directions // Calculate measured average speed. The minus sign (-) is because motors spin in opposite directions
#if !defined(INVERT_L_DIRECTION) && !defined(INVERT_R_DIRECTION) #if !defined(INVERT_L_DIRECTION) && !defined(INVERT_R_DIRECTION)
@ -470,7 +480,7 @@ int checkInputType(int16_t min, int16_t mid, int16_t max){
#ifdef CONTROL_ADC #ifdef CONTROL_ADC
if ((min + INPUT_MARGIN - ADC_PROTECT_THRESH) > 0 && (max - INPUT_MARGIN + ADC_PROTECT_THRESH) < 4095) { if ((min + INPUT_MARGIN - ADC_PROTECT_THRESH) > 0 && (max - INPUT_MARGIN + ADC_PROTECT_THRESH) < 4095) {
printf(" and protected"); printf(" and protected");
longBeep(2); // Indicate protection by a beep beepLong(2); // Indicate protection by a beep
} }
#endif #endif
} }
@ -498,10 +508,7 @@ void adcCalibLim(void) {
} }
#if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER)
printf("# Input calibration started...\n"); printf("Input calibration started...\r\n");
printf("# move the potentiometers freely to the min and max limits repeatedly\n");
printf("# release potentiometers to the resting postion\n");
printf("# press the power button to confirm or wait for the 20 sec timeout\n");
readInput(); readInput();
// Inititalization: MIN = a high value, MAX = a low value // Inititalization: MIN = a high value, MAX = a low value
@ -535,10 +542,10 @@ void adcCalibLim(void) {
INPUT1_MIN_CAL = INPUT1_MIN_temp + INPUT_MARGIN; INPUT1_MIN_CAL = INPUT1_MIN_temp + INPUT_MARGIN;
INPUT1_MID_CAL = INPUT1_MID_temp; INPUT1_MID_CAL = INPUT1_MID_temp;
INPUT1_MAX_CAL = INPUT1_MAX_temp - INPUT_MARGIN; INPUT1_MAX_CAL = INPUT1_MAX_temp - INPUT_MARGIN;
printf("# Input1 OK\n"); HAL_Delay(10); printf("# Input1 OK\r\n"); HAL_Delay(10);
} else { } else {
INPUT1_TYP_CAL = 0; // Disable input INPUT1_TYP_CAL = 0; // Disable input
printf("# Input1 Fail\n"); HAL_Delay(10); printf("# Input1 Fail\r\n"); HAL_Delay(10);
} }
INPUT2_TYP_CAL = checkInputType(INPUT2_MIN_temp, INPUT2_MID_temp, INPUT2_MAX_temp); INPUT2_TYP_CAL = checkInputType(INPUT2_MIN_temp, INPUT2_MID_temp, INPUT2_MAX_temp);
@ -546,10 +553,10 @@ void adcCalibLim(void) {
INPUT2_MIN_CAL = INPUT2_MIN_temp + INPUT_MARGIN; INPUT2_MIN_CAL = INPUT2_MIN_temp + INPUT_MARGIN;
INPUT2_MID_CAL = INPUT2_MID_temp; INPUT2_MID_CAL = INPUT2_MID_temp;
INPUT2_MAX_CAL = INPUT2_MAX_temp - INPUT_MARGIN; INPUT2_MAX_CAL = INPUT2_MAX_temp - INPUT_MARGIN;
printf("# Input2 OK\n"); HAL_Delay(10); printf("# Input2 OK\r\n"); HAL_Delay(10);
} else { } else {
INPUT2_TYP_CAL = 0; // Disable input INPUT2_TYP_CAL = 0; // Disable input
printf("# Input2 Fail\n"); HAL_Delay(10); printf("# Input2 Fail\r\n"); HAL_Delay(10);
} }
inp_cal_valid = 1; // Mark calibration to be saved in Flash at shutdown inp_cal_valid = 1; // Mark calibration to be saved in Flash at shutdown
printf("# Limits: INPUT1_TYP_CAL:%i INPUT1_MIN_CAL:%i INPUT1_MID_CAL:%i INPUT1_MAX_CAL:%i INPUT2_TYP_CAL:%i INPUT2_MIN_CAL:%i INPUT2_MID_CAL:%i INPUT2_MAX_CAL:%i\n", printf("# Limits: INPUT1_TYP_CAL:%i INPUT1_MIN_CAL:%i INPUT1_MID_CAL:%i INPUT1_MAX_CAL:%i INPUT2_TYP_CAL:%i INPUT2_MIN_CAL:%i INPUT2_MID_CAL:%i INPUT2_MAX_CAL:%i\n",
@ -569,9 +576,7 @@ void updateCurSpdLim(void) {
} }
#if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER)
printf("# Torque and Speed limits update started...\n"); printf("Torque and Speed limits update started...\r\n");
printf("# move and hold the pots to a desired limit position for Current and Speed\n");
printf("# press the power button to confirm or wait for the 10 sec timeout\n");
int32_t input1_fixdt = input1 << 16; int32_t input1_fixdt = input1 << 16;
int32_t input2_fixdt = input2 << 16; int32_t input2_fixdt = input2 << 16;
@ -737,9 +742,10 @@ void cruiseControl(uint8_t button) {
/* =========================== Poweroff Functions =========================== */ /* =========================== Poweroff Functions =========================== */
void poweroff(void) { void poweroff(void) {
buzzerPattern = 0;
enable = 0; enable = 0;
printf("# -- Motors disabled --\n"); printf("-- Motors disabled --\r\n");
buzzerCount = 0; // prevent interraction with beep counter
buzzerPattern = 0;
for (int i = 0; i < 8; i++) { for (int i = 0; i < 8; i++) {
buzzerFreq = (uint8_t)i; buzzerFreq = (uint8_t)i;
HAL_Delay(100); HAL_Delay(100);
@ -757,19 +763,19 @@ void poweroffPressCheck(void) {
uint16_t cnt_press = 0; uint16_t cnt_press = 0;
while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {
HAL_Delay(10); HAL_Delay(10);
if (cnt_press++ == 5 * 100) { shortBeep(5); } if (cnt_press++ == 5 * 100) { beepShort(5); }
} }
if (cnt_press >= 5 * 100) { // Check if press is more than 5 sec if (cnt_press >= 5 * 100) { // Check if press is more than 5 sec
HAL_Delay(1000); HAL_Delay(1000);
if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { // Double press: Adjust Max Current, Max Speed if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { // Double press: Adjust Max Current, Max Speed
while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); } while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); }
longBeep(8); beepLong(8);
updateCurSpdLim(); updateCurSpdLim();
shortBeep(5); beepShort(5);
} else { // Long press: Calibrate ADC Limits } else { // Long press: Calibrate ADC Limits
longBeep(16); beepLong(16);
adcCalibLim(); adcCalibLim();
shortBeep(5); beepShort(5);
} }
} else { // Short press: power off } else { // Short press: power off
poweroff(); poweroff();
@ -779,11 +785,11 @@ void poweroffPressCheck(void) {
if(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { if(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {
enable = 0; enable = 0;
while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); } while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); }
shortBeep(5); beepShort(5);
HAL_Delay(300); HAL_Delay(300);
if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {
while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); } while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); }
longBeep(5); beepLong(5);
HAL_Delay(350); HAL_Delay(350);
poweroff(); poweroff();
} else { } else {
@ -791,7 +797,7 @@ void poweroffPressCheck(void) {
if (setDistance > 2.6) { if (setDistance > 2.6) {
setDistance = 0.5; setDistance = 0.5;
} }
shortBeep(setDistance / 0.25); beepShort(setDistance / 0.25);
saveValue = setDistance * 1000; saveValue = setDistance * 1000;
saveValue_valid = 1; saveValue_valid = 1;
} }
@ -1161,7 +1167,7 @@ void usart_process_sideboard(SerialSideboard *Sideboard_in, SerialSideboard *Sid
{ {
uint16_t checksum; uint16_t checksum;
if (Sideboard_in->start == SERIAL_START_FRAME) { if (Sideboard_in->start == SERIAL_START_FRAME) {
checksum = (uint16_t)(Sideboard_in->start ^ Sideboard_in->roll ^ Sideboard_in->pitch ^ Sideboard_in->yaw ^ Sideboard_in->sensors); checksum = (uint16_t)(Sideboard_in->start ^ Sideboard_in->pitch ^ Sideboard_in->dPitch ^ Sideboard_in->cmd1 ^ Sideboard_in->cmd2 ^ Sideboard_in->sensors);
if (Sideboard_in->checksum == checksum) { if (Sideboard_in->checksum == checksum) {
*Sideboard_out = *Sideboard_in; *Sideboard_out = *Sideboard_in;
if (usart_idx == 2) { // Sideboard USART2 if (usart_idx == 2) { // Sideboard USART2
@ -1295,7 +1301,7 @@ void sideboardSensors(uint8_t sensors) {
rtP_Right.z_ctrlTypSel = COM_CTRL; rtP_Right.z_ctrlTypSel = COM_CTRL;
break; break;
} }
shortBeepMany(sensor1_index + 1, 1); beepShortMany(sensor1_index + 1, 1);
} }
// Field Weakening: use Sensor2 as push button // Field Weakening: use Sensor2 as push button
@ -1320,7 +1326,7 @@ void sideboardSensors(uint8_t sensors) {
Input_Lim_Init(); Input_Lim_Init();
break; break;
} }
shortBeepMany(sensor2_index + 1, 1); beepShortMany(sensor2_index + 1, 1);
} }
#endif // CRUISE_CONTROL_SUPPORT #endif // CRUISE_CONTROL_SUPPORT
#endif #endif

Binary file not shown.

After

Width:  |  Height:  |  Size: 108 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 105 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 106 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 112 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 118 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 116 KiB

View File

@ -32,17 +32,16 @@ upload_protocol = stlink
; Serial Port settings (make sure the COM port is correct) ; Serial Port settings (make sure the COM port is correct)
monitor_port = COM5 monitor_port = COM5
monitor_speed = 38400 monitor_speed = 115200
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_ADC -D VARIANT_ADC
;================================================================ ;================================================================
@ -61,12 +60,11 @@ monitor_speed = 38400
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_USART -D VARIANT_USART
;================================================================ ;================================================================
@ -81,12 +79,11 @@ upload_protocol = stlink
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_NUNCHUK -D VARIANT_NUNCHUK
;================================================================ ;================================================================
@ -101,12 +98,11 @@ upload_protocol = stlink
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_PPM -D VARIANT_PPM
;================================================================ ;================================================================
@ -121,12 +117,11 @@ upload_protocol = stlink
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_PWM -D VARIANT_PWM
;================================================================ ;================================================================
@ -141,12 +136,11 @@ upload_protocol = stlink
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_IBUS -D VARIANT_IBUS
;================================================================ ;================================================================
@ -165,12 +159,11 @@ monitor_speed = 38400
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_HOVERCAR -D VARIANT_HOVERCAR
;================================================================ ;================================================================
@ -189,12 +182,11 @@ monitor_speed = 38400
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_HOVERBOARD -D VARIANT_HOVERBOARD
;================================================================ ;================================================================
@ -209,12 +201,11 @@ upload_protocol = stlink
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_TRANSPOTTER -D VARIANT_TRANSPOTTER
;================================================================ ;================================================================
@ -230,12 +221,11 @@ upload_protocol = stlink
build_flags = build_flags =
-DUSE_HAL_DRIVER -DUSE_HAL_DRIVER
-DSTM32F103xE -DSTM32F103xE
-Wl,-u,_printf_float ; enable float for printf -u,_printf_float ; enable float for printf
-Wl,-T./STM32F103RCTx_FLASH.ld -T./STM32F103RCTx_FLASH.ld
-Wl,-lc -lc
-Wl,-lm -lm
-g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization -g -ggdb ; to generate correctly the 'firmware.elf' for STM STUDIO vizualization
# -Wl,-lnosys
-D VARIANT_SKATEBOARD -D VARIANT_SKATEBOARD
;================================================================ ;================================================================