-
Notifications
You must be signed in to change notification settings - Fork 932
/
main.c
579 lines (504 loc) · 24.7 KB
/
main.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
/*
* This file is part of the hoverboard-firmware-hack project.
*
* Copyright (C) 2017-2018 Rene Hopf <renehopf@mac.com>
* Copyright (C) 2017-2018 Nico Stute <crinq@crinq.de>
* Copyright (C) 2017-2018 Niklas Fauth <niklas.fauth@kit.fail>
* Copyright (C) 2019-2020 Emanuel FERU <aerdronix@gmail.com>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdio.h>
#include <stdlib.h> // for abs()
#include "stm32f1xx_hal.h"
#include "defines.h"
#include "setup.h"
#include "config.h"
#include "util.h"
#include "BLDC_controller.h" /* BLDC's header file */
#include "rtwtypes.h"
#include "comms.h"
#if defined(DEBUG_I2C_LCD) || defined(SUPPORT_LCD)
#include "hd44780.h"
#endif
void SystemClock_Config(void);
//------------------------------------------------------------------------
// Global variables set externally
//------------------------------------------------------------------------
extern TIM_HandleTypeDef htim_left;
extern TIM_HandleTypeDef htim_right;
extern ADC_HandleTypeDef hadc1;
extern ADC_HandleTypeDef hadc2;
extern volatile adc_buf_t adc_buffer;
#if defined(DEBUG_I2C_LCD) || defined(SUPPORT_LCD)
extern LCD_PCF8574_HandleTypeDef lcd;
extern uint8_t LCDerrorFlag;
#endif
extern UART_HandleTypeDef huart2;
extern UART_HandleTypeDef huart3;
volatile uint8_t uart_buf[200];
// Matlab defines - from auto-code generation
//---------------
extern P rtP_Left; /* Block parameters (auto storage) */
extern P rtP_Right; /* Block parameters (auto storage) */
extern ExtY rtY_Left; /* External outputs */
extern ExtY rtY_Right; /* External outputs */
extern ExtU rtU_Left; /* External inputs */
extern ExtU rtU_Right; /* External inputs */
//---------------
extern uint8_t inIdx; // input index used for dual-inputs
extern uint8_t inIdx_prev;
extern InputStruct input1[]; // input structure
extern InputStruct input2[]; // input structure
extern int16_t speedAvg; // Average measured speed
extern int16_t speedAvgAbs; // Average measured speed in absolute
extern volatile uint32_t timeoutCntGen; // Timeout counter for the General timeout (PPM, PWM, Nunchuk)
extern volatile uint8_t timeoutFlgGen; // Timeout Flag for the General timeout (PPM, PWM, Nunchuk)
extern uint8_t timeoutFlgADC; // Timeout Flag for for ADC Protection: 0 = OK, 1 = Problem detected (line disconnected or wrong ADC data)
extern uint8_t timeoutFlgSerial; // Timeout Flag for Rx Serial command: 0 = OK, 1 = Problem detected (line disconnected or wrong Rx data)
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 uint8_t enable; // global variable for motor enable
extern int16_t batVoltage; // global variable for battery voltage
#if defined(SIDEBOARD_SERIAL_USART2)
extern SerialSideboard Sideboard_L;
#endif
#if defined(SIDEBOARD_SERIAL_USART3)
extern SerialSideboard Sideboard_R;
#endif
#if (defined(CONTROL_PPM_LEFT) && defined(DEBUG_SERIAL_USART3)) || (defined(CONTROL_PPM_RIGHT) && defined(DEBUG_SERIAL_USART2))
extern volatile uint16_t ppm_captured_value[PPM_NUM_CHANNELS+1];
#endif
#if (defined(CONTROL_PWM_LEFT) && defined(DEBUG_SERIAL_USART3)) || (defined(CONTROL_PWM_RIGHT) && defined(DEBUG_SERIAL_USART2))
extern volatile uint16_t pwm_captured_ch1_value;
extern volatile uint16_t pwm_captured_ch2_value;
#endif
//------------------------------------------------------------------------
// Global variables set here in main.c
//------------------------------------------------------------------------
uint8_t backwardDrive;
extern volatile uint32_t buzzerTimer;
volatile uint32_t main_loop_counter;
int16_t batVoltageCalib; // global variable for calibrated battery voltage
int16_t board_temp_deg_c; // global variable for calibrated temperature in degrees Celsius
int16_t left_dc_curr; // global variable for Left DC Link current
int16_t right_dc_curr; // global variable for Right DC Link current
int16_t dc_curr; // global variable for Total DC Link current
int16_t cmdL; // global variable for Left Command
int16_t cmdR; // global variable for Right Command
//------------------------------------------------------------------------
// Local variables
//------------------------------------------------------------------------
#if defined(FEEDBACK_SERIAL_USART2) || defined(FEEDBACK_SERIAL_USART3)
typedef struct{
uint16_t start;
int16_t cmd1;
int16_t cmd2;
int16_t speedR_meas;
int16_t speedL_meas;
int16_t batVoltage;
int16_t boardTemp;
uint16_t cmdLed;
uint16_t checksum;
} SerialFeedback;
static SerialFeedback Feedback;
#endif
#if defined(FEEDBACK_SERIAL_USART2)
static uint8_t sideboard_leds_L;
#endif
#if defined(FEEDBACK_SERIAL_USART3)
static uint8_t sideboard_leds_R;
#endif
#ifdef VARIANT_TRANSPOTTER
extern uint8_t nunchuk_connected;
extern float setDistance;
static uint8_t checkRemote = 0;
static uint16_t distance;
static float steering;
static int distanceErr;
static int lastDistance = 0;
static uint16_t transpotter_counter = 0;
#endif
static int16_t speed; // local variable for speed. -1000 to 1000
#ifndef VARIANT_TRANSPOTTER
static int16_t steer; // local variable for steering. -1000 to 1000
static int16_t steerRateFixdt; // local fixed-point variable for steering rate limiter
static int16_t speedRateFixdt; // local fixed-point variable for speed rate limiter
static int32_t steerFixdt; // local fixed-point variable for steering low-pass filter
static int32_t speedFixdt; // local fixed-point variable for speed low-pass filter
#endif
static uint32_t buzzerTimer_prev = 0;
static uint32_t inactivity_timeout_counter;
static MultipleTap MultipleTapBrake; // define multiple tap functionality for the Brake pedal
int main(void) {
HAL_Init();
__HAL_RCC_AFIO_CLK_ENABLE();
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
/* System interrupt init*/
/* MemoryManagement_IRQn interrupt configuration */
HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0);
/* BusFault_IRQn interrupt configuration */
HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0);
/* UsageFault_IRQn interrupt configuration */
HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0);
/* SVCall_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0);
/* DebugMonitor_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0);
/* PendSV_IRQn interrupt configuration */
HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0);
/* SysTick_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
SystemClock_Config();
__HAL_RCC_DMA1_CLK_DISABLE();
MX_GPIO_Init();
MX_TIM_Init();
MX_ADC1_Init();
MX_ADC2_Init();
BLDC_Init(); // BLDC Controller Init
HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, GPIO_PIN_SET); // Activate Latch
Input_Lim_Init(); // Input Limitations Init
Input_Init(); // Input Init
HAL_ADC_Start(&hadc1);
HAL_ADC_Start(&hadc2);
poweronMelody();
HAL_GPIO_WritePin(LED_PORT, LED_PIN, GPIO_PIN_SET);
int32_t board_temp_adcFixdt = adc_buffer.temp << 16; // Fixed-point filter output initialized with current ADC converted to fixed-point
int16_t board_temp_adcFilt = adc_buffer.temp;
// Loop until button is released
while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); }
while(1) {
if (buzzerTimer - buzzerTimer_prev > 16*DELAY_IN_MAIN_LOOP) { // 1 ms = 16 ticks buzzerTimer
readCommand(); // Read Command: input1[inIdx].cmd, input2[inIdx].cmd
calcAvgSpeed(); // Calculate average measured speed: speedAvg, speedAvgAbs
#ifndef VARIANT_TRANSPOTTER
// ####### MOTOR ENABLING: Only if the initial input is very small (for SAFETY) #######
if (enable == 0 && (!rtY_Left.z_errCode && !rtY_Right.z_errCode) && (input1[inIdx].cmd > -50 && input1[inIdx].cmd < 50) && (input2[inIdx].cmd > -50 && input2[inIdx].cmd < 50)){
beepShort(6); // make 2 beeps indicating the motor enable
beepShort(4); HAL_Delay(100);
steerFixdt = speedFixdt = 0; // reset filters
enable = 1; // enable motors
#if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3)
printf("-- Motors enabled --\r\n");
#endif
}
// ####### VARIANT_HOVERCAR #######
#if defined(VARIANT_HOVERCAR) || defined(VARIANT_SKATEBOARD) || defined(ELECTRIC_BRAKE_ENABLE)
uint16_t speedBlend; // Calculate speed Blend, a number between [0, 1] in fixdt(0,16,15)
speedBlend = (uint16_t)(((CLAMP(speedAvgAbs,10,60) - 10) << 15) / 50); // speedBlend [0,1] is within [10 rpm, 60rpm]
#endif
#ifdef STANDSTILL_HOLD_ENABLE
standstillHold(); // Apply Standstill Hold functionality. Only available and makes sense for VOLTAGE or TORQUE Mode
#endif
#ifdef VARIANT_HOVERCAR
if (inIdx == CONTROL_ADC) { // Only use use implementation below if pedals are in use (ADC input)
if (speedAvgAbs < 60) { // Check if Hovercar is physically close to standstill to enable Double tap detection on Brake pedal for Reverse functionality
multipleTapDet(input1[inIdx].cmd, HAL_GetTick(), &MultipleTapBrake); // Brake pedal in this case is "input1" variable
}
if (input1[inIdx].cmd > 30) { // If Brake pedal (input1) is pressed, bring to 0 also the Throttle pedal (input2) to avoid "Double pedal" driving
input2[inIdx].cmd = (int16_t)((input2[inIdx].cmd * speedBlend) >> 15);
cruiseControl((uint8_t)rtP_Left.b_cruiseCtrlEna); // Cruise control deactivated by Brake pedal if it was active
}
}
#endif
#ifdef ELECTRIC_BRAKE_ENABLE
electricBrake(speedBlend, MultipleTapBrake.b_multipleTap); // Apply Electric Brake. Only available and makes sense for TORQUE Mode
#endif
#ifdef VARIANT_HOVERCAR
if (inIdx == CONTROL_ADC) { // Only use use implementation below if pedals are in use (ADC input)
if (speedAvg > 0) { // Make sure the Brake pedal is opposite to the direction of motion AND it goes to 0 as we reach standstill (to avoid Reverse driving by Brake pedal)
input1[inIdx].cmd = (int16_t)((-input1[inIdx].cmd * speedBlend) >> 15);
} else {
input1[inIdx].cmd = (int16_t)(( input1[inIdx].cmd * speedBlend) >> 15);
}
}
#endif
#ifdef VARIANT_SKATEBOARD
if (input2[inIdx].cmd < 0) { // When Throttle is negative, it acts as brake. This condition is to make sure it goes to 0 as we reach standstill (to avoid Reverse driving)
if (speedAvg > 0) { // Make sure the braking is opposite to the direction of motion
input2[inIdx].cmd = (int16_t)(( input2[inIdx].cmd * speedBlend) >> 15);
} else {
input2[inIdx].cmd = (int16_t)((-input2[inIdx].cmd * speedBlend) >> 15);
}
}
#endif
// ####### LOW-PASS FILTER #######
rateLimiter16(input1[inIdx].cmd , RATE, &steerRateFixdt);
rateLimiter16(input2[inIdx].cmd , RATE, &speedRateFixdt);
filtLowPass32(steerRateFixdt >> 4, FILTER, &steerFixdt);
filtLowPass32(speedRateFixdt >> 4, FILTER, &speedFixdt);
steer = (int16_t)(steerFixdt >> 16); // convert fixed-point to integer
speed = (int16_t)(speedFixdt >> 16); // convert fixed-point to integer
// ####### VARIANT_HOVERCAR #######
#ifdef VARIANT_HOVERCAR
if (inIdx == CONTROL_ADC) { // Only use use implementation below if pedals are in use (ADC input)
if (!MultipleTapBrake.b_multipleTap) { // Check driving direction
speed = steer + speed; // Forward driving: in this case steer = Brake, speed = Throttle
} else {
speed = steer - speed; // Reverse driving: in this case steer = Brake, speed = Throttle
}
steer = 0; // Do not apply steering to avoid side effects if STEER_COEFFICIENT is NOT 0
}
#endif
// ####### MIXER #######
// cmdR = CLAMP((int)(speed * SPEED_COEFFICIENT - steer * STEER_COEFFICIENT), INPUT_MIN, INPUT_MAX);
// cmdL = CLAMP((int)(speed * SPEED_COEFFICIENT + steer * STEER_COEFFICIENT), INPUT_MIN, INPUT_MAX);
mixerFcn(speed << 4, steer << 4, &cmdR, &cmdL); // This function implements the equations above
// ####### SET OUTPUTS (if the target change is less than +/- 100) #######
#ifdef INVERT_R_DIRECTION
pwmr = cmdR;
#else
pwmr = -cmdR;
#endif
#ifdef INVERT_L_DIRECTION
pwml = -cmdL;
#else
pwml = cmdL;
#endif
#endif
#ifdef VARIANT_TRANSPOTTER
distance = CLAMP(input1[inIdx].cmd - 180, 0, 4095);
steering = (input2[inIdx].cmd - 2048) / 2048.0;
distanceErr = distance - (int)(setDistance * 1345);
if (nunchuk_connected == 0) {
cmdL = cmdL * 0.8f + (CLAMP(distanceErr + (steering*((float)MAX(ABS(distanceErr), 50)) * ROT_P), -850, 850) * -0.2f);
cmdR = cmdR * 0.8f + (CLAMP(distanceErr - (steering*((float)MAX(ABS(distanceErr), 50)) * ROT_P), -850, 850) * -0.2f);
if (distanceErr > 0) {
enable = 1;
}
if (distanceErr > -300) {
#ifdef INVERT_R_DIRECTION
pwmr = cmdR;
#else
pwmr = -cmdR;
#endif
#ifdef INVERT_L_DIRECTION
pwml = -cmdL;
#else
pwml = cmdL;
#endif
if (checkRemote) {
if (!HAL_GPIO_ReadPin(LED_PORT, LED_PIN)) {
//enable = 1;
} else {
enable = 0;
}
}
} else {
enable = 0;
}
timeoutCntGen = 0;
timeoutFlgGen = 0;
}
if (timeoutFlgGen) {
pwml = 0;
pwmr = 0;
enable = 0;
#ifdef SUPPORT_LCD
LCD_SetLocation(&lcd, 0, 0); LCD_WriteString(&lcd, "Len:");
LCD_SetLocation(&lcd, 8, 0); LCD_WriteString(&lcd, "m(");
LCD_SetLocation(&lcd, 14, 0); LCD_WriteString(&lcd, "m)");
#endif
HAL_Delay(1000);
nunchuk_connected = 0;
}
if ((distance / 1345.0) - setDistance > 0.5 && (lastDistance / 1345.0) - setDistance > 0.5) { // Error, robot too far away!
enable = 0;
beepLong(5);
#ifdef SUPPORT_LCD
LCD_ClearDisplay(&lcd);
HAL_Delay(5);
LCD_SetLocation(&lcd, 0, 0); LCD_WriteString(&lcd, "Emergency Off!");
LCD_SetLocation(&lcd, 0, 1); LCD_WriteString(&lcd, "Keeper too fast.");
#endif
poweroff();
}
#ifdef SUPPORT_NUNCHUK
if (transpotter_counter % 500 == 0) {
if (nunchuk_connected == 0 && enable == 0) {
if (Nunchuk_Ping()) {
HAL_Delay(500);
Nunchuk_Init();
#ifdef SUPPORT_LCD
LCD_SetLocation(&lcd, 0, 0); LCD_WriteString(&lcd, "Nunchuk Control");
#endif
timeoutCntGen = 0;
timeoutFlgGen = 0;
HAL_Delay(1000);
nunchuk_connected = 1;
}
}
}
#endif
#ifdef SUPPORT_LCD
if (transpotter_counter % 100 == 0) {
if (LCDerrorFlag == 1 && enable == 0) {
} else {
if (nunchuk_connected == 0) {
LCD_SetLocation(&lcd, 4, 0); LCD_WriteFloat(&lcd,distance/1345.0,2);
LCD_SetLocation(&lcd, 10, 0); LCD_WriteFloat(&lcd,setDistance,2);
}
LCD_SetLocation(&lcd, 4, 1); LCD_WriteFloat(&lcd,batVoltage, 1);
// LCD_SetLocation(&lcd, 11, 1); LCD_WriteFloat(&lcd,MAX(ABS(currentR), ABS(currentL)),2);
}
}
#endif
transpotter_counter++;
#endif
// ####### SIDEBOARDS HANDLING #######
#if defined(SIDEBOARD_SERIAL_USART2) && defined(FEEDBACK_SERIAL_USART2)
sideboardLeds(&sideboard_leds_L);
sideboardSensors((uint8_t)Sideboard_L.sensors);
#endif
#if defined(SIDEBOARD_SERIAL_USART3) && defined(FEEDBACK_SERIAL_USART3)
sideboardLeds(&sideboard_leds_R);
sideboardSensors((uint8_t)Sideboard_R.sensors);
#endif
// ####### CALC BOARD TEMPERATURE #######
filtLowPass32(adc_buffer.temp, TEMP_FILT_COEF, &board_temp_adcFixdt);
board_temp_adcFilt = (int16_t)(board_temp_adcFixdt >> 16); // convert fixed-point to integer
board_temp_deg_c = (TEMP_CAL_HIGH_DEG_C - TEMP_CAL_LOW_DEG_C) * (board_temp_adcFilt - TEMP_CAL_LOW_ADC) / (TEMP_CAL_HIGH_ADC - TEMP_CAL_LOW_ADC) + TEMP_CAL_LOW_DEG_C;
// ####### CALC CALIBRATED BATTERY VOLTAGE #######
batVoltageCalib = batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC;
// ####### CALC DC LINK CURRENT #######
left_dc_curr = -(rtU_Left.i_DCLink * 100) / A2BIT_CONV; // Left DC Link Current * 100
right_dc_curr = -(rtU_Right.i_DCLink * 100) / A2BIT_CONV; // Right DC Link Current * 100
dc_curr = left_dc_curr + right_dc_curr; // Total DC Link Current * 100
// ####### DEBUG SERIAL OUT #######
#if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3)
if (main_loop_counter % 25 == 0) { // Send data periodically every 125 ms
#if defined(DEBUG_SERIAL_PROTOCOL)
process_debug();
#else
printf("in1:%i in2:%i cmdL:%i cmdR:%i BatADC:%i BatV:%i TempADC:%i Temp:%i\r\n",
input1[inIdx].raw, // 1: INPUT1
input2[inIdx].raw, // 2: INPUT2
cmdL, // 3: output command: [-1000, 1000]
cmdR, // 4: output command: [-1000, 1000]
adc_buffer.batt1, // 5: for battery voltage calibration
batVoltageCalib, // 6: for verifying battery voltage calibration
board_temp_adcFilt, // 7: for board temperature calibration
board_temp_deg_c); // 8: for verifying board temperature calibration
#endif
}
#endif
// ####### FEEDBACK SERIAL OUT #######
#if defined(FEEDBACK_SERIAL_USART2) || defined(FEEDBACK_SERIAL_USART3)
if (main_loop_counter % 2 == 0) { // Send data periodically every 10 ms
Feedback.start = (uint16_t)SERIAL_START_FRAME;
Feedback.cmd1 = (int16_t)input1[inIdx].cmd;
Feedback.cmd2 = (int16_t)input2[inIdx].cmd;
Feedback.speedR_meas = (int16_t)rtY_Right.n_mot;
Feedback.speedL_meas = (int16_t)rtY_Left.n_mot;
Feedback.batVoltage = (int16_t)batVoltageCalib;
Feedback.boardTemp = (int16_t)board_temp_deg_c;
#if defined(FEEDBACK_SERIAL_USART2)
if(__HAL_DMA_GET_COUNTER(huart2.hdmatx) == 0) {
Feedback.cmdLed = (uint16_t)sideboard_leds_L;
Feedback.checksum = (uint16_t)(Feedback.start ^ Feedback.cmd1 ^ Feedback.cmd2 ^ Feedback.speedR_meas ^ Feedback.speedL_meas
^ Feedback.batVoltage ^ Feedback.boardTemp ^ Feedback.cmdLed);
HAL_UART_Transmit_DMA(&huart2, (uint8_t *)&Feedback, sizeof(Feedback));
}
#endif
#if defined(FEEDBACK_SERIAL_USART3)
if(__HAL_DMA_GET_COUNTER(huart3.hdmatx) == 0) {
Feedback.cmdLed = (uint16_t)sideboard_leds_R;
Feedback.checksum = (uint16_t)(Feedback.start ^ Feedback.cmd1 ^ Feedback.cmd2 ^ Feedback.speedR_meas ^ Feedback.speedL_meas
^ Feedback.batVoltage ^ Feedback.boardTemp ^ Feedback.cmdLed);
HAL_UART_Transmit_DMA(&huart3, (uint8_t *)&Feedback, sizeof(Feedback));
}
#endif
}
#endif
// ####### POWEROFF BY POWER-BUTTON #######
poweroffPressCheck();
// ####### BEEP AND EMERGENCY POWEROFF #######
if ((TEMP_POWEROFF_ENABLE && board_temp_deg_c >= TEMP_POWEROFF && speedAvgAbs < 20) || (batVoltage < BAT_DEAD && speedAvgAbs < 20)) { // poweroff before mainboard burns OR low bat 3
poweroff();
} else if (rtY_Left.z_errCode || rtY_Right.z_errCode) { // 1 beep (low pitch): Motor error, disable motors
enable = 0;
beepCount(1, 24, 1);
} else if (timeoutFlgADC) { // 2 beeps (low pitch): ADC timeout
beepCount(2, 24, 1);
} else if (timeoutFlgSerial) { // 3 beeps (low pitch): Serial timeout
beepCount(3, 24, 1);
} else if (timeoutFlgGen) { // 4 beeps (low pitch): General timeout (PPM, PWM, Nunchuk)
beepCount(4, 24, 1);
} else if (TEMP_WARNING_ENABLE && board_temp_deg_c >= TEMP_WARNING) { // 5 beeps (low pitch): Mainboard temperature warning
beepCount(5, 24, 1);
} else if (BAT_LVL1_ENABLE && batVoltage < BAT_LVL1) { // 1 beep fast (medium pitch): Low bat 1
beepCount(0, 10, 6);
} else if (BAT_LVL2_ENABLE && batVoltage < BAT_LVL2) { // 1 beep slow (medium pitch): Low bat 2
beepCount(0, 10, 30);
} else if (BEEPS_BACKWARD && ((speed < -50 && speedAvg < 0) || MultipleTapBrake.b_multipleTap)) { // 1 beep fast (high pitch): Backward spinning motors
beepCount(0, 5, 1);
backwardDrive = 1;
} else { // do not beep
beepCount(0, 0, 0);
backwardDrive = 0;
}
// ####### INACTIVITY TIMEOUT #######
if (abs(cmdL) > 50 || abs(cmdR) > 50) {
inactivity_timeout_counter = 0;
} else {
inactivity_timeout_counter++;
}
if (inactivity_timeout_counter > (INACTIVITY_TIMEOUT * 60 * 1000) / (DELAY_IN_MAIN_LOOP + 1)) { // rest of main loop needs maybe 1ms
poweroff();
}
// HAL_GPIO_TogglePin(LED_PORT, LED_PIN); // This is to measure the main() loop duration with an oscilloscope connected to LED_PIN
// Update states
inIdx_prev = inIdx;
buzzerTimer_prev = buzzerTimer;
main_loop_counter++;
}
}
}
// ===========================================================
/** System Clock Configuration
*/
void SystemClock_Config(void) {
RCC_OscInitTypeDef RCC_OscInitStruct;
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_PeriphCLKInitTypeDef PeriphClkInit;
/**Initializes the CPU, AHB and APB busses clocks
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = 16;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI_DIV2;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16;
HAL_RCC_OscConfig(&RCC_OscInitStruct);
/**Initializes the CPU, AHB and APB busses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2);
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
// PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV8; // 8 MHz
PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV4; // 16 MHz
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
/**Configure the Systick interrupt time
*/
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);
/**Configure the Systick
*/
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
/* SysTick_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
}