From 76a27b086c2c728105699c3b6a07603ecfc7c53c Mon Sep 17 00:00:00 2001 From: Candas1 Date: Tue, 27 Oct 2020 19:22:23 +0100 Subject: [PATCH 01/26] Add function for MAP --- Inc/defines.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Inc/defines.h b/Inc/defines.h index 1aebdf1..5c53214 100644 --- a/Inc/defines.h +++ b/Inc/defines.h @@ -181,6 +181,8 @@ #define MIN3(a, b, c) MIN(a, MIN(b, c)) #define MAX3(a, b, c) MAX(a, MAX(b, c)) #define ARRAY_LEN(x) (uint32_t)(sizeof(x) / sizeof(*(x))) +#define MAP(x, in_min, in_max, out_min, out_max) ((((x - in_min) * (out_max - out_min)) / (in_max - in_min)) + out_min ) + typedef struct { uint16_t dcr; From 0ab8e8e5acc3a4ecb064a0b83185ac5dfcc2bdde Mon Sep 17 00:00:00 2001 From: Candas1 Date: Tue, 27 Oct 2020 19:39:12 +0100 Subject: [PATCH 02/26] Improve adddeadband function - Use MAP function - add additional parameter for middle value - use adddeadband function with ADC input when mid resting pot is used --- Src/util.c | 34 +++++++++++++--------------------- 1 file changed, 13 insertions(+), 21 deletions(-) diff --git a/Src/util.c b/Src/util.c index 6de9c31..0349aa2 100644 --- a/Src/util.c +++ b/Src/util.c @@ -565,20 +565,14 @@ void saveConfig() { * Add Dead-band to a signal * This function realizes a dead-band around 0 and scales the input between [out_min, out_max] */ -int addDeadBand(int16_t u, int16_t deadBand, int16_t in_min, int16_t in_max, int16_t out_min, int16_t out_max) { -#if defined(CONTROL_PPM_LEFT) || defined(CONTROL_PPM_RIGHT) || defined(CONTROL_PWM_LEFT) || defined(CONTROL_PWM_RIGHT) - int outVal = 0; - if(u > -deadBand && u < deadBand) { - outVal = 0; +int addDeadBand(int16_t u, int16_t deadBand, int16_t in_min, int16_t in_mid, int16_t in_max, int16_t out_min, int16_t out_max) { + if(u > in_mid - deadBand && u < in_mid + deadBand) { + return 0; } else if(u > 0) { - outVal = (out_max * CLAMP(u - deadBand, 0, in_max - deadBand)) / (in_max - deadBand); + return MAP(u, in_mid + deadband, in_max, 0, out_max); } else { - outVal = (out_min * CLAMP(u + deadBand, in_min + deadBand, 0)) / (in_min + deadBand); - } - return outVal; -#else - return 0; -#endif + return MAP(u, in_mid - deadband, in_min, out_min, 0); + } } /* @@ -757,8 +751,8 @@ void readCommand(void) { #endif #if defined(CONTROL_PPM_LEFT) || defined(CONTROL_PPM_RIGHT) - cmd1 = addDeadBand((ppm_captured_value[0] - 500) * 2, PPM_DEADBAND, PPM_CH1_MIN, PPM_CH1_MAX, INPUT_MIN, INPUT_MAX); - cmd2 = addDeadBand((ppm_captured_value[1] - 500) * 2, PPM_DEADBAND, PPM_CH2_MIN, PPM_CH2_MAX, INPUT_MIN, INPUT_MAX); + cmd1 = addDeadBand((ppm_captured_value[0] - 500) * 2, PPM_DEADBAND, PPM_CH1_MIN, 0, PPM_CH1_MAX, INPUT_MIN, INPUT_MAX); + cmd2 = addDeadBand((ppm_captured_value[1] - 500) * 2, PPM_DEADBAND, PPM_CH2_MIN, 0, PPM_CH2_MAX, INPUT_MIN, INPUT_MAX); #ifdef SUPPORT_BUTTONS button1 = ppm_captured_value[5] > 500; button2 = 0; @@ -770,11 +764,11 @@ void readCommand(void) { #endif #if defined(CONTROL_PWM_LEFT) || defined(CONTROL_PWM_RIGHT) - cmd1 = addDeadBand((pwm_captured_ch1_value - 500) * 2, PWM_DEADBAND, PWM_CH1_MIN, PWM_CH1_MAX, INPUT_MIN, INPUT_MAX); + cmd1 = addDeadBand((pwm_captured_ch1_value - 500) * 2, PWM_DEADBAND, PWM_CH1_MIN, 0, PWM_CH1_MAX, INPUT_MIN, INPUT_MAX); #if !defined(VARIANT_SKATEBOARD) - cmd2 = addDeadBand((pwm_captured_ch2_value - 500) * 2, PWM_DEADBAND, PWM_CH2_MIN, PWM_CH2_MAX, INPUT_MIN, INPUT_MAX); + cmd2 = addDeadBand((pwm_captured_ch2_value - 500) * 2, PWM_DEADBAND, PWM_CH2_MIN, 0, PWM_CH2_MAX, INPUT_MIN, INPUT_MAX); #else - cmd2 = addDeadBand((pwm_captured_ch2_value - 500) * 2, PWM_DEADBAND, PWM_CH2_MIN, PWM_CH2_MAX, PWM_CH2_OUT_MIN, INPUT_MAX); + cmd2 = addDeadBand((pwm_captured_ch2_value - 500) * 2, PWM_DEADBAND, PWM_CH2_MIN, 0, PWM_CH2_MAX, PWM_CH2_OUT_MIN, INPUT_MAX); #endif #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); @@ -785,15 +779,13 @@ void readCommand(void) { #ifdef CONTROL_ADC // ADC values range: 0-4095, see ADC-calibration in config.h #ifdef ADC1_MID_POT - cmd1 = CLAMP((adc_buffer.l_tx2 - ADC1_MID_CAL) * INPUT_MAX / (ADC1_MAX_CAL - ADC1_MID_CAL), 0, INPUT_MAX) - +CLAMP((ADC1_MID_CAL - adc_buffer.l_tx2) * INPUT_MIN / (ADC1_MID_CAL - ADC1_MIN_CAL), INPUT_MIN, 0); // ADC1 + cmd1 = addDeadBand(adc_buffer.l_tx2, ADC_DEADBAND, ADC1_MIN_CAL, ADC1_MID_CAL, ADC1_MAX_CAL, INPUT_MIN, INPUT_MAX); #else cmd1 = CLAMP((adc_buffer.l_tx2 - ADC1_MIN_CAL) * INPUT_MAX / (ADC1_MAX_CAL - ADC1_MIN_CAL), 0, INPUT_MAX); // ADC1 #endif #ifdef ADC2_MID_POT - cmd2 = CLAMP((adc_buffer.l_rx2 - ADC2_MID_CAL) * INPUT_MAX / (ADC2_MAX_CAL - ADC2_MID_CAL), 0, INPUT_MAX) - +CLAMP((ADC2_MID_CAL - adc_buffer.l_rx2) * INPUT_MIN / (ADC2_MID_CAL - ADC2_MIN_CAL), INPUT_MIN, 0); // ADC2 + cmd1 = addDeadBand(adc_buffer.l_rx2, ADC_DEADBAND, ADC1_MIN_CAL, ADC1_MID_CAL, ADC1_MAX_CAL, INPUT_MIN, INPUT_MAX); #else cmd2 = CLAMP((adc_buffer.l_rx2 - ADC2_MIN_CAL) * INPUT_MAX / (ADC2_MAX_CAL - ADC2_MIN_CAL), 0, INPUT_MAX); // ADC2 #endif From df37f6dcc327bac2c2919c57342f92b6e6a3424c Mon Sep 17 00:00:00 2001 From: Candas1 Date: Tue, 27 Oct 2020 19:41:47 +0100 Subject: [PATCH 03/26] Add parameter for ADC deadband --- Inc/config.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Inc/config.h b/Inc/config.h index cbd43e5..a374132 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -254,6 +254,7 @@ // #define ADC_PROTECT_ENA // ADC Protection Enable flag. Use this flag to make sure the ADC is protected when GND or Vcc wire is disconnected #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values + #define ADC_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // #define ADC1_MID_POT // ADC1 middle resting poti: comment-out if NOT a middle resting poti #define ADC1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) #define ADC1_MID 2048 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) From 4ba8a8d82aabbf181ee91fee495adf05bc0723cc Mon Sep 17 00:00:00 2001 From: Candas1 Date: Tue, 27 Oct 2020 20:23:35 +0100 Subject: [PATCH 04/26] Add new parameter to adddeadband function --- Inc/util.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Inc/util.h b/Inc/util.h index 5cba7d2..d238870 100644 --- a/Inc/util.h +++ b/Inc/util.h @@ -69,7 +69,7 @@ void calcAvgSpeed(void); void adcCalibLim(void); void updateCurSpdLim(void); void saveConfig(void); -int addDeadBand(int16_t u, int16_t deadBand, int16_t in_min, int16_t in_max, int16_t out_min, int16_t out_max); +int addDeadBand(int16_t u, int16_t deadBand, int16_t in_min, int16_t in_mid, int16_t in_max, int16_t out_min, int16_t out_max); void standstillHold(int16_t *speedCmd); void electricBrake(uint16_t speedBlend, uint8_t reverseDir); void cruiseControl(uint8_t button); From 5d954a05aaf7ed7557768108dd91f8e91b936a10 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Tue, 27 Oct 2020 20:24:56 +0100 Subject: [PATCH 05/26] Fix typo --- Src/util.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Src/util.c b/Src/util.c index 0349aa2..53789ee 100644 --- a/Src/util.c +++ b/Src/util.c @@ -569,9 +569,9 @@ int addDeadBand(int16_t u, int16_t deadBand, int16_t in_min, int16_t in_mid, int if(u > in_mid - deadBand && u < in_mid + deadBand) { return 0; } else if(u > 0) { - return MAP(u, in_mid + deadband, in_max, 0, out_max); + return MAP(u, in_mid + deadBand, in_max, 0, out_max); } else { - return MAP(u, in_mid - deadband, in_min, out_min, 0); + return MAP(u, in_mid - deadBand, in_min, out_min, 0); } } From 09b2728168b08336a2ab1ae068a0e5c6b6489291 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Tue, 27 Oct 2020 20:38:19 +0100 Subject: [PATCH 06/26] Update util.c --- Src/util.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Src/util.c b/Src/util.c index 53789ee..5d00d02 100644 --- a/Src/util.c +++ b/Src/util.c @@ -785,7 +785,7 @@ void readCommand(void) { #endif #ifdef ADC2_MID_POT - cmd1 = addDeadBand(adc_buffer.l_rx2, ADC_DEADBAND, ADC1_MIN_CAL, ADC1_MID_CAL, ADC1_MAX_CAL, INPUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(adc_buffer.l_rx2, ADC_DEADBAND, ADC1_MIN_CAL, ADC1_MID_CAL, ADC1_MAX_CAL, INPUT_MIN, INPUT_MAX); #else cmd2 = CLAMP((adc_buffer.l_rx2 - ADC2_MIN_CAL) * INPUT_MAX / (ADC2_MAX_CAL - ADC2_MIN_CAL), 0, INPUT_MAX); // ADC2 #endif From d7880dafeb9a55857fe00c5d87c5db98c018f710 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Tue, 27 Oct 2020 20:44:52 +0100 Subject: [PATCH 07/26] Update util.c --- Src/util.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Src/util.c b/Src/util.c index 5d00d02..d1e8926 100644 --- a/Src/util.c +++ b/Src/util.c @@ -785,7 +785,7 @@ void readCommand(void) { #endif #ifdef ADC2_MID_POT - cmd2 = addDeadBand(adc_buffer.l_rx2, ADC_DEADBAND, ADC1_MIN_CAL, ADC1_MID_CAL, ADC1_MAX_CAL, INPUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(adc_buffer.l_rx2, ADC_DEADBAND, ADC2_MIN_CAL, ADC2_MID_CAL, ADC2_MAX_CAL, INPUT_MIN, INPUT_MAX); #else cmd2 = CLAMP((adc_buffer.l_rx2 - ADC2_MIN_CAL) * INPUT_MAX / (ADC2_MAX_CAL - ADC2_MIN_CAL), 0, INPUT_MAX); // ADC2 #endif From 1b32555fb08d65367c38fc591b327969d86ac1dc Mon Sep 17 00:00:00 2001 From: Candas1 Date: Wed, 28 Oct 2020 09:26:26 +0100 Subject: [PATCH 08/26] Update util.c --- Src/util.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Src/util.c b/Src/util.c index d1e8926..09c1001 100644 --- a/Src/util.c +++ b/Src/util.c @@ -781,12 +781,14 @@ void readCommand(void) { #ifdef ADC1_MID_POT cmd1 = addDeadBand(adc_buffer.l_tx2, ADC_DEADBAND, ADC1_MIN_CAL, ADC1_MID_CAL, ADC1_MAX_CAL, INPUT_MIN, INPUT_MAX); #else + // cmd1 = MAP( adc_buffer.l_tx2 , ADC1_MIN_CAL, ADC1_MAX_CAL, 0, INPUT_MAX ); // ADC1 cmd1 = CLAMP((adc_buffer.l_tx2 - ADC1_MIN_CAL) * INPUT_MAX / (ADC1_MAX_CAL - ADC1_MIN_CAL), 0, INPUT_MAX); // ADC1 #endif #ifdef ADC2_MID_POT cmd2 = addDeadBand(adc_buffer.l_rx2, ADC_DEADBAND, ADC2_MIN_CAL, ADC2_MID_CAL, ADC2_MAX_CAL, INPUT_MIN, INPUT_MAX); #else + // cmd2 = MAP( adc_buffer.l_rx2 , ADC2_MIN_CAL, ADC2_MAX_CAL, 0, INPUT_MAX ); // ADC2 cmd2 = CLAMP((adc_buffer.l_rx2 - ADC2_MIN_CAL) * INPUT_MAX / (ADC2_MAX_CAL - ADC2_MIN_CAL), 0, INPUT_MAX); // ADC2 #endif From 78246f4e53dff87348e5449ce11b4edfc20ac347 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Wed, 28 Oct 2020 19:02:21 +0100 Subject: [PATCH 09/26] Update util.c --- Src/util.c | 73 +++++++++++++++++++++++++++++------------------------- 1 file changed, 39 insertions(+), 34 deletions(-) diff --git a/Src/util.c b/Src/util.c index 09c1001..3288fc8 100644 --- a/Src/util.c +++ b/Src/util.c @@ -740,36 +740,33 @@ void readCommand(void) { #if defined(CONTROL_NUNCHUK) || defined(SUPPORT_NUNCHUK) if (nunchuk_connected != 0) { Nunchuk_Read(); - cmd1 = CLAMP((nunchuk_data[0] - 127) * 8, INPUT_MIN, INPUT_MAX); // x - axis. Nunchuk joystick readings range 30 - 230 - cmd2 = CLAMP((nunchuk_data[1] - 128) * 8, INPUT_MIN, INPUT_MAX); // y - axis - - #ifdef SUPPORT_BUTTONS - button1 = (uint8_t)nunchuk_data[5] & 1; - button2 = (uint8_t)(nunchuk_data[5] >> 1) & 1; - #endif + cmd1_in = (nunchuk_data[0] - 127) * 8; // X axis 0-255 + cmd2_in = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 + + #ifdef SUPPORT_BUTTONS + button1 = (uint8_t)nunchuk_data[5] & 1; + button2 = (uint8_t)(nunchuk_data[5] >> 1) & 1; + #endif } #endif #if defined(CONTROL_PPM_LEFT) || defined(CONTROL_PPM_RIGHT) - cmd1 = addDeadBand((ppm_captured_value[0] - 500) * 2, PPM_DEADBAND, PPM_CH1_MIN, 0, PPM_CH1_MAX, INPUT_MIN, INPUT_MAX); - cmd2 = addDeadBand((ppm_captured_value[1] - 500) * 2, PPM_DEADBAND, PPM_CH2_MIN, 0, PPM_CH2_MAX, INPUT_MIN, INPUT_MAX); - #ifdef SUPPORT_BUTTONS - button1 = ppm_captured_value[5] > 500; - button2 = 0; + cmd1_in = (ppm_captured_value[0] - 500) * 2; + cmd2_in = (ppm_captured_value[1] - 500) * 2; + #ifdef SUPPORT_BUTTONS + button1 = ppm_captured_value[5] > 500; + button2 = 0; #elif defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); - #endif + #endif // float scale = ppm_captured_value[2] / 1000.0f; // not used for now, uncomment if needed #endif #if defined(CONTROL_PWM_LEFT) || defined(CONTROL_PWM_RIGHT) - cmd1 = addDeadBand((pwm_captured_ch1_value - 500) * 2, PWM_DEADBAND, PWM_CH1_MIN, 0, PWM_CH1_MAX, INPUT_MIN, INPUT_MAX); - #if !defined(VARIANT_SKATEBOARD) - cmd2 = addDeadBand((pwm_captured_ch2_value - 500) * 2, PWM_DEADBAND, PWM_CH2_MIN, 0, PWM_CH2_MAX, INPUT_MIN, INPUT_MAX); - #else - cmd2 = addDeadBand((pwm_captured_ch2_value - 500) * 2, PWM_DEADBAND, PWM_CH2_MIN, 0, PWM_CH2_MAX, PWM_CH2_OUT_MIN, INPUT_MAX); - #endif + cmd1_in = (pwm_captured_ch1_value - 500) * 2; + cmd2_in = (pwm_captured_ch2_value - 500) * 2; + #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); @@ -778,19 +775,8 @@ void readCommand(void) { #ifdef CONTROL_ADC // ADC values range: 0-4095, see ADC-calibration in config.h - #ifdef ADC1_MID_POT - cmd1 = addDeadBand(adc_buffer.l_tx2, ADC_DEADBAND, ADC1_MIN_CAL, ADC1_MID_CAL, ADC1_MAX_CAL, INPUT_MIN, INPUT_MAX); - #else - // cmd1 = MAP( adc_buffer.l_tx2 , ADC1_MIN_CAL, ADC1_MAX_CAL, 0, INPUT_MAX ); // ADC1 - cmd1 = CLAMP((adc_buffer.l_tx2 - ADC1_MIN_CAL) * INPUT_MAX / (ADC1_MAX_CAL - ADC1_MIN_CAL), 0, INPUT_MAX); // ADC1 - #endif - - #ifdef ADC2_MID_POT - cmd2 = addDeadBand(adc_buffer.l_rx2, ADC_DEADBAND, ADC2_MIN_CAL, ADC2_MID_CAL, ADC2_MAX_CAL, INPUT_MIN, INPUT_MAX); - #else - // cmd2 = MAP( adc_buffer.l_rx2 , ADC2_MIN_CAL, ADC2_MAX_CAL, 0, INPUT_MAX ); // ADC2 - cmd2 = CLAMP((adc_buffer.l_rx2 - ADC2_MIN_CAL) * INPUT_MAX / (ADC2_MAX_CAL - ADC2_MIN_CAL), 0, INPUT_MAX); // ADC2 - #endif + cmd1_in = adc_buffer.l_tx2; + cmd2_in = adc_buffer.l_rx2; #ifdef ADC_PROTECT_ENA if (adc_buffer.l_tx2 >= (ADC1_MIN_CAL - ADC_PROTECT_THRESH) && adc_buffer.l_tx2 <= (ADC1_MAX_CAL + ADC_PROTECT_THRESH) && @@ -822,8 +808,8 @@ void readCommand(void) { for (uint8_t i = 0; i < (IBUS_NUM_CHANNELS * 2); i+=2) { ibus_captured_value[(i/2)] = CLAMP(command.channels[i] + (command.channels[i+1] << 8) - 1000, 0, INPUT_MAX); // 1000-2000 -> 0-1000 } - cmd1 = CLAMP((ibus_captured_value[0] - 500) * 2, INPUT_MIN, INPUT_MAX); - cmd2 = CLAMP((ibus_captured_value[1] - 500) * 2, INPUT_MIN, INPUT_MAX); + cmd1_in = (ibus_captured_value[0] - 500) * 2; + cmd2_in = (ibus_captured_value[1] - 500) * 2; #else if (IN_RANGE(command.steer, INPUT_MIN, INPUT_MAX) && IN_RANGE(command.speed, INPUT_MIN, INPUT_MAX)) { cmd1 = command.steer; @@ -855,6 +841,25 @@ void readCommand(void) { #if defined(SIDEBOARD_SERIAL_USART2) && defined(SIDEBOARD_SERIAL_USART3) timeoutFlagSerial = timeoutFlagSerial_L || timeoutFlagSerial_R; #endif + + cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN, INPUT1_MID, INPUT1_MAX, INPUT_MIN, INPUT_MAX); + #if !defined(VARIANT_SKATEBOARD) + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_MIN, INPUT_MAX); + #else + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_OUT_MIN, INPUT_MAX); + #endif + + #ifdef ADC1_MID_POT + + #else + cmd1 = MAP( adc_buffer.l_tx2 , ADC1_MIN_CAL, ADC1_MAX_CAL, 0, INPUT_MAX ); // ADC1 + #endif + + #ifdef ADC2_MID_POT + + #else + cmd2 = MAP( adc_buffer.l_rx2 , ADC2_MIN_CAL, ADC2_MAX_CAL, 0, INPUT_MAX ); // ADC2 + #endif #ifdef VARIANT_HOVERCAR brakePressed = (uint8_t)(cmd1 > 50); From dd09115e956db8d80b327fc3cd00293ce672eb37 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Wed, 28 Oct 2020 23:34:29 +0100 Subject: [PATCH 10/26] Update util.c --- Src/util.c | 264 +++++++++++++++++++++++++---------------------------- 1 file changed, 126 insertions(+), 138 deletions(-) diff --git a/Src/util.c b/Src/util.c index 3288fc8..eb8a447 100644 --- a/Src/util.c +++ b/Src/util.c @@ -88,6 +88,8 @@ ExtY rtY_Right; /* External outputs */ int16_t cmd1; // normalized input value. -1000 to 1000 int16_t cmd2; // normalized input value. -1000 to 1000 +int16_t cmd1_in; // normalized input value. -1000 to 1000 +int16_t cmd2_in; // normalized input value. -1000 to 1000 int16_t speedAvg; // average measured speed int16_t speedAvgAbs; // average measured speed in absolute @@ -125,24 +127,24 @@ uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1300}; // Dummy virtual address to av static int16_t INPUT_MAX; // [-] Input target maximum limitation static int16_t INPUT_MIN; // [-] Input target minimum limitation -#ifdef CONTROL_ADC - static uint8_t cur_spd_valid = 0; - static uint8_t adc_cal_valid = 0; - static uint16_t ADC1_MIN_CAL = ADC1_MIN; - static uint16_t ADC1_MAX_CAL = ADC1_MAX; - static uint16_t ADC2_MIN_CAL = ADC2_MIN; - static uint16_t ADC2_MAX_CAL = ADC2_MAX; - #ifdef ADC1_MID_POT - static uint16_t ADC1_MID_CAL = ADC1_MID; - #else - static uint16_t ADC1_MID_CAL = 0; - #endif - #ifdef ADC1_MID_POT - static uint16_t ADC2_MID_CAL = ADC2_MID; - #else - static uint16_t ADC2_MID_CAL = 0; - #endif + +static uint8_t cur_spd_valid = 0; +static uint8_t adc_cal_valid = 0; +static uint16_t INPUT1_MIN_CAL = INPUT1_MIN; +static uint16_t INPUT1_MAX_CAL = INPUT1_MAX; +static uint16_t INPUT2_MIN_CAL = INPUT2_MIN; +static uint16_t INPUT2_MAX_CAL = INPUT2_MAX; +#ifdef INPUT1_MID_POT +static uint16_t INPUT1_MID_CAL = INPUT1_MID; +#else +static uint16_t INPUT1_MID_CAL = 0; #endif +#ifdef INPUT1_MID_POT +static uint16_t INPUT2_MID_CAL = INPUT2_MID; +#else +static uint16_t INPUT2_MID_CAL = 0; +#endif + #if defined(CONTROL_ADC) && defined(ADC_PROTECT_ENA) static int16_t timeoutCntADC = 0; // Timeout counter for ADC Protection @@ -278,12 +280,12 @@ void Input_Init(void) { EE_Init(); /* EEPROM Init */ EE_ReadVariable(VirtAddVarTab[0], &writeCheck); if (writeCheck == FLASH_WRITE_KEY) { - EE_ReadVariable(VirtAddVarTab[1], &ADC1_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[2], &ADC1_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[3], &ADC1_MID_CAL); - EE_ReadVariable(VirtAddVarTab[4], &ADC2_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[5], &ADC2_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[6], &ADC2_MID_CAL); + EE_ReadVariable(VirtAddVarTab[1], &INPUT1_MIN_CAL); + EE_ReadVariable(VirtAddVarTab[2], &INPUT1_MAX_CAL); + EE_ReadVariable(VirtAddVarTab[3], &INPUT1_MID_CAL); + EE_ReadVariable(VirtAddVarTab[4], &INPUT2_MIN_CAL); + EE_ReadVariable(VirtAddVarTab[5], &INPUT2_MAX_CAL); + EE_ReadVariable(VirtAddVarTab[6], &INPUT2_MID_CAL); EE_ReadVariable(VirtAddVarTab[7], &i_max); EE_ReadVariable(VirtAddVarTab[8], &n_max); rtP_Left.i_max = i_max; @@ -427,65 +429,63 @@ void calcAvgSpeed(void) { * - release potentiometers to the resting postion * - press the power button to confirm or wait for the 20 sec timeout */ -void adcCalibLim(void) { +void inputCalibLim(void) { if (speedAvgAbs > 5) { // do not enter this mode if motors are spinning return; } - #ifdef CONTROL_ADC - consoleLog("ADC calibration started... "); + + consoleLog("Input calibration started... "); - // Inititalization: MIN = a high values, MAX = a low value, - int32_t adc1_fixdt = adc_buffer.l_tx2 << 16; - int32_t adc2_fixdt = adc_buffer.l_rx2 << 16; - uint16_t adc_cal_timeout = 0; - uint16_t ADC1_MIN_temp = 4095; - uint16_t ADC1_MID_temp = 0; - uint16_t ADC1_MAX_temp = 0; - uint16_t ADC2_MIN_temp = 4095; - uint16_t ADC2_MID_temp = 0; - uint16_t ADC2_MAX_temp = 0; + // Inititalization: MIN = a high values, MAX = a low value, + int32_t input1_fixdt = adc_buffer.l_tx2 << 16; + int32_t input2_fixdt = adc_buffer.l_rx2 << 16; + uint16_t input_cal_timeout = 0; + uint16_t INPUT1_MIN_temp = 4095; + uint16_t INPUT1_MID_temp = 0; + uint16_t INPUT1_MAX_temp = 0; + uint16_t INPUT2_MIN_temp = 4095; + uint16_t INPUT2_MID_temp = 0; + uint16_t INPUT2_MAX_temp = 0; - adc_cal_valid = 1; + input_cal_valid = 1; - // Extract MIN, MAX and MID from ADC while the power button is not pressed - while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && adc_cal_timeout++ < 4000) { // 20 sec timeout - filtLowPass32(adc_buffer.l_tx2, FILTER, &adc1_fixdt); - filtLowPass32(adc_buffer.l_rx2, FILTER, &adc2_fixdt); - ADC1_MID_temp = (uint16_t)CLAMP(adc1_fixdt >> 16, 0, 4095); // convert fixed-point to integer - ADC2_MID_temp = (uint16_t)CLAMP(adc2_fixdt >> 16, 0, 4095); - ADC1_MIN_temp = MIN(ADC1_MIN_temp, ADC1_MID_temp); - ADC1_MAX_temp = MAX(ADC1_MAX_temp, ADC1_MID_temp); - ADC2_MIN_temp = MIN(ADC2_MIN_temp, ADC2_MID_temp); - ADC2_MAX_temp = MAX(ADC2_MAX_temp, ADC2_MID_temp); - HAL_Delay(5); - } - - // ADC calibration checks - #ifdef ADC_PROTECT_ENA - if ((ADC1_MIN_temp + 100 - ADC_PROTECT_THRESH) > 0 && (ADC1_MAX_temp - 100 + ADC_PROTECT_THRESH) < 4095 && - (ADC2_MIN_temp + 100 - ADC_PROTECT_THRESH) > 0 && (ADC2_MAX_temp - 100 + ADC_PROTECT_THRESH) < 4095) { - adc_cal_valid = 1; - } else { - adc_cal_valid = 0; - consoleLog("FAIL (ADC out-of-range protection not possible)\n"); - } - #endif - - // Add final ADC margin to have exact 0 and MAX at the minimum and maximum ADC value - if (adc_cal_valid && (ADC1_MAX_temp - ADC1_MIN_temp) > 500 && (ADC2_MAX_temp - ADC2_MIN_temp) > 500) { - ADC1_MIN_CAL = ADC1_MIN_temp + 100; - ADC1_MID_CAL = ADC1_MID_temp; - ADC1_MAX_CAL = ADC1_MAX_temp - 100; - ADC2_MIN_CAL = ADC2_MIN_temp + 100; - ADC2_MID_CAL = ADC2_MID_temp; - ADC2_MAX_CAL = ADC2_MAX_temp - 100; - consoleLog("OK\n"); - } else { - adc_cal_valid = 0; - consoleLog("FAIL (Pots travel too short)\n"); - } + // Extract MIN, MAX and MID from ADC while the power button is not pressed + while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && input_cal_timeout++ < 4000) { // 20 sec timeout + filtLowPass32(cmd1_in, FILTER, &input1_fixdt); + filtLowPass32(cmd2_in, FILTER, &input2_fixdt); + INPUT1_MID_temp = (uint16_t)CLAMP(input1_fixdt >> 16, 0, 4095); // convert fixed-point to integer + INPUT2_MID_temp = (uint16_t)CLAMP(input2_fixdt >> 16, 0, 4095); + INPUT1_MIN_temp = MIN(INPUT1_MIN_temp, INPUT1_MID_temp); + INPUT1_MAX_temp = MAX(INPUT1_MAX_temp, INPUT1_MID_temp); + INPUT2_MIN_temp = MIN(INPUT2_MIN_temp, INPUT2_MID_temp); + INPUT2_MAX_temp = MAX(INPUT2_MAX_temp, INPUT2_MID_temp); + HAL_Delay(5); + } + // ADC calibration checks + #ifdef ADC_PROTECT_ENA + if ((INPUT1_MIN_temp + 100 - ADC_PROTECT_THRESH) > 0 && (INPUT1_MAX_temp - 100 + ADC_PROTECT_THRESH) < 4095 && + (INPUT2_MIN_temp + 100 - ADC_PROTECT_THRESH) > 0 && (INPUT2_MAX_temp - 100 + ADC_PROTECT_THRESH) < 4095) { + input_cal_valid = 1; + } else { + input_cal_valid = 0; + consoleLog("FAIL (ADC out-of-range protection not possible)\n"); + } #endif + + // Add final ADC margin to have exact 0 and MAX at the minimum and maximum ADC value + if (input_cal_valid && (INPUT1_MAX_temp - INPUT1_MIN_temp) > 500 && (INPUT2_MAX_temp - INPUT2_MIN_temp) > 500) { + INPUT1_MIN_CAL = INPUT1_MIN_temp + 100; + INPUT1_MID_CAL = INPUT1_MID_temp; + INPUT1_MAX_CAL = INPUT1_MAX_temp - 100; + INPUT2_MIN_CAL = INPUT2_MIN_temp + 100; + INPUT2_MID_CAL = INPUT2_MID_temp; + INPUT2_MAX_CAL = INPUT2_MAX_temp - 100; + consoleLog("OK\n"); + } else { + input_cal_valid = 0; + consoleLog("FAIL (Pots travel too short)\n"); + } } @@ -548,12 +548,12 @@ void saveConfig() { if (adc_cal_valid || cur_spd_valid) { HAL_FLASH_Unlock(); EE_WriteVariable(VirtAddVarTab[0], FLASH_WRITE_KEY); - EE_WriteVariable(VirtAddVarTab[1], ADC1_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[2], ADC1_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[3], ADC1_MID_CAL); - EE_WriteVariable(VirtAddVarTab[4], ADC2_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[5], ADC2_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[6], ADC2_MID_CAL); + EE_WriteVariable(VirtAddVarTab[1], INPUT1_MIN_CAL); + EE_WriteVariable(VirtAddVarTab[2], INPUT1_MAX_CAL); + EE_WriteVariable(VirtAddVarTab[3], INPUT1_MID_CAL); + EE_WriteVariable(VirtAddVarTab[4], INPUT2_MIN_CAL); + EE_WriteVariable(VirtAddVarTab[5], INPUT2_MAX_CAL); + EE_WriteVariable(VirtAddVarTab[6], INPUT2_MID_CAL); EE_WriteVariable(VirtAddVarTab[7], rtP_Left.i_max); EE_WriteVariable(VirtAddVarTab[8], rtP_Left.n_max); HAL_FLASH_Lock(); @@ -731,21 +731,16 @@ void poweroffPressCheck(void) { #endif } - - -/* =========================== Read Command Function =========================== */ - -void readCommand(void) { - - #if defined(CONTROL_NUNCHUK) || defined(SUPPORT_NUNCHUK) +void readInput(void) { + #if defined(CONTROL_NUNCHUK) || defined(SUPPORT_NUNCHUK) if (nunchuk_connected != 0) { Nunchuk_Read(); cmd1_in = (nunchuk_data[0] - 127) * 8; // X axis 0-255 cmd2_in = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 #ifdef SUPPORT_BUTTONS - button1 = (uint8_t)nunchuk_data[5] & 1; - button2 = (uint8_t)(nunchuk_data[5] >> 1) & 1; + button1 = (uint8_t)nunchuk_data[5] & 1; + button2 = (uint8_t)(nunchuk_data[5] >> 1) & 1; #endif } #endif @@ -756,28 +751,44 @@ void readCommand(void) { #ifdef SUPPORT_BUTTONS button1 = ppm_captured_value[5] > 500; button2 = 0; - #elif defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) - button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); - button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); #endif - // float scale = ppm_captured_value[2] / 1000.0f; // not used for now, uncomment if needed #endif #if defined(CONTROL_PWM_LEFT) || defined(CONTROL_PWM_RIGHT) cmd1_in = (pwm_captured_ch1_value - 500) * 2; cmd2_in = (pwm_captured_ch2_value - 500) * 2; - - #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) - button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); - button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); - #endif #endif #ifdef CONTROL_ADC // ADC values range: 0-4095, see ADC-calibration in config.h cmd1_in = adc_buffer.l_tx2; cmd2_in = adc_buffer.l_rx2; + #endif + #if defined(CONTROL_SERIAL_USART2) || defined(CONTROL_SERIAL_USART3) + // Handle received data validity, timeout and fix out-of-sync if necessary + #ifdef CONTROL_IBUS + for (uint8_t i = 0; i < (IBUS_NUM_CHANNELS * 2); i+=2) { + ibus_captured_value[(i/2)] = CLAMP(command.channels[i] + (command.channels[i+1] << 8) - 1000, 0, INPUT_MAX); // 1000-2000 -> 0-1000 + } + cmd1_in = (ibus_captured_value[0] - 500) * 2; + cmd2_in = (ibus_captured_value[1] - 500) * 2; + #else + if (IN_RANGE(command.steer, INPUT_MIN, INPUT_MAX) && IN_RANGE(command.speed, INPUT_MIN, INPUT_MAX)) { + cmd1_in = command.steer; + cmd2_in = command.speed; + } + #endif + timeoutCnt = 0; + #endif + +} + +/* =========================== Read Command Function =========================== */ + +void readCommand(void) { + readInput(); + #ifdef CONTROL_ADC #ifdef ADC_PROTECT_ENA if (adc_buffer.l_tx2 >= (ADC1_MIN_CAL - ADC_PROTECT_THRESH) && adc_buffer.l_tx2 <= (ADC1_MAX_CAL + ADC_PROTECT_THRESH) && adc_buffer.l_rx2 >= (ADC2_MIN_CAL - ADC_PROTECT_THRESH) && adc_buffer.l_rx2 <= (ADC2_MAX_CAL + ADC_PROTECT_THRESH)) { @@ -795,32 +806,6 @@ void readCommand(void) { } #endif - #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) - button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); - button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); - #endif - timeoutCnt = 0; - #endif - - #if defined(CONTROL_SERIAL_USART2) || defined(CONTROL_SERIAL_USART3) - // Handle received data validity, timeout and fix out-of-sync if necessary - #ifdef CONTROL_IBUS - for (uint8_t i = 0; i < (IBUS_NUM_CHANNELS * 2); i+=2) { - ibus_captured_value[(i/2)] = CLAMP(command.channels[i] + (command.channels[i+1] << 8) - 1000, 0, INPUT_MAX); // 1000-2000 -> 0-1000 - } - cmd1_in = (ibus_captured_value[0] - 500) * 2; - cmd2_in = (ibus_captured_value[1] - 500) * 2; - #else - if (IN_RANGE(command.steer, INPUT_MIN, INPUT_MAX) && IN_RANGE(command.speed, INPUT_MIN, INPUT_MAX)) { - cmd1 = command.steer; - cmd2 = command.speed; - } - #endif - - #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) - button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); - button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); - #endif timeoutCnt = 0; #endif @@ -841,29 +826,32 @@ void readCommand(void) { #if defined(SIDEBOARD_SERIAL_USART2) && defined(SIDEBOARD_SERIAL_USART3) timeoutFlagSerial = timeoutFlagSerial_L || timeoutFlagSerial_R; #endif + + #ifdef INPUT1_MID_POT + cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN, INPUT1_MID, INPUT1_MAX, INPUT_MIN, INPUT_MAX); + #else + cmd1 = MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ); // ADC1 + #endif - cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN, INPUT1_MID, INPUT1_MAX, INPUT_MIN, INPUT_MAX); #if !defined(VARIANT_SKATEBOARD) - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_MIN, INPUT_MAX); + #ifdef INPUT2_MID_POT + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_MIN, INPUT_MAX); + #else + cmd2 = MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ); // ADC2 + #endif #else cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_OUT_MIN, INPUT_MAX); #endif - - #ifdef ADC1_MID_POT - - #else - cmd1 = MAP( adc_buffer.l_tx2 , ADC1_MIN_CAL, ADC1_MAX_CAL, 0, INPUT_MAX ); // ADC1 - #endif - - #ifdef ADC2_MID_POT - - #else - cmd2 = MAP( adc_buffer.l_rx2 , ADC2_MIN_CAL, ADC2_MAX_CAL, 0, INPUT_MAX ); // ADC2 - #endif + #ifdef VARIANT_HOVERCAR brakePressed = (uint8_t)(cmd1 > 50); #endif + + #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) + button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); + button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); + #endif #ifdef VARIANT_TRANSPOTTER #ifdef GAMETRAK_CONNECTION_NORMAL From aaeb44d0b63005aa3ac307aa52577f24149bd13d Mon Sep 17 00:00:00 2001 From: Candas1 Date: Wed, 28 Oct 2020 23:36:24 +0100 Subject: [PATCH 11/26] Update main.c --- Src/main.c | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/Src/main.c b/Src/main.c index da3f99a..68e746c 100644 --- a/Src/main.c +++ b/Src/main.c @@ -407,18 +407,8 @@ int main(void) { // ####### DEBUG SERIAL OUT ####### #if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3) if (main_loop_counter % 25 == 0) { // Send data periodically every 125 ms - #ifdef CONTROL_ADC - setScopeChannel(0, (int16_t)adc_buffer.l_tx2); // 1: ADC1 - setScopeChannel(1, (int16_t)adc_buffer.l_rx2); // 2: ADC2 - #endif - #if defined(CONTROL_PPM_LEFT) || defined(CONTROL_PPM_RIGHT) - setScopeChannel(0, ppm_captured_value[0]); // 1: CH1 - setScopeChannel(1, ppm_captured_value[1]); // 2: CH2 - #endif - #if defined(CONTROL_PWM_LEFT) || defined(CONTROL_PWM_RIGHT) - setScopeChannel(0, (pwm_captured_ch1_value - 500) * 2); // 1: CH1 - setScopeChannel(1, (pwm_captured_ch2_value - 500) * 2); // 2: CH2 - #endif + setScopeChannel(0, (int16_t)cmd1_in); // 1: ADC1 + setScopeChannel(1, (int16_t)cmd2_in); // 2: ADC2 setScopeChannel(2, (int16_t)speedR); // 3: output command: [-1000, 1000] setScopeChannel(3, (int16_t)speedL); // 4: output command: [-1000, 1000] setScopeChannel(4, (int16_t)adc_buffer.batt1); // 5: for battery voltage calibration From e508a2131ad4ae2ac8bd415079caaecf977eb219 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Wed, 28 Oct 2020 23:42:22 +0100 Subject: [PATCH 12/26] Update util.c --- Src/util.c | 52 ++++++++++++++++++++++++++-------------------------- 1 file changed, 26 insertions(+), 26 deletions(-) diff --git a/Src/util.c b/Src/util.c index eb8a447..58267d3 100644 --- a/Src/util.c +++ b/Src/util.c @@ -429,7 +429,7 @@ void calcAvgSpeed(void) { * - release potentiometers to the resting postion * - press the power button to confirm or wait for the 20 sec timeout */ -void inputCalibLim(void) { +void adcCalibLim(void) { if (speedAvgAbs > 5) { // do not enter this mode if motors are spinning return; } @@ -451,6 +451,7 @@ void inputCalibLim(void) { // Extract MIN, MAX and MID from ADC while the power button is not pressed while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && input_cal_timeout++ < 4000) { // 20 sec timeout + readInput(); filtLowPass32(cmd1_in, FILTER, &input1_fixdt); filtLowPass32(cmd2_in, FILTER, &input2_fixdt); INPUT1_MID_temp = (uint16_t)CLAMP(input1_fixdt >> 16, 0, 4095); // convert fixed-point to integer @@ -500,36 +501,35 @@ void updateCurSpdLim(void) { if (speedAvgAbs > 5) { // do not enter this mode if motors are spinning return; } - #ifdef CONTROL_ADC - consoleLog("Torque and Speed limits update started... "); + + consoleLog("Torque and Speed limits update started... "); - int32_t adc1_fixdt = adc_buffer.l_tx2 << 16; - int32_t adc2_fixdt = adc_buffer.l_rx2 << 16; - uint16_t cur_spd_timeout = 0; - uint16_t cur_factor; // fixdt(0,16,16) - uint16_t spd_factor; // fixdt(0,16,16) + int32_t input1_fixdt = cmd1_in << 16; + int32_t input2_fixdt = cmd2_in << 16; + uint16_t cur_spd_timeout = 0; + uint16_t cur_factor; // fixdt(0,16,16) + uint16_t spd_factor; // fixdt(0,16,16) - // Wait for the power button press - while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && cur_spd_timeout++ < 2000) { // 10 sec timeout - filtLowPass32(adc_buffer.l_tx2, FILTER, &adc1_fixdt); - filtLowPass32(adc_buffer.l_rx2, FILTER, &adc2_fixdt); - HAL_Delay(5); - } + // Wait for the power button press + while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && cur_spd_timeout++ < 2000) { // 10 sec timeout + readInput(); + filtLowPass32(cmd1_in, FILTER, &input1_fixdt); + filtLowPass32(cmd2_in, FILTER, &input2_fixdt); + HAL_Delay(5); + } - // Calculate scaling factors - cur_factor = CLAMP((adc1_fixdt - (ADC1_MIN_CAL << 16)) / (ADC1_MAX_CAL - ADC1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A - spd_factor = CLAMP((adc2_fixdt - (ADC2_MIN_CAL << 16)) / (ADC2_MAX_CAL - ADC2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm + // Calculate scaling factors + cur_factor = CLAMP((input1_fixdt - (INPUT1_MIN_CAL << 16)) / (INPUT1_MAX_CAL - INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A + spd_factor = CLAMP((input2_fixdt - (INPUT2_MIN_CAL << 16)) / (INPUT2_MAX_CAL - INPUT2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm + // Update maximum limits + rtP_Left.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) + rtP_Left.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) + rtP_Right.i_max = rtP_Left.i_max; + rtP_Right.n_max = rtP_Left.n_max; - // Update maximum limits - rtP_Left.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) - rtP_Left.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) - rtP_Right.i_max = rtP_Left.i_max; - rtP_Right.n_max = rtP_Left.n_max; + cur_spd_valid = 1; + consoleLog("OK\n"); - cur_spd_valid = 1; - consoleLog("OK\n"); - - #endif } /* From 5dc88b7e02f10d0a7dda6f04a7fc0603767ae052 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Wed, 28 Oct 2020 23:43:19 +0100 Subject: [PATCH 13/26] Update util.h --- Inc/util.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Inc/util.h b/Inc/util.h index d238870..cca2489 100644 --- a/Inc/util.h +++ b/Inc/util.h @@ -80,6 +80,7 @@ void poweroffPressCheck(void); // Read Command Function void readCommand(void); +void readInput(void); void usart2_rx_check(void); void usart3_rx_check(void); #if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3) From 95c912d7577ec4e5d9a97a9fbb38122bf4d54724 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Thu, 29 Oct 2020 00:10:52 +0100 Subject: [PATCH 14/26] Update config.h --- Inc/config.h | 118 ++++++++++++++++++++++++++++++++++++--------------- 1 file changed, 84 insertions(+), 34 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index a374132..2bb459c 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -254,15 +254,16 @@ // #define ADC_PROTECT_ENA // ADC Protection Enable flag. Use this flag to make sure the ADC is protected when GND or Vcc wire is disconnected #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values - #define ADC_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - // #define ADC1_MID_POT // ADC1 middle resting poti: comment-out if NOT a middle resting poti - #define ADC1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) - #define ADC1_MID 2048 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) - #define ADC1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) - // #define ADC2_MID_POT // ADC2 middle resting poti: comment-out if NOT a middle resting poti - #define ADC2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) - #define ADC2_MID 2048 // mid ADC2-value while poti at minimum-position (ADC2_MIN - ADC2_MAX) - #define ADC2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + // #define INPUT1_MID_POT // ADC1 middle resting poti: comment-out if NOT a middle resting poti + #define INPUT1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) + #define INPUT1_MID 2048 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) + #define INPUT1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) + // #define INPUT2_MID_POT // ADC2 middle resting poti: comment-out if NOT a middle resting poti + #define INPUT2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) + #define INPUT2_MID 2048 // mid ADC2-value while poti at minimum-position (ADC2_MIN - ADC2_MAX) + #define INPUT2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! #endif @@ -273,12 +274,23 @@ // ############################ VARIANT_USART SETTINGS ############################ #ifdef VARIANT_USART // #define SIDEBOARD_SERIAL_USART2 - // #define CONTROL_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! For Arduino control check the hoverSerial.ino - // #define FEEDBACK_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! + // #define CONTROL_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! For Arduino control check the hoverSerial.ino + // #define FEEDBACK_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! // #define SIDEBOARD_SERIAL_USART3 - #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 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 INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + // Min / Max values of each channel (use DEBUG to determine these values) + #define INPUT1_MID_POT + #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_MID 0 + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT2_MID_POT + #define INPUT2_MIN -1000 // (-1000 - 0) + #define INPUT2_MID 0 + #define INPUT2_MAX 1000 // (0 - 1000) // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! #endif @@ -295,6 +307,17 @@ * Recommendation: Nunchuk Breakout Board https://github.com/Jan--Henrik/hoverboard-breakout */ #define CONTROL_NUNCHUK // use nunchuk as input. disable FEEDBACK_SERIAL_USART3, DEBUG_SERIAL_USART3! + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + // Min / Max values of each channel (use DEBUG to determine these values) + #define INPUT1_MID_POT + #define INPUT1_MIN -1024 // (-1000 - 0) + #define INPUT1_MID 0 + #define INPUT1_MAX 1024 // (0 - 1000) + #define INPUT2_MID_POT + #define INPUT2_MIN -1024 // (-1000 - 0) + #define INPUT2_MID 0 + #define INPUT2_MAX 1024 // (0 - 1000) // # maybe good for ARMCHAIR # #define FILTER 3276 // 0.05f #define SPEED_COEFFICIENT 8192 // 0.5f @@ -318,13 +341,18 @@ #else #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif - #define PPM_NUM_CHANNELS 6 // total number of PPM channels to receive, even if they are not used. - #define PPM_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define PPM_NUM_CHANNELS 6 // total number of PPM channels to receive, even if they are not used. + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define PPM_CH1_MAX 1000 // (0 - 1000) - #define PPM_CH1_MIN -1000 // (-1000 - 0) - #define PPM_CH2_MAX 1000 // (0 - 1000) - #define PPM_CH2_MIN -1000 // (-1000 - 0) + #define INPUT1_MID_POT + #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_MID 0 + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT2_MID_POT + #define INPUT2_MIN -1000 // (-1000 - 0) + #define INPUT2_MID 0 + #define INPUT2_MAX 1000 // (0 - 1000) // #define SUPPORT_BUTTONS // Define for PPM buttons support // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! @@ -340,12 +368,17 @@ */ #define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! // #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! - #define PWM_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define PWM_CH1_MAX 1000 // (0 - 1000) - #define PWM_CH1_MIN -1000 // (-1000 - 0) - #define PWM_CH2_MAX 1000 // (0 - 1000) - #define PWM_CH2_MIN -1000 // (-1000 - 0) + #define INPUT1_MID_POT + #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_MID 0 + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT2_MID_POT + #define INPUT2_MIN -1000 // (-1000 - 0) + #define INPUT2_MID 0 + #define INPUT2_MAX 1000 // (0 - 1000) #define FILTER 6553 // 0.1f [-] fixdt(0,16,16) lower value == softer filter [0, 65535] = [0.0 - 1.0]. #define SPEED_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 #define STEER_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14. If you do not want any steering, set it to 0. @@ -373,6 +406,18 @@ #define IBUS_LENGTH 0x20 #define IBUS_COMMAND 0x40 + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + // Min / Max values of each channel (use DEBUG to determine these values) + #define INPUT1_MID_POT + #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_MID 0 + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT2_MID_POT + #define INPUT2_MIN -1000 // (-1000 - 0) + #define INPUT2_MID 0 + #define INPUT2_MAX 1000 // (0 - 1000) + #undef USART2_BAUD #define USART2_BAUD 115200 #define CONTROL_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! @@ -390,10 +435,10 @@ #define ADC_PROTECT_ENA // ADC Protection Enable flag. Use this flag to make sure the ADC is protected when GND or Vcc wire is disconnected #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values - #define ADC1_MIN 1000 // min ADC1-value while poti at minimum-position (0 - 4095) - #define ADC1_MAX 2500 // max ADC1-value while poti at maximum-position (0 - 4095) - #define ADC2_MIN 500 // min ADC2-value while poti at minimum-position (0 - 4095) - #define ADC2_MAX 2200 // max ADC2-value while poti at maximum-position (0 - 4095) + #define INPUT1_MIN 1000 // min ADC1-value while poti at minimum-position (0 - 4095) + #define INPUT1_MAX 2500 // max ADC1-value while poti at maximum-position (0 - 4095) + #define INPUT2_MIN 500 // min ADC2-value while poti at minimum-position (0 - 4095) + #define INPUT2_MAX 2200 // max ADC2-value while poti at maximum-position (0 - 4095) #define SPEED_COEFFICIENT 16384 // 1.0f #define STEER_COEFFICIENT 0 // 0.0f // #define INVERT_R_DIRECTION // Invert rotation of right motor @@ -460,13 +505,18 @@ #define CTRL_MOD_REQ TRQ_MODE // SKATEBOARD works best in TORQUE Mode // #define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! - #define PWM_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define PWM_CH1_MAX 1000 // (0 - 1000) - #define PWM_CH1_MIN -1000 // (-1000 - 0) - #define PWM_CH2_MAX 700 // (0 - 1000) - #define PWM_CH2_MIN -800 // (-1000 - 0) - #define PWM_CH2_OUT_MIN -400 // (-1000 - 0) Change this value to adjust the braking amount + #define INPUT1_MID_POT + #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_MID 0 + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT2_MID_POT + #define INPUT2_MIN -800 // (-1000 - 0) + #define INPUT2_MID 0 + #define INPUT2_MAX 700 // (0 - 1000) + #define INPUT2_OUT_MIN -400 // (-1000 - 0) Change this value to adjust the braking amount #define FILTER 6553 // 0.1f [-] fixdt(0,16,16) lower value == softer filter [0, 65535] = [0.0 - 1.0]. #define SPEED_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 #define STEER_COEFFICIENT 0 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14. If you do not want any steering, set it to 0. From b50efdcab22b461e2fe5f194fdf59e82e31ef9af Mon Sep 17 00:00:00 2001 From: Candas1 Date: Thu, 29 Oct 2020 00:41:41 +0100 Subject: [PATCH 15/26] Fix typo --- Src/main.c | 2 ++ Src/util.c | 76 ++++++++++++++++++++++++++++++------------------------ 2 files changed, 44 insertions(+), 34 deletions(-) diff --git a/Src/main.c b/Src/main.c index 68e746c..17866ed 100644 --- a/Src/main.c +++ b/Src/main.c @@ -62,6 +62,8 @@ extern ExtY rtY_Right; /* External outputs */ extern int16_t cmd1; // normalized input value. -1000 to 1000 extern int16_t cmd2; // normalized input value. -1000 to 1000 +extern int16_t cmd1_in; // normalized input value. -1000 to 1000 +extern int16_t cmd2_in; // normalized input value. -1000 to 1000 extern int16_t speedAvg; // Average measured speed extern int16_t speedAvgAbs; // Average measured speed in absolute diff --git a/Src/util.c b/Src/util.c index 58267d3..d204dc5 100644 --- a/Src/util.c +++ b/Src/util.c @@ -128,23 +128,24 @@ static int16_t INPUT_MAX; // [-] Input target maximum limitation static int16_t INPUT_MIN; // [-] Input target minimum limitation -static uint8_t cur_spd_valid = 0; -static uint8_t adc_cal_valid = 0; -static uint16_t INPUT1_MIN_CAL = INPUT1_MIN; -static uint16_t INPUT1_MAX_CAL = INPUT1_MAX; -static uint16_t INPUT2_MIN_CAL = INPUT2_MIN; -static uint16_t INPUT2_MAX_CAL = INPUT2_MAX; -#ifdef INPUT1_MID_POT -static uint16_t INPUT1_MID_CAL = INPUT1_MID; -#else -static uint16_t INPUT1_MID_CAL = 0; +#if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) + static uint8_t cur_spd_valid = 0; + static uint8_t input_cal_valid = 0; + static uint16_t INPUT1_MIN_CAL = INPUT1_MIN; + static uint16_t INPUT1_MAX_CAL = INPUT1_MAX; + static uint16_t INPUT2_MIN_CAL = INPUT2_MIN; + static uint16_t INPUT2_MAX_CAL = INPUT2_MAX; + #ifdef INPUT1_MID_POT + static uint16_t INPUT1_MID_CAL = INPUT1_MID; + #else + static uint16_t INPUT1_MID_CAL = 0; + #endif + #ifdef INPUT1_MID_POT + static uint16_t INPUT2_MID_CAL = INPUT2_MID; + #else + static uint16_t INPUT2_MID_CAL = 0; + #endif #endif -#ifdef INPUT1_MID_POT -static uint16_t INPUT2_MID_CAL = INPUT2_MID; -#else -static uint16_t INPUT2_MID_CAL = 0; -#endif - #if defined(CONTROL_ADC) && defined(ADC_PROTECT_ENA) static int16_t timeoutCntADC = 0; // Timeout counter for ADC Protection @@ -433,6 +434,8 @@ void adcCalibLim(void) { if (speedAvgAbs > 5) { // do not enter this mode if motors are spinning return; } + + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) consoleLog("Input calibration started... "); @@ -487,6 +490,7 @@ void adcCalibLim(void) { input_cal_valid = 0; consoleLog("FAIL (Pots travel too short)\n"); } + #endif } @@ -501,6 +505,8 @@ void updateCurSpdLim(void) { if (speedAvgAbs > 5) { // do not enter this mode if motors are spinning return; } + + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) consoleLog("Torque and Speed limits update started... "); @@ -529,7 +535,7 @@ void updateCurSpdLim(void) { cur_spd_valid = 1; consoleLog("OK\n"); - + #endif } /* @@ -545,7 +551,7 @@ void saveConfig() { } #endif #ifdef CONTROL_ADC - if (adc_cal_valid || cur_spd_valid) { + if (input_cal_valid || cur_spd_valid) { HAL_FLASH_Unlock(); EE_WriteVariable(VirtAddVarTab[0], FLASH_WRITE_KEY); EE_WriteVariable(VirtAddVarTab[1], INPUT1_MIN_CAL); @@ -749,8 +755,8 @@ void readInput(void) { cmd1_in = (ppm_captured_value[0] - 500) * 2; cmd2_in = (ppm_captured_value[1] - 500) * 2; #ifdef SUPPORT_BUTTONS - button1 = ppm_captured_value[5] > 500; - button2 = 0; + button1 = ppm_captured_value[5] > 500; + button2 = 0; #endif #endif @@ -761,8 +767,8 @@ void readInput(void) { #ifdef CONTROL_ADC // ADC values range: 0-4095, see ADC-calibration in config.h - cmd1_in = adc_buffer.l_tx2; - cmd2_in = adc_buffer.l_rx2; + cmd1_in = adc_buffer.l_tx2; + cmd2_in = adc_buffer.l_rx2; #endif #if defined(CONTROL_SERIAL_USART2) || defined(CONTROL_SERIAL_USART3) @@ -827,20 +833,22 @@ void readCommand(void) { timeoutFlagSerial = timeoutFlagSerial_L || timeoutFlagSerial_R; #endif - #ifdef INPUT1_MID_POT - cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN, INPUT1_MID, INPUT1_MAX, INPUT_MIN, INPUT_MAX); - #else - cmd1 = MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ); // ADC1 - #endif - - #if !defined(VARIANT_SKATEBOARD) - #ifdef INPUT2_MID_POT - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_MIN, INPUT_MAX); + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) + #ifdef INPUT1_MID_POT + cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN, INPUT1_MID, INPUT1_MAX, INPUT_MIN, INPUT_MAX); #else - cmd2 = MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ); // ADC2 + cmd1 = MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ); // ADC1 + #endif + + #if !defined(VARIANT_SKATEBOARD) + #ifdef INPUT2_MID_POT + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_MIN, INPUT_MAX); + #else + cmd2 = MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ); // ADC2 + #endif + #else + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT2_OUT_MIN, INPUT_MAX); #endif - #else - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_OUT_MIN, INPUT_MAX); #endif From b1169c02b7bfd87ab7b939e727e977cfc0ec61f5 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Sat, 31 Oct 2020 21:14:15 +0100 Subject: [PATCH 16/26] Fixes --- Inc/config.h | 30 +++++++++---------- Inc/defines.h | 2 +- Src/main.c | 4 +-- Src/util.c | 82 +++++++++++++++++++++++++++++---------------------- 4 files changed, 65 insertions(+), 53 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index 2bb459c..f08ea06 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -250,22 +250,22 @@ * For middle resting potis: Let the potis in the middle resting position, write value 1 to ADC1_MID and value 2 to ADC2_MID * Make, flash and test it. */ - #define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2, FEEDBACK_SERIAL_USART2, DEBUG_SERIAL_USART2! - // #define ADC_PROTECT_ENA // ADC Protection Enable flag. Use this flag to make sure the ADC is protected when GND or Vcc wire is disconnected - #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken - #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values - #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - // #define INPUT1_MID_POT // ADC1 middle resting poti: comment-out if NOT a middle resting poti + #define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2, FEEDBACK_SERIAL_USART2, DEBUG_SERIAL_USART2! + // #define ADC_PROTECT_ENA // ADC Protection Enable flag. Use this flag to make sure the ADC is protected when GND or Vcc wire is disconnected + #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken + #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT1_MID_POT // ADC1 middle resting poti: comment-out if NOT a middle resting poti #define INPUT1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) #define INPUT1_MID 2048 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) #define INPUT1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) - // #define INPUT2_MID_POT // ADC2 middle resting poti: comment-out if NOT a middle resting poti + #define INPUT2_MID_POT // ADC2 middle resting poti: comment-out if NOT a middle resting poti #define INPUT2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) #define INPUT2_MID 2048 // mid ADC2-value while poti at minimum-position (ADC2_MIN - ADC2_MAX) #define INPUT2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) - // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! - // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! + // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! + // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! #endif // ############################# END OF VARIANT_ADC SETTINGS ######################### @@ -311,13 +311,13 @@ #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) #define INPUT1_MID_POT - #define INPUT1_MIN -1024 // (-1000 - 0) + #define INPUT1_MIN -1024 // (-1024 - 0) #define INPUT1_MID 0 - #define INPUT1_MAX 1024 // (0 - 1000) + #define INPUT1_MAX 1024 // (0 - 1024) #define INPUT2_MID_POT - #define INPUT2_MIN -1024 // (-1000 - 0) + #define INPUT2_MIN -1024 // (-1024 - 0) #define INPUT2_MID 0 - #define INPUT2_MAX 1024 // (0 - 1000) + #define INPUT2_MAX 1024 // (0 - 1024) // # maybe good for ARMCHAIR # #define FILTER 3276 // 0.05f #define SPEED_COEFFICIENT 8192 // 0.5f @@ -503,7 +503,7 @@ */ #undef CTRL_MOD_REQ #define CTRL_MOD_REQ TRQ_MODE // SKATEBOARD works best in TORQUE Mode - // #define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! + //#define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) diff --git a/Inc/defines.h b/Inc/defines.h index 5c53214..5a887da 100644 --- a/Inc/defines.h +++ b/Inc/defines.h @@ -181,7 +181,7 @@ #define MIN3(a, b, c) MIN(a, MIN(b, c)) #define MAX3(a, b, c) MAX(a, MAX(b, c)) #define ARRAY_LEN(x) (uint32_t)(sizeof(x) / sizeof(*(x))) -#define MAP(x, in_min, in_max, out_min, out_max) ((((x - in_min) * (out_max - out_min)) / (in_max - in_min)) + out_min ) +#define MAP(x, in_min, in_max, out_min, out_max) (((((x) - (in_min)) * ((out_max) - (out_min))) / ((in_max) - (in_min))) + (out_min)) typedef struct { diff --git a/Src/main.c b/Src/main.c index 17866ed..fb3c668 100644 --- a/Src/main.c +++ b/Src/main.c @@ -411,8 +411,8 @@ int main(void) { if (main_loop_counter % 25 == 0) { // Send data periodically every 125 ms setScopeChannel(0, (int16_t)cmd1_in); // 1: ADC1 setScopeChannel(1, (int16_t)cmd2_in); // 2: ADC2 - setScopeChannel(2, (int16_t)speedR); // 3: output command: [-1000, 1000] - setScopeChannel(3, (int16_t)speedL); // 4: output command: [-1000, 1000] + setScopeChannel(2, (int16_t)cmd1); //speedR); // 3: output command: [-1000, 1000] + setScopeChannel(3, (int16_t)cmd2); //speedL); // 4: output command: [-1000, 1000] setScopeChannel(4, (int16_t)adc_buffer.batt1); // 5: for battery voltage calibration setScopeChannel(5, (int16_t)(batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC)); // 6: for verifying battery voltage calibration setScopeChannel(6, (int16_t)board_temp_adcFilt); // 7: for board temperature calibration diff --git a/Src/util.c b/Src/util.c index d204dc5..c2ced91 100644 --- a/Src/util.c +++ b/Src/util.c @@ -114,7 +114,7 @@ float setDistance; uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1337}; // Virtual address defined by the user: 0xFFFF value is prohibited static uint16_t saveValue = 0; static uint8_t saveValue_valid = 0; -#elif defined(CONTROL_ADC) +#elif !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308}; #else uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1300}; // Dummy virtual address to avoid warnings @@ -274,7 +274,7 @@ void Input_Init(void) { UART_DisableRxErrors(&huart3); #endif - #ifdef CONTROL_ADC + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) uint16_t writeCheck, i_max, n_max; HAL_FLASH_Unlock(); @@ -438,17 +438,18 @@ void adcCalibLim(void) { #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) consoleLog("Input calibration started... "); - + + readInput(); // Inititalization: MIN = a high values, MAX = a low value, - int32_t input1_fixdt = adc_buffer.l_tx2 << 16; - int32_t input2_fixdt = adc_buffer.l_rx2 << 16; + int32_t input1_fixdt = cmd1_in << 16; + int32_t input2_fixdt = cmd2_in << 16; uint16_t input_cal_timeout = 0; - uint16_t INPUT1_MIN_temp = 4095; - uint16_t INPUT1_MID_temp = 0; - uint16_t INPUT1_MAX_temp = 0; - uint16_t INPUT2_MIN_temp = 4095; - uint16_t INPUT2_MID_temp = 0; - uint16_t INPUT2_MAX_temp = 0; + int16_t INPUT1_MIN_temp = INPUT1_MAX; + int16_t INPUT1_MID_temp = 0; + int16_t INPUT1_MAX_temp = INPUT1_MIN; + int16_t INPUT2_MIN_temp = INPUT2_MAX; + int16_t INPUT2_MID_temp = 0; + int16_t INPUT2_MAX_temp = INPUT2_MIN; input_cal_valid = 1; @@ -457,8 +458,9 @@ void adcCalibLim(void) { readInput(); filtLowPass32(cmd1_in, FILTER, &input1_fixdt); filtLowPass32(cmd2_in, FILTER, &input2_fixdt); - INPUT1_MID_temp = (uint16_t)CLAMP(input1_fixdt >> 16, 0, 4095); // convert fixed-point to integer - INPUT2_MID_temp = (uint16_t)CLAMP(input2_fixdt >> 16, 0, 4095); + + INPUT1_MID_temp = (int16_t)CLAMP(input1_fixdt >> 16, INPUT1_MIN, INPUT1_MAX); // convert fixed-point to integer + INPUT2_MID_temp = (int16_t)CLAMP(input2_fixdt >> 16, INPUT2_MIN, INPUT2_MAX); INPUT1_MIN_temp = MIN(INPUT1_MIN_temp, INPUT1_MID_temp); INPUT1_MAX_temp = MAX(INPUT1_MAX_temp, INPUT1_MID_temp); INPUT2_MIN_temp = MIN(INPUT2_MIN_temp, INPUT2_MID_temp); @@ -477,20 +479,26 @@ void adcCalibLim(void) { } #endif + uint16_t input_margin = 0; + #ifdef CONTROL_ADC + input_margin = 100; + #endif + // Add final ADC margin to have exact 0 and MAX at the minimum and maximum ADC value if (input_cal_valid && (INPUT1_MAX_temp - INPUT1_MIN_temp) > 500 && (INPUT2_MAX_temp - INPUT2_MIN_temp) > 500) { - INPUT1_MIN_CAL = INPUT1_MIN_temp + 100; + INPUT1_MIN_CAL = INPUT1_MIN_temp + input_margin; INPUT1_MID_CAL = INPUT1_MID_temp; - INPUT1_MAX_CAL = INPUT1_MAX_temp - 100; - INPUT2_MIN_CAL = INPUT2_MIN_temp + 100; + INPUT1_MAX_CAL = INPUT1_MAX_temp - input_margin; + INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; INPUT2_MID_CAL = INPUT2_MID_temp; - INPUT2_MAX_CAL = INPUT2_MAX_temp - 100; + INPUT2_MAX_CAL = INPUT2_MAX_temp - input_margin; consoleLog("OK\n"); } else { input_cal_valid = 0; consoleLog("FAIL (Pots travel too short)\n"); } #endif + } @@ -550,7 +558,7 @@ void saveConfig() { HAL_FLASH_Lock(); } #endif - #ifdef CONTROL_ADC + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) if (input_cal_valid || cur_spd_valid) { HAL_FLASH_Unlock(); EE_WriteVariable(VirtAddVarTab[0], FLASH_WRITE_KEY); @@ -572,12 +580,12 @@ void saveConfig() { * This function realizes a dead-band around 0 and scales the input between [out_min, out_max] */ int addDeadBand(int16_t u, int16_t deadBand, int16_t in_min, int16_t in_mid, int16_t in_max, int16_t out_min, int16_t out_max) { - if(u > in_mid - deadBand && u < in_mid + deadBand) { + if( u > in_mid - deadBand && u < in_mid + deadBand ) { return 0; - } else if(u > 0) { - return MAP(u, in_mid + deadBand, in_max, 0, out_max); + } else if(u > in_mid) { + return CLAMP( MAP(u, in_mid + deadBand, in_max, 0, out_max), 0 , out_max); } else { - return MAP(u, in_mid - deadBand, in_min, out_min, 0); + return CLAMP( MAP(u, in_mid - deadBand, in_min, 0, out_min), out_min, 0); } } @@ -683,7 +691,7 @@ void poweroff(void) { void poweroffPressCheck(void) { - #if defined(CONTROL_ADC) + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) if(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { enable = 0; uint16_t cnt_press = 0; @@ -741,13 +749,13 @@ void readInput(void) { #if defined(CONTROL_NUNCHUK) || defined(SUPPORT_NUNCHUK) if (nunchuk_connected != 0) { Nunchuk_Read(); - cmd1_in = (nunchuk_data[0] - 127) * 8; // X axis 0-255 - cmd2_in = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 + cmd1_in = (nunchuk_data[0] - 127) * 8; // X axis 0-255 + cmd2_in = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 - #ifdef SUPPORT_BUTTONS - button1 = (uint8_t)nunchuk_data[5] & 1; - button2 = (uint8_t)(nunchuk_data[5] >> 1) & 1; - #endif + #ifdef SUPPORT_BUTTONS + button1 = (uint8_t)nunchuk_data[5] & 1; + button2 = (uint8_t)(nunchuk_data[5] >> 1) & 1; + #endif } #endif @@ -833,21 +841,25 @@ void readCommand(void) { timeoutFlagSerial = timeoutFlagSerial_L || timeoutFlagSerial_R; #endif + //setScopeChannel(4, (int16_t)INPUT1_MIN_CAL); + //setScopeChannel(5, (int16_t)INPUT1_MID_CAL); + //setScopeChannel(6, (int16_t)INPUT1_MAX_CAL); + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) #ifdef INPUT1_MID_POT - cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN, INPUT1_MID, INPUT1_MAX, INPUT_MIN, INPUT_MAX); + cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); #else - cmd1 = MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ); // ADC1 + cmd1 = CLAMP(MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC1 #endif #if !defined(VARIANT_SKATEBOARD) #ifdef INPUT2_MID_POT - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); #else - cmd2 = MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ); // ADC2 + cmd2 = CLAMP(MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC2 #endif #else - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN, INPUT2_MID, INPUT2_MAX, INPUT2_OUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_OUT_MIN, INPUT_MAX); #endif #endif @@ -1033,7 +1045,7 @@ void usart_process_debug(uint8_t *userCommand, uint32_t len) { for (; len > 0; len--, userCommand++) { if (*userCommand != '\n' && *userCommand != '\r') { // Do not accept 'new line' and 'carriage return' commands - consoleLog("-- Command received --\r\n"); + //consoleLog("-- Command received --\r\n"); // handle_input(*userCommand); // -> Create this function to handle the user commands } } From 4cc02fddc190f3a5dbe585fef2822a5220d0d5cc Mon Sep 17 00:00:00 2001 From: Candas1 Date: Wed, 11 Nov 2020 21:36:40 +0100 Subject: [PATCH 17/26] Improved auto-calibration --- Inc/config.h | 83 ++++++++++-------- Inc/eeprom.h | 2 +- Src/util.c | 235 ++++++++++++++++++++++++++++++++------------------- 3 files changed, 200 insertions(+), 120 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index f08ea06..15da433 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -135,8 +135,8 @@ #define TRQ_MODE 3 // [-] TORQUE mode // Enable/Disable Motor -#define MOTOR_LEFT_ENA // [-] Enable LEFT motor. Comment-out if this motor is not needed to be operational -#define MOTOR_RIGHT_ENA // [-] Enable RIGHT motor. Comment-out if this motor is not needed to be operational +//#define MOTOR_LEFT_ENA // [-] Enable LEFT motor. Comment-out if this motor is not needed to be operational +//#define MOTOR_RIGHT_ENA // [-] Enable RIGHT motor. Comment-out if this motor is not needed to be operational // Control selections #define CTRL_TYP_SEL FOC_CTRL // [-] Control type selection: COM_CTRL, SIN_CTRL, FOC_CTRL (default) @@ -251,16 +251,16 @@ * Make, flash and test it. */ #define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2, FEEDBACK_SERIAL_USART2, DEBUG_SERIAL_USART2! - // #define ADC_PROTECT_ENA // ADC Protection Enable flag. Use this flag to make sure the ADC is protected when GND or Vcc wire is disconnected #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT1_MID_POT // ADC1 middle resting poti: comment-out if NOT a middle resting poti #define INPUT1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) #define INPUT1_MID 2048 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) #define INPUT1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) - #define INPUT2_MID_POT // ADC2 middle resting poti: comment-out if NOT a middle resting poti + + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) #define INPUT2_MID 2048 // mid ADC2-value while poti at minimum-position (ADC2_MIN - ADC2_MAX) #define INPUT2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) @@ -280,14 +280,15 @@ // #define SIDEBOARD_SERIAL_USART3 #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 INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_MID_POT + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) - #define INPUT2_MID_POT + + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) @@ -307,14 +308,15 @@ * Recommendation: Nunchuk Breakout Board https://github.com/Jan--Henrik/hoverboard-breakout */ #define CONTROL_NUNCHUK // use nunchuk as input. disable FEEDBACK_SERIAL_USART3, DEBUG_SERIAL_USART3! - #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_MID_POT + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN -1024 // (-1024 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1024 // (0 - 1024) - #define INPUT2_MID_POT + + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN -1024 // (-1024 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1024 // (0 - 1024) @@ -342,14 +344,15 @@ #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif #define PPM_NUM_CHANNELS 6 // total number of PPM channels to receive, even if they are not used. - #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_MID_POT + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) - #define INPUT2_MID_POT + + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) @@ -368,17 +371,19 @@ */ #define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! // #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! - #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_MID_POT + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) - #define INPUT2_MID_POT + + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) + #define FILTER 6553 // 0.1f [-] fixdt(0,16,16) lower value == softer filter [0, 65535] = [0.0 - 1.0]. #define SPEED_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 #define STEER_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14. If you do not want any steering, set it to 0. @@ -406,14 +411,15 @@ #define IBUS_LENGTH 0x20 #define IBUS_COMMAND 0x40 - #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_MID_POT + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) - #define INPUT2_MID_POT + + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) @@ -432,13 +438,21 @@ #undef CTRL_MOD_REQ #define CTRL_MOD_REQ TRQ_MODE // HOVERCAR works best in TORQUE Mode #define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2, FEEDBACK_SERIAL_USART2, DEBUG_SERIAL_USART2! - #define ADC_PROTECT_ENA // ADC Protection Enable flag. Use this flag to make sure the ADC is protected when GND or Vcc wire is disconnected #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values + + #define INPUT1_TYPE 1 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN 1000 // min ADC1-value while poti at minimum-position (0 - 4095) + #define INPUT1_MID 0 #define INPUT1_MAX 2500 // max ADC1-value while poti at maximum-position (0 - 4095) + + #define INPUT2_TYPE 1 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN 500 // min ADC2-value while poti at minimum-position (0 - 4095) + #define INPUT2_MID 0 #define INPUT2_MAX 2200 // max ADC2-value while poti at maximum-position (0 - 4095) + #define SPEED_COEFFICIENT 16384 // 1.0f #define STEER_COEFFICIENT 0 // 0.0f // #define INVERT_R_DIRECTION // Invert rotation of right motor @@ -505,18 +519,21 @@ #define CTRL_MOD_REQ TRQ_MODE // SKATEBOARD works best in TORQUE Mode //#define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! - #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_MID_POT + #define INPUT1_TYPE 0 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) - #define INPUT2_MID_POT - #define INPUT2_MIN -800 // (-1000 - 0) + + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_MIN -800 // (-1000 - 0) #define INPUT2_MID 0 - #define INPUT2_MAX 700 // (0 - 1000) + #define INPUT2_MAX 700 // (0 - 1000) #define INPUT2_OUT_MIN -400 // (-1000 - 0) Change this value to adjust the braking amount + #define FILTER 6553 // 0.1f [-] fixdt(0,16,16) lower value == softer filter [0, 65535] = [0.0 - 1.0]. #define SPEED_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 #define STEER_COEFFICIENT 0 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14. If you do not want any steering, set it to 0. diff --git a/Inc/eeprom.h b/Inc/eeprom.h index d992b27..cc7b1b9 100644 --- a/Inc/eeprom.h +++ b/Inc/eeprom.h @@ -209,7 +209,7 @@ #define PAGE_FULL ((uint8_t)0x80) /* Variables' number */ -#define NB_OF_VAR ((uint8_t)0x09) +#define NB_OF_VAR ((uint8_t)0x0B) /* Exported types ------------------------------------------------------------*/ /* Exported macro ------------------------------------------------------------*/ diff --git a/Src/util.c b/Src/util.c index c2ced91..6c4352e 100644 --- a/Src/util.c +++ b/Src/util.c @@ -115,7 +115,7 @@ uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1337}; // Virtual address defined by static uint16_t saveValue = 0; static uint8_t saveValue_valid = 0; #elif !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) -uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308}; +uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1300, 1301, 1302, 1303, 1304, 1305, 1306, 1307, 1308, 1309, 1310}; #else uint16_t VirtAddVarTab[NB_OF_VAR] = {0x1300}; // Dummy virtual address to avoid warnings #endif @@ -132,22 +132,16 @@ static int16_t INPUT_MIN; // [-] Input target minimum limitation static uint8_t cur_spd_valid = 0; static uint8_t input_cal_valid = 0; static uint16_t INPUT1_MIN_CAL = INPUT1_MIN; - static uint16_t INPUT1_MAX_CAL = INPUT1_MAX; - static uint16_t INPUT2_MIN_CAL = INPUT2_MIN; - static uint16_t INPUT2_MAX_CAL = INPUT2_MAX; - #ifdef INPUT1_MID_POT static uint16_t INPUT1_MID_CAL = INPUT1_MID; - #else - static uint16_t INPUT1_MID_CAL = 0; - #endif - #ifdef INPUT1_MID_POT + static uint16_t INPUT1_MAX_CAL = INPUT1_MAX; + static uint16_t INPUT1_TYPE_CAL = INPUT1_TYPE; + static uint16_t INPUT2_MIN_CAL = INPUT2_MIN; static uint16_t INPUT2_MID_CAL = INPUT2_MID; - #else - static uint16_t INPUT2_MID_CAL = 0; - #endif + static uint16_t INPUT2_MAX_CAL = INPUT2_MAX; + static uint16_t INPUT2_TYPE_CAL = INPUT2_TYPE; #endif -#if defined(CONTROL_ADC) && defined(ADC_PROTECT_ENA) +#if defined(CONTROL_ADC) static int16_t timeoutCntADC = 0; // Timeout counter for ADC Protection #endif @@ -281,14 +275,16 @@ void Input_Init(void) { EE_Init(); /* EEPROM Init */ EE_ReadVariable(VirtAddVarTab[0], &writeCheck); if (writeCheck == FLASH_WRITE_KEY) { - EE_ReadVariable(VirtAddVarTab[1], &INPUT1_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[2], &INPUT1_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[3], &INPUT1_MID_CAL); - EE_ReadVariable(VirtAddVarTab[4], &INPUT2_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[5], &INPUT2_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[6], &INPUT2_MID_CAL); - EE_ReadVariable(VirtAddVarTab[7], &i_max); - EE_ReadVariable(VirtAddVarTab[8], &n_max); + EE_ReadVariable(VirtAddVarTab[1] , &INPUT1_MIN_CAL); + EE_ReadVariable(VirtAddVarTab[2] , &INPUT1_MAX_CAL); + EE_ReadVariable(VirtAddVarTab[3] , &INPUT1_MID_CAL); + EE_ReadVariable(VirtAddVarTab[4] , &INPUT2_MIN_CAL); + EE_ReadVariable(VirtAddVarTab[5] , &INPUT2_MAX_CAL); + EE_ReadVariable(VirtAddVarTab[6] , &INPUT2_MID_CAL); + EE_ReadVariable(VirtAddVarTab[7] , &i_max); + EE_ReadVariable(VirtAddVarTab[8] , &n_max); + EE_ReadVariable(VirtAddVarTab[9] , &INPUT1_TYPE_CAL); + EE_ReadVariable(VirtAddVarTab[10], &INPUT2_TYPE_CAL); rtP_Left.i_max = i_max; rtP_Left.n_max = n_max; rtP_Right.i_max = i_max; @@ -437,7 +433,7 @@ void adcCalibLim(void) { #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - consoleLog("Input calibration started... "); + consoleLog("Input calibration started...\n"); readInput(); // Inititalization: MIN = a high values, MAX = a low value, @@ -468,37 +464,90 @@ void adcCalibLim(void) { HAL_Delay(5); } - // ADC calibration checks - #ifdef ADC_PROTECT_ENA - if ((INPUT1_MIN_temp + 100 - ADC_PROTECT_THRESH) > 0 && (INPUT1_MAX_temp - 100 + ADC_PROTECT_THRESH) < 4095 && - (INPUT2_MIN_temp + 100 - ADC_PROTECT_THRESH) > 0 && (INPUT2_MAX_temp - 100 + ADC_PROTECT_THRESH) < 4095) { - input_cal_valid = 1; - } else { - input_cal_valid = 0; - consoleLog("FAIL (ADC out-of-range protection not possible)\n"); - } - #endif + HAL_Delay(50); uint16_t input_margin = 0; #ifdef CONTROL_ADC input_margin = 100; #endif - - // Add final ADC margin to have exact 0 and MAX at the minimum and maximum ADC value - if (input_cal_valid && (INPUT1_MAX_temp - INPUT1_MIN_temp) > 500 && (INPUT2_MAX_temp - INPUT2_MIN_temp) > 500) { - INPUT1_MIN_CAL = INPUT1_MIN_temp + input_margin; - INPUT1_MID_CAL = INPUT1_MID_temp; - INPUT1_MAX_CAL = INPUT1_MAX_temp - input_margin; - INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; - INPUT2_MID_CAL = INPUT2_MID_temp; - INPUT2_MAX_CAL = INPUT2_MAX_temp - input_margin; - consoleLog("OK\n"); + + int16_t threshold = (INPUT1_MAX - INPUT1_MIN) / 10; + INPUT1_MIN_CAL = INPUT1_MIN_temp + input_margin; + INPUT1_MID_CAL = INPUT1_MID_temp; + INPUT1_MAX_CAL = INPUT1_MAX_temp - input_margin; + if ( (INPUT1_MIN_temp/threshold) == (INPUT1_MAX_temp/threshold) ){ + // MIN MID and MAX are close, there is no input + INPUT1_TYPE_CAL = 0; + consoleLog("Input1 is ignored"); } else { - input_cal_valid = 0; - consoleLog("FAIL (Pots travel too short)\n"); - } - #endif + if ( (INPUT1_MIN_temp/threshold) == (INPUT1_MID_temp/threshold) ){ + // MIN and MID are close, it's a normal pot + INPUT1_TYPE_CAL = 1; + consoleLog("Input1 is a normal pot"); + }else { + INPUT1_TYPE_CAL = 2; + consoleLog("Input1 is a mid-resting pot"); + } + HAL_Delay(50); + #ifdef CONTROL_ADC + if ( (INPUT1_MIN_CAL - ADC_PROTECT_THRESH) > 0 && (INPUT1_MAX_CAL + ADC_PROTECT_THRESH) < 4095){ + consoleLog(" and protected"); + } + #endif + input_cal_valid = 1; + } + + HAL_Delay(50); + consoleLog("\n"); + HAL_Delay(50); + + threshold = (INPUT2_MAX - INPUT2_MIN) / 10; + INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; + INPUT2_MID_CAL = INPUT2_MID_temp; + INPUT2_MAX_CAL = INPUT2_MAX_temp - input_margin; + if ( (INPUT2_MIN_temp/threshold) == (INPUT2_MAX_temp/threshold) ){ + // MIN MID and MAX are close, there is no input + INPUT2_TYPE_CAL = 0; + consoleLog("Input2 is ignored"); + } else { + if ( (INPUT2_MIN_temp/threshold) == (INPUT2_MID_temp/threshold) ){ + // MIN and MID are close, it's a normal pot + INPUT2_TYPE_CAL = 1; + consoleLog("Input2 is a normal pot"); + }else { + INPUT2_TYPE_CAL = 2; + consoleLog("Input2 is a mid-resting pot"); + } + + HAL_Delay(50); + + #ifdef CONTROL_ADC + if ( (INPUT2_MIN_CAL - ADC_PROTECT_THRESH) > 0 && (INPUT2_MAX_CAL + ADC_PROTECT_THRESH) < 4095 ){ + consoleLog(" and protected"); + } + #endif + input_cal_valid = 1; + } + + HAL_Delay(50); + consoleLog("\n"); + HAL_Delay(50); + consoleLog("Saved limits\n"); + HAL_Delay(50); + setScopeChannel(0, (int16_t)INPUT1_MIN_CAL); + setScopeChannel(1, (int16_t)INPUT1_MID_CAL); + setScopeChannel(2, (int16_t)INPUT1_MAX_CAL); + setScopeChannel(3, (int16_t)0); + setScopeChannel(4, (int16_t)INPUT2_MIN_CAL); + setScopeChannel(5, (int16_t)INPUT2_MID_CAL); + setScopeChannel(6, (int16_t)INPUT2_MAX_CAL); + setScopeChannel(7, (int16_t)0); + consoleScope(); + + HAL_Delay(50); + + #endif } @@ -561,15 +610,17 @@ void saveConfig() { #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) if (input_cal_valid || cur_spd_valid) { HAL_FLASH_Unlock(); - EE_WriteVariable(VirtAddVarTab[0], FLASH_WRITE_KEY); - EE_WriteVariable(VirtAddVarTab[1], INPUT1_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[2], INPUT1_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[3], INPUT1_MID_CAL); - EE_WriteVariable(VirtAddVarTab[4], INPUT2_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[5], INPUT2_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[6], INPUT2_MID_CAL); - EE_WriteVariable(VirtAddVarTab[7], rtP_Left.i_max); - EE_WriteVariable(VirtAddVarTab[8], rtP_Left.n_max); + EE_WriteVariable(VirtAddVarTab[0] , FLASH_WRITE_KEY); + EE_WriteVariable(VirtAddVarTab[1] , INPUT1_MIN_CAL); + EE_WriteVariable(VirtAddVarTab[2] , INPUT1_MAX_CAL); + EE_WriteVariable(VirtAddVarTab[3] , INPUT1_MID_CAL); + EE_WriteVariable(VirtAddVarTab[4] , INPUT2_MIN_CAL); + EE_WriteVariable(VirtAddVarTab[5] , INPUT2_MAX_CAL); + EE_WriteVariable(VirtAddVarTab[6] , INPUT2_MID_CAL); + EE_WriteVariable(VirtAddVarTab[7] , rtP_Left.i_max); + EE_WriteVariable(VirtAddVarTab[8] , rtP_Left.n_max); + EE_WriteVariable(VirtAddVarTab[9] , INPUT1_TYPE_CAL); + EE_WriteVariable(VirtAddVarTab[10], INPUT2_TYPE_CAL); HAL_FLASH_Lock(); } #endif @@ -803,23 +854,21 @@ void readInput(void) { void readCommand(void) { readInput(); #ifdef CONTROL_ADC - #ifdef ADC_PROTECT_ENA - if (adc_buffer.l_tx2 >= (ADC1_MIN_CAL - ADC_PROTECT_THRESH) && adc_buffer.l_tx2 <= (ADC1_MAX_CAL + ADC_PROTECT_THRESH) && - adc_buffer.l_rx2 >= (ADC2_MIN_CAL - ADC_PROTECT_THRESH) && adc_buffer.l_rx2 <= (ADC2_MAX_CAL + ADC_PROTECT_THRESH)) { - if (timeoutFlagADC) { // Check for previous timeout flag - if (timeoutCntADC-- <= 0) // Timeout de-qualification - timeoutFlagADC = 0; // Timeout flag cleared - } else { - timeoutCntADC = 0; // Reset the timeout counter - } + // If input1 or Input2 is either below MIN - Threshold or above MAX + Threshold, ADC protection timeout + if ((IN_RANGE(cmd1_in,INPUT1_MIN_CAL - ADC_PROTECT_THRESH,INPUT1_MAX_CAL + ADC_PROTECT_THRESH)) && + (IN_RANGE(cmd1_in,INPUT2_MIN_CAL - ADC_PROTECT_THRESH,INPUT2_MAX_CAL + ADC_PROTECT_THRESH))){ + if (timeoutFlagADC) { // Check for previous timeout flag + if (timeoutCntADC-- <= 0) // Timeout de-qualification + timeoutFlagADC = 0; // Timeout flag cleared } else { - if (timeoutCntADC++ >= ADC_PROTECT_TIMEOUT) { // Timeout qualification - timeoutFlagADC = 1; // Timeout detected - timeoutCntADC = ADC_PROTECT_TIMEOUT; // Limit timout counter value - } - } - #endif - + timeoutCntADC = 0; // Reset the timeout counter + } + } else { + if (timeoutCntADC++ >= ADC_PROTECT_TIMEOUT) { // Timeout qualification + timeoutFlagADC = 1; // Timeout detected + timeoutCntADC = ADC_PROTECT_TIMEOUT; // Limit timout counter value + } + } timeoutCnt = 0; #endif @@ -841,23 +890,37 @@ void readCommand(void) { timeoutFlagSerial = timeoutFlagSerial_L || timeoutFlagSerial_R; #endif - //setScopeChannel(4, (int16_t)INPUT1_MIN_CAL); - //setScopeChannel(5, (int16_t)INPUT1_MID_CAL); - //setScopeChannel(6, (int16_t)INPUT1_MAX_CAL); - #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - #ifdef INPUT1_MID_POT - cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); - #else - cmd1 = CLAMP(MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC1 - #endif - + switch (INPUT1_TYPE_CAL){ + case 0: // Input1 is ignored + cmd1 = 0; + break; + case 1: // Input1 is a normal pot + cmd1 = CLAMP(MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC1 + break; + case 2: // Input1 is a mid resting pot + cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); + break; + default: + cmd1 = 0; + break; + } + #if !defined(VARIANT_SKATEBOARD) - #ifdef INPUT2_MID_POT - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); - #else - cmd2 = CLAMP(MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC2 - #endif + switch (INPUT2_TYPE_CAL){ + case 0: // Input2 is ignored + cmd2 = 0; + break; + case 1: // Input2 is a normal pot + cmd2 = CLAMP(MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC2 + break; + case 2: // Input2 is a mid resting pot + cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); + break; + default: + cmd2 = 0; + break; + } #else cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_OUT_MIN, INPUT_MAX); #endif From 11ab8481030616d4b108b58d4fab4313817a9394 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Fri, 13 Nov 2020 22:31:49 +0100 Subject: [PATCH 18/26] Current and speed setting for all variants --- Inc/config.h | 21 +++++++++++++-------- Src/util.c | 42 +++++++++++++++++++++++++++++------------- 2 files changed, 42 insertions(+), 21 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index 15da433..449c9fb 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -135,8 +135,8 @@ #define TRQ_MODE 3 // [-] TORQUE mode // Enable/Disable Motor -//#define MOTOR_LEFT_ENA // [-] Enable LEFT motor. Comment-out if this motor is not needed to be operational -//#define MOTOR_RIGHT_ENA // [-] Enable RIGHT motor. Comment-out if this motor is not needed to be operational +#define MOTOR_LEFT_ENA // [-] Enable LEFT motor. Comment-out if this motor is not needed to be operational +#define MOTOR_RIGHT_ENA // [-] Enable RIGHT motor. Comment-out if this motor is not needed to be operational // Control selections #define CTRL_TYP_SEL FOC_CTRL // [-] Control type selection: COM_CTRL, SIN_CTRL, FOC_CTRL (default) @@ -324,6 +324,7 @@ #define FILTER 3276 // 0.05f #define SPEED_COEFFICIENT 8192 // 0.5f #define STEER_COEFFICIENT 62259 // -0.2f + #define DEBUG_SERIAL_USART2 // left sensor cable debug // #define SUPPORT_BUTTONS // Define for Nunchuck buttons support #endif // ############################# END OF VARIANT_NUNCHUK SETTINGS ######################### @@ -371,6 +372,11 @@ */ #define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! // #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! + #ifdef CONTROL_PWM_RIGHT + #define DEBUG_SERIAL_USART2 // left sensor cable debug + #else + #define DEBUG_SERIAL_USART3 // right sensor cable debug + #endif // Min / Max values of each channel (use DEBUG to determine these values) #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) @@ -519,7 +525,11 @@ #define CTRL_MOD_REQ TRQ_MODE // SKATEBOARD works best in TORQUE Mode //#define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! - + #ifdef CONTROL_PWM_RIGHT + #define DEBUG_SERIAL_USART2 // left sensor cable debug + #else + #define DEBUG_SERIAL_USART3 // right sensor cable debug + #endif // Min / Max values of each channel (use DEBUG to determine these values) #define INPUT1_TYPE 0 // 0:Disabled 1:Normal POT 2:Middle Resting Pot #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) @@ -542,11 +552,6 @@ // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! // #define STANDSTILL_HOLD_ENABLE // [-] Flag to hold the position when standtill is reached. Only available and makes sense for VOLTAGE or TORQUE mode. - #ifdef CONTROL_PWM_RIGHT - #define DEBUG_SERIAL_USART2 // left sensor cable debug - #else - #define DEBUG_SERIAL_USART3 // right sensor cable debug - #endif #endif // ############################# END OF VARIANT_SKATEBOARD SETTINGS ############################ diff --git a/Src/util.c b/Src/util.c index 6c4352e..87cb14e 100644 --- a/Src/util.c +++ b/Src/util.c @@ -464,7 +464,7 @@ void adcCalibLim(void) { HAL_Delay(5); } - HAL_Delay(50); + HAL_Delay(10); uint16_t input_margin = 0; #ifdef CONTROL_ADC @@ -489,7 +489,7 @@ void adcCalibLim(void) { consoleLog("Input1 is a mid-resting pot"); } - HAL_Delay(50); + HAL_Delay(10); #ifdef CONTROL_ADC if ( (INPUT1_MIN_CAL - ADC_PROTECT_THRESH) > 0 && (INPUT1_MAX_CAL + ADC_PROTECT_THRESH) < 4095){ consoleLog(" and protected"); @@ -498,9 +498,9 @@ void adcCalibLim(void) { input_cal_valid = 1; } - HAL_Delay(50); + HAL_Delay(10); consoleLog("\n"); - HAL_Delay(50); + HAL_Delay(10); threshold = (INPUT2_MAX - INPUT2_MIN) / 10; INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; @@ -520,7 +520,7 @@ void adcCalibLim(void) { consoleLog("Input2 is a mid-resting pot"); } - HAL_Delay(50); + HAL_Delay(10); #ifdef CONTROL_ADC if ( (INPUT2_MIN_CAL - ADC_PROTECT_THRESH) > 0 && (INPUT2_MAX_CAL + ADC_PROTECT_THRESH) < 4095 ){ @@ -530,11 +530,11 @@ void adcCalibLim(void) { input_cal_valid = 1; } - HAL_Delay(50); + HAL_Delay(10); consoleLog("\n"); - HAL_Delay(50); + HAL_Delay(10); consoleLog("Saved limits\n"); - HAL_Delay(50); + HAL_Delay(10); setScopeChannel(0, (int16_t)INPUT1_MIN_CAL); setScopeChannel(1, (int16_t)INPUT1_MID_CAL); setScopeChannel(2, (int16_t)INPUT1_MAX_CAL); @@ -545,8 +545,9 @@ void adcCalibLim(void) { setScopeChannel(7, (int16_t)0); consoleScope(); - HAL_Delay(50); - + HAL_Delay(20); + consoleLog("OK\n"); + #endif } @@ -565,7 +566,7 @@ void updateCurSpdLim(void) { #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - consoleLog("Torque and Speed limits update started... "); + consoleLog("Torque and Speed limits update started...\n"); int32_t input1_fixdt = cmd1_in << 16; int32_t input2_fixdt = cmd2_in << 16; @@ -582,14 +583,29 @@ void updateCurSpdLim(void) { } // Calculate scaling factors - cur_factor = CLAMP((input1_fixdt - (INPUT1_MIN_CAL << 16)) / (INPUT1_MAX_CAL - INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A - spd_factor = CLAMP((input2_fixdt - (INPUT2_MIN_CAL << 16)) / (INPUT2_MAX_CAL - INPUT2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm + cur_factor = CLAMP((input1_fixdt - ((int16_t)INPUT1_MIN_CAL << 16)) / ((int16_t)INPUT1_MAX_CAL - (int16_t)INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A + spd_factor = CLAMP((input2_fixdt - ((int16_t)INPUT2_MIN_CAL << 16)) / ((int16_t)INPUT2_MAX_CAL - (int16_t)INPUT2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm // Update maximum limits rtP_Left.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) rtP_Left.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) rtP_Right.i_max = rtP_Left.i_max; rtP_Right.n_max = rtP_Left.n_max; + HAL_Delay(10); + consoleLog("Saved limits\n"); + HAL_Delay(10); + setScopeChannel(0, (int16_t)input1_fixdt); + setScopeChannel(1, (uint16_t)cur_factor); + setScopeChannel(2, (int16_t)rtP_Right.i_max); + setScopeChannel(3, (int16_t)0); + setScopeChannel(4, (int16_t)input2_fixdt); + setScopeChannel(5, (uint16_t)spd_factor); + setScopeChannel(6, (int16_t)rtP_Right.n_max); + setScopeChannel(7, (int16_t)0); + consoleScope(); + + HAL_Delay(20); + cur_spd_valid = 1; consoleLog("OK\n"); #endif From f962d16cd647954826fa914d73082f2d2c321318 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Sat, 14 Nov 2020 19:30:38 +0100 Subject: [PATCH 19/26] Test print log --- Inc/comms.h | 1 + Src/comms.c | 26 ++++++++++++ Src/main.c | 8 ++-- Src/util.c | 111 ++++++++++++++++++++++--------------------------- platformio.ini | 2 +- 5 files changed, 82 insertions(+), 66 deletions(-) diff --git a/Inc/comms.h b/Inc/comms.h index 6bdb730..b723283 100644 --- a/Inc/comms.h +++ b/Inc/comms.h @@ -28,6 +28,7 @@ void setScopeChannel(uint8_t ch, int16_t val); void consoleScope(void); void consoleLog(char *message); +void print( const char * format, ... ); #endif diff --git a/Src/comms.c b/Src/comms.c index 61ee47d..881b2cc 100644 --- a/Src/comms.c +++ b/Src/comms.c @@ -1,4 +1,5 @@ #include +#include #include #include "stm32f1xx_hal.h" #include "defines.h" @@ -79,3 +80,28 @@ void consoleLog(char *message) #endif #endif } + +void print( const char * format, ... ) +{ + va_list args; + va_start (args, format); + + static volatile uint8_t buffer[100]; + int strLength; + strLength = vsprintf((char *)(uintptr_t)buffer,format, args); + + #ifdef DEBUG_SERIAL_USART2 + while(__HAL_DMA_GET_COUNTER(huart2.hdmatx) > 0) { + HAL_Delay(1); + } + HAL_UART_Transmit_DMA(&huart2, (uint8_t *)buffer, strLength); + #endif + #ifdef DEBUG_SERIAL_USART3 + while(__HAL_DMA_GET_COUNTER(huart3.hdmatx) > 0) { + HAL_Delay(1); + } + HAL_UART_Transmit_DMA(&huart3, (uint8_t *)buffer, strLength); + #endif + + va_end (args); +} \ No newline at end of file diff --git a/Src/main.c b/Src/main.c index fb3c668..7f3384d 100644 --- a/Src/main.c +++ b/Src/main.c @@ -62,8 +62,8 @@ extern ExtY rtY_Right; /* External outputs */ extern int16_t cmd1; // normalized input value. -1000 to 1000 extern int16_t cmd2; // normalized input value. -1000 to 1000 -extern int16_t cmd1_in; // normalized input value. -1000 to 1000 -extern int16_t cmd2_in; // normalized input value. -1000 to 1000 +extern int16_t input1; // Non normalized input value +extern int16_t input2; // Non normalized input value extern int16_t speedAvg; // Average measured speed extern int16_t speedAvgAbs; // Average measured speed in absolute @@ -409,8 +409,8 @@ int main(void) { // ####### DEBUG SERIAL OUT ####### #if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3) if (main_loop_counter % 25 == 0) { // Send data periodically every 125 ms - setScopeChannel(0, (int16_t)cmd1_in); // 1: ADC1 - setScopeChannel(1, (int16_t)cmd2_in); // 2: ADC2 + setScopeChannel(0, (int16_t)input1); // 1: ADC1 + setScopeChannel(1, (int16_t)input2); // 2: ADC2 setScopeChannel(2, (int16_t)cmd1); //speedR); // 3: output command: [-1000, 1000] setScopeChannel(3, (int16_t)cmd2); //speedL); // 4: output command: [-1000, 1000] setScopeChannel(4, (int16_t)adc_buffer.batt1); // 5: for battery voltage calibration diff --git a/Src/util.c b/Src/util.c index 87cb14e..9630769 100644 --- a/Src/util.c +++ b/Src/util.c @@ -88,8 +88,8 @@ ExtY rtY_Right; /* External outputs */ int16_t cmd1; // normalized input value. -1000 to 1000 int16_t cmd2; // normalized input value. -1000 to 1000 -int16_t cmd1_in; // normalized input value. -1000 to 1000 -int16_t cmd2_in; // normalized input value. -1000 to 1000 +int16_t input1; // Non normalized input value +int16_t input2; // Non normalized input value int16_t speedAvg; // average measured speed int16_t speedAvgAbs; // average measured speed in absolute @@ -437,8 +437,8 @@ void adcCalibLim(void) { readInput(); // Inititalization: MIN = a high values, MAX = a low value, - int32_t input1_fixdt = cmd1_in << 16; - int32_t input2_fixdt = cmd2_in << 16; + int32_t input1_fixdt = input1 << 16; + int32_t input2_fixdt = input2 << 16; uint16_t input_cal_timeout = 0; int16_t INPUT1_MIN_temp = INPUT1_MAX; int16_t INPUT1_MID_temp = 0; @@ -452,8 +452,8 @@ void adcCalibLim(void) { // Extract MIN, MAX and MID from ADC while the power button is not pressed while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && input_cal_timeout++ < 4000) { // 20 sec timeout readInput(); - filtLowPass32(cmd1_in, FILTER, &input1_fixdt); - filtLowPass32(cmd2_in, FILTER, &input2_fixdt); + filtLowPass32(input1, FILTER, &input1_fixdt); + filtLowPass32(input2, FILTER, &input2_fixdt); INPUT1_MID_temp = (int16_t)CLAMP(input1_fixdt >> 16, INPUT1_MIN, INPUT1_MAX); // convert fixed-point to integer INPUT2_MID_temp = (int16_t)CLAMP(input2_fixdt >> 16, INPUT2_MIN, INPUT2_MAX); @@ -464,8 +464,6 @@ void adcCalibLim(void) { HAL_Delay(5); } - HAL_Delay(10); - uint16_t input_margin = 0; #ifdef CONTROL_ADC input_margin = 100; @@ -491,7 +489,7 @@ void adcCalibLim(void) { HAL_Delay(10); #ifdef CONTROL_ADC - if ( (INPUT1_MIN_CAL - ADC_PROTECT_THRESH) > 0 && (INPUT1_MAX_CAL + ADC_PROTECT_THRESH) < 4095){ + if ( ((int16_t)INPUT1_MIN_CAL - ADC_PROTECT_THRESH) > 0 && ((int16_t)INPUT1_MAX_CAL + ADC_PROTECT_THRESH) < 4095){ consoleLog(" and protected"); } #endif @@ -523,31 +521,19 @@ void adcCalibLim(void) { HAL_Delay(10); #ifdef CONTROL_ADC - if ( (INPUT2_MIN_CAL - ADC_PROTECT_THRESH) > 0 && (INPUT2_MAX_CAL + ADC_PROTECT_THRESH) < 4095 ){ + if ( ((int16_t)INPUT2_MIN_CAL - ADC_PROTECT_THRESH) > 0 && ((int16_t)INPUT2_MAX_CAL + ADC_PROTECT_THRESH) < 4095 ){ consoleLog(" and protected"); } #endif input_cal_valid = 1; } - HAL_Delay(10); - consoleLog("\n"); - HAL_Delay(10); - consoleLog("Saved limits\n"); - HAL_Delay(10); - setScopeChannel(0, (int16_t)INPUT1_MIN_CAL); - setScopeChannel(1, (int16_t)INPUT1_MID_CAL); - setScopeChannel(2, (int16_t)INPUT1_MAX_CAL); - setScopeChannel(3, (int16_t)0); - setScopeChannel(4, (int16_t)INPUT2_MIN_CAL); - setScopeChannel(5, (int16_t)INPUT2_MID_CAL); - setScopeChannel(6, (int16_t)INPUT2_MAX_CAL); - setScopeChannel(7, (int16_t)0); - consoleScope(); - - HAL_Delay(20); - consoleLog("OK\n"); - + print("\n"); + print("Saved limits\n"); + print("INPUT1_MIN:%i INPUT1_MID:%i INPUT1_MAX:%i\n", (int16_t)INPUT1_MIN_CAL,(int16_t)INPUT1_MID_CAL,(int16_t)INPUT1_MAX_CAL); + print("INPUT2_MIN:%i INPUT2_MID:%i INPUT2_MAX:%i\n", (int16_t)INPUT2_MIN_CAL,(int16_t)INPUT2_MID_CAL,(int16_t)INPUT2_MAX_CAL); + print("OK\n"); + #endif } @@ -568,8 +554,8 @@ void updateCurSpdLim(void) { consoleLog("Torque and Speed limits update started...\n"); - int32_t input1_fixdt = cmd1_in << 16; - int32_t input2_fixdt = cmd2_in << 16; + int32_t input1_fixdt = input1 << 16; + int32_t input2_fixdt = input2 << 16; uint16_t cur_spd_timeout = 0; uint16_t cur_factor; // fixdt(0,16,16) uint16_t spd_factor; // fixdt(0,16,16) @@ -577,21 +563,26 @@ void updateCurSpdLim(void) { // Wait for the power button press while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && cur_spd_timeout++ < 2000) { // 10 sec timeout readInput(); - filtLowPass32(cmd1_in, FILTER, &input1_fixdt); - filtLowPass32(cmd2_in, FILTER, &input2_fixdt); + filtLowPass32(input1, FILTER, &input1_fixdt); + filtLowPass32(input2, FILTER, &input2_fixdt); HAL_Delay(5); } - // Calculate scaling factors cur_factor = CLAMP((input1_fixdt - ((int16_t)INPUT1_MIN_CAL << 16)) / ((int16_t)INPUT1_MAX_CAL - (int16_t)INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A spd_factor = CLAMP((input2_fixdt - ((int16_t)INPUT2_MIN_CAL << 16)) / ((int16_t)INPUT2_MAX_CAL - (int16_t)INPUT2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm - // Update maximum limits - rtP_Left.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) - rtP_Left.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) - rtP_Right.i_max = rtP_Left.i_max; - rtP_Right.n_max = rtP_Left.n_max; + + if (INPUT1_TYPE != 0){ + // Update current limit + rtP_Right.i_max = rtP_Left.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) + cur_spd_valid = 1; + } - HAL_Delay(10); + if (INPUT2_TYPE != 0){ + // Update speed limit + rtP_Right.n_max = rtP_Left.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) + cur_spd_valid = 1; + } + consoleLog("Saved limits\n"); HAL_Delay(10); setScopeChannel(0, (int16_t)input1_fixdt); @@ -603,11 +594,9 @@ void updateCurSpdLim(void) { setScopeChannel(6, (int16_t)rtP_Right.n_max); setScopeChannel(7, (int16_t)0); consoleScope(); - HAL_Delay(20); - - cur_spd_valid = 1; consoleLog("OK\n"); + #endif } @@ -816,8 +805,8 @@ void readInput(void) { #if defined(CONTROL_NUNCHUK) || defined(SUPPORT_NUNCHUK) if (nunchuk_connected != 0) { Nunchuk_Read(); - cmd1_in = (nunchuk_data[0] - 127) * 8; // X axis 0-255 - cmd2_in = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 + input1 = (nunchuk_data[0] - 127) * 8; // X axis 0-255 + input2 = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 #ifdef SUPPORT_BUTTONS button1 = (uint8_t)nunchuk_data[5] & 1; @@ -827,8 +816,8 @@ void readInput(void) { #endif #if defined(CONTROL_PPM_LEFT) || defined(CONTROL_PPM_RIGHT) - cmd1_in = (ppm_captured_value[0] - 500) * 2; - cmd2_in = (ppm_captured_value[1] - 500) * 2; + input1 = (ppm_captured_value[0] - 500) * 2; + input2 = (ppm_captured_value[1] - 500) * 2; #ifdef SUPPORT_BUTTONS button1 = ppm_captured_value[5] > 500; button2 = 0; @@ -836,14 +825,14 @@ void readInput(void) { #endif #if defined(CONTROL_PWM_LEFT) || defined(CONTROL_PWM_RIGHT) - cmd1_in = (pwm_captured_ch1_value - 500) * 2; - cmd2_in = (pwm_captured_ch2_value - 500) * 2; + input1 = (pwm_captured_ch1_value - 500) * 2; + input2 = (pwm_captured_ch2_value - 500) * 2; #endif #ifdef CONTROL_ADC // ADC values range: 0-4095, see ADC-calibration in config.h - cmd1_in = adc_buffer.l_tx2; - cmd2_in = adc_buffer.l_rx2; + input1 = adc_buffer.l_tx2; + input2 = adc_buffer.l_rx2; #endif #if defined(CONTROL_SERIAL_USART2) || defined(CONTROL_SERIAL_USART3) @@ -852,12 +841,12 @@ void readInput(void) { for (uint8_t i = 0; i < (IBUS_NUM_CHANNELS * 2); i+=2) { ibus_captured_value[(i/2)] = CLAMP(command.channels[i] + (command.channels[i+1] << 8) - 1000, 0, INPUT_MAX); // 1000-2000 -> 0-1000 } - cmd1_in = (ibus_captured_value[0] - 500) * 2; - cmd2_in = (ibus_captured_value[1] - 500) * 2; + input1 = (ibus_captured_value[0] - 500) * 2; + input2 = (ibus_captured_value[1] - 500) * 2; #else if (IN_RANGE(command.steer, INPUT_MIN, INPUT_MAX) && IN_RANGE(command.speed, INPUT_MIN, INPUT_MAX)) { - cmd1_in = command.steer; - cmd2_in = command.speed; + input1 = command.steer; + input2 = command.speed; } #endif timeoutCnt = 0; @@ -871,8 +860,8 @@ void readCommand(void) { readInput(); #ifdef CONTROL_ADC // If input1 or Input2 is either below MIN - Threshold or above MAX + Threshold, ADC protection timeout - if ((IN_RANGE(cmd1_in,INPUT1_MIN_CAL - ADC_PROTECT_THRESH,INPUT1_MAX_CAL + ADC_PROTECT_THRESH)) && - (IN_RANGE(cmd1_in,INPUT2_MIN_CAL - ADC_PROTECT_THRESH,INPUT2_MAX_CAL + ADC_PROTECT_THRESH))){ + if ((IN_RANGE(input1,(int16_t)INPUT1_MIN_CAL - ADC_PROTECT_THRESH,(int16_t)INPUT1_MAX_CAL + ADC_PROTECT_THRESH)) && + (IN_RANGE(input2,(int16_t)INPUT2_MIN_CAL - ADC_PROTECT_THRESH,(int16_t)INPUT2_MAX_CAL + ADC_PROTECT_THRESH))){ if (timeoutFlagADC) { // Check for previous timeout flag if (timeoutCntADC-- <= 0) // Timeout de-qualification timeoutFlagADC = 0; // Timeout flag cleared @@ -912,10 +901,10 @@ void readCommand(void) { cmd1 = 0; break; case 1: // Input1 is a normal pot - cmd1 = CLAMP(MAP( cmd1_in , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC1 + cmd1 = CLAMP(MAP( input1 , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); break; case 2: // Input1 is a mid resting pot - cmd1 = addDeadBand(cmd1_in, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); + cmd1 = addDeadBand(input1, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); break; default: cmd1 = 0; @@ -928,17 +917,17 @@ void readCommand(void) { cmd2 = 0; break; case 1: // Input2 is a normal pot - cmd2 = CLAMP(MAP( cmd2_in , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); // ADC2 + cmd2 = CLAMP(MAP( input2 , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); break; case 2: // Input2 is a mid resting pot - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(input2, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); break; default: cmd2 = 0; break; } #else - cmd2 = addDeadBand(cmd2_in, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_OUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(input2, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_OUT_MIN, INPUT_MAX); #endif #endif diff --git a/platformio.ini b/platformio.ini index 9926883..2a45d1b 100644 --- a/platformio.ini +++ b/platformio.ini @@ -11,7 +11,7 @@ src_dir = Src ; ;default_envs = VARIANT_ADC ; Variant for control via ADC input ;default_envs = VARIANT_USART ; Variant for Serial control via USART3 input -;default_envs = VARIANT_NUNCHUK ; Variant for Nunchuk controlled vehicle build +default_envs = VARIANT_NUNCHUK ; Variant for Nunchuk controlled vehicle build ;default_envs = VARIANT_PPM ; Variant for RC-Remotes with PPM-Sum signal ;default_envs = VARIANT_PWM ; Variant for RC-Remotes with PWM signal ;default_envs = VARIANT_IBUS ; Variant for RC-Remotes with FLYSKY IBUS From 1ab75e5ff9aab76ca16ddc74a55992bcef1aa5d0 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Sun, 15 Nov 2020 18:09:30 +0100 Subject: [PATCH 20/26] Fix auto calibration --- Inc/comms.h | 1 - Inc/config.h | 1 + Inc/util.h | 3 +- Src/comms.c | 25 ------- Src/main.c | 8 +-- Src/util.c | 179 ++++++++++++++++++++++--------------------------- platformio.ini | 2 +- 7 files changed, 89 insertions(+), 130 deletions(-) diff --git a/Inc/comms.h b/Inc/comms.h index b723283..6bdb730 100644 --- a/Inc/comms.h +++ b/Inc/comms.h @@ -28,7 +28,6 @@ void setScopeChannel(uint8_t ch, int16_t val); void consoleScope(void); void consoleLog(char *message); -void print( const char * format, ... ); #endif diff --git a/Inc/config.h b/Inc/config.h index 449c9fb..a287a96 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -434,6 +434,7 @@ #define USART2_BAUD 115200 #define CONTROL_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! #define FEEDBACK_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! + // #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif // ############################# END OF VARIANT_IBUS SETTINGS ############################ diff --git a/Inc/util.h b/Inc/util.h index cca2489..ee2cba6 100644 --- a/Inc/util.h +++ b/Inc/util.h @@ -67,9 +67,10 @@ void shortBeepMany(uint8_t cnt, int8_t dir); void longBeep(uint8_t freq); void calcAvgSpeed(void); void adcCalibLim(void); +int checkInputType(int16_t min, int16_t mid, int16_t max); void updateCurSpdLim(void); void saveConfig(void); -int addDeadBand(int16_t u, 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); void standstillHold(int16_t *speedCmd); void electricBrake(uint16_t speedBlend, uint8_t reverseDir); void cruiseControl(uint8_t button); diff --git a/Src/comms.c b/Src/comms.c index 881b2cc..d1626e5 100644 --- a/Src/comms.c +++ b/Src/comms.c @@ -80,28 +80,3 @@ void consoleLog(char *message) #endif #endif } - -void print( const char * format, ... ) -{ - va_list args; - va_start (args, format); - - static volatile uint8_t buffer[100]; - int strLength; - strLength = vsprintf((char *)(uintptr_t)buffer,format, args); - - #ifdef DEBUG_SERIAL_USART2 - while(__HAL_DMA_GET_COUNTER(huart2.hdmatx) > 0) { - HAL_Delay(1); - } - HAL_UART_Transmit_DMA(&huart2, (uint8_t *)buffer, strLength); - #endif - #ifdef DEBUG_SERIAL_USART3 - while(__HAL_DMA_GET_COUNTER(huart3.hdmatx) > 0) { - HAL_Delay(1); - } - HAL_UART_Transmit_DMA(&huart3, (uint8_t *)buffer, strLength); - #endif - - va_end (args); -} \ No newline at end of file diff --git a/Src/main.c b/Src/main.c index 7f3384d..09e156f 100644 --- a/Src/main.c +++ b/Src/main.c @@ -409,10 +409,10 @@ int main(void) { // ####### DEBUG SERIAL OUT ####### #if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3) if (main_loop_counter % 25 == 0) { // Send data periodically every 125 ms - setScopeChannel(0, (int16_t)input1); // 1: ADC1 - setScopeChannel(1, (int16_t)input2); // 2: ADC2 - setScopeChannel(2, (int16_t)cmd1); //speedR); // 3: output command: [-1000, 1000] - setScopeChannel(3, (int16_t)cmd2); //speedL); // 4: output command: [-1000, 1000] + setScopeChannel(0, (int16_t)input1); // 1: INPUT1 + setScopeChannel(1, (int16_t)input2); // 2: INPUT2 + setScopeChannel(2, (int16_t)speedR); // 3: output command: [-1000, 1000] + setScopeChannel(3, (int16_t)speedL); // 4: output command: [-1000, 1000] setScopeChannel(4, (int16_t)adc_buffer.batt1); // 5: for battery voltage calibration setScopeChannel(5, (int16_t)(batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC)); // 6: for verifying battery voltage calibration setScopeChannel(6, (int16_t)board_temp_adcFilt); // 7: for board temperature calibration diff --git a/Src/util.c b/Src/util.c index 9630769..e7de42c 100644 --- a/Src/util.c +++ b/Src/util.c @@ -455,86 +455,87 @@ void adcCalibLim(void) { filtLowPass32(input1, FILTER, &input1_fixdt); filtLowPass32(input2, FILTER, &input2_fixdt); - INPUT1_MID_temp = (int16_t)CLAMP(input1_fixdt >> 16, INPUT1_MIN, INPUT1_MAX); // convert fixed-point to integer - INPUT2_MID_temp = (int16_t)CLAMP(input2_fixdt >> 16, INPUT2_MIN, INPUT2_MAX); + INPUT1_MID_temp = (int16_t)(input1_fixdt >> 16);// CLAMP(input1_fixdt >> 16, INPUT1_MIN, INPUT1_MAX); // convert fixed-point to integer + INPUT2_MID_temp = (int16_t)(input2_fixdt >> 16);// CLAMP(input2_fixdt >> 16, INPUT2_MIN, INPUT2_MAX); INPUT1_MIN_temp = MIN(INPUT1_MIN_temp, INPUT1_MID_temp); INPUT1_MAX_temp = MAX(INPUT1_MAX_temp, INPUT1_MID_temp); INPUT2_MIN_temp = MIN(INPUT2_MIN_temp, INPUT2_MID_temp); INPUT2_MAX_temp = MAX(INPUT2_MAX_temp, INPUT2_MID_temp); HAL_Delay(5); } - + uint16_t input_margin = 0; #ifdef CONTROL_ADC input_margin = 100; #endif - int16_t threshold = (INPUT1_MAX - INPUT1_MIN) / 10; INPUT1_MIN_CAL = INPUT1_MIN_temp + input_margin; INPUT1_MID_CAL = INPUT1_MID_temp; INPUT1_MAX_CAL = INPUT1_MAX_temp - input_margin; - if ( (INPUT1_MIN_temp/threshold) == (INPUT1_MAX_temp/threshold) ){ - // MIN MID and MAX are close, there is no input - INPUT1_TYPE_CAL = 0; - consoleLog("Input1 is ignored"); - } else { - if ( (INPUT1_MIN_temp/threshold) == (INPUT1_MID_temp/threshold) ){ - // MIN and MID are close, it's a normal pot - INPUT1_TYPE_CAL = 1; - consoleLog("Input1 is a normal pot"); - }else { - INPUT1_TYPE_CAL = 2; - consoleLog("Input1 is a mid-resting pot"); - } + INPUT1_TYPE_CAL = checkInputType(INPUT1_MIN_CAL,INPUT1_MID_CAL,INPUT1_MAX_CAL); - HAL_Delay(10); - #ifdef CONTROL_ADC - if ( ((int16_t)INPUT1_MIN_CAL - ADC_PROTECT_THRESH) > 0 && ((int16_t)INPUT1_MAX_CAL + ADC_PROTECT_THRESH) < 4095){ - consoleLog(" and protected"); - } - #endif - input_cal_valid = 1; + INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; + INPUT2_MID_CAL = INPUT2_MID_temp; + INPUT2_MAX_CAL = INPUT2_MAX_temp - input_margin; + INPUT2_TYPE_CAL = checkInputType(INPUT2_MIN_CAL,INPUT2_MID_CAL,INPUT2_MAX_CAL); + + consoleLog("Saved limits\n"); + HAL_Delay(10); + setScopeChannel(0, (int16_t)INPUT1_MIN_CAL); + setScopeChannel(1, (uint16_t)INPUT1_MID_CAL); + setScopeChannel(2, (int16_t)INPUT1_MAX_CAL); + setScopeChannel(3, (int16_t)0); + setScopeChannel(4, (int16_t)INPUT2_MIN_CAL); + setScopeChannel(5, (uint16_t)INPUT2_MID_CAL); + setScopeChannel(6, (int16_t)INPUT2_MAX_CAL); + setScopeChannel(7, (int16_t)0); + consoleScope(); + HAL_Delay(20); + consoleLog("OK\n"); + + #endif +} + +int checkInputType(int16_t min, int16_t mid, int16_t max){ + + HAL_Delay(10); + + int type = 0; + + // Threshold to define if values are too close + int16_t threshold = 200; + #ifdef CONTROL_ADC + threshold = 400; + #endif + + if ( (min/threshold) == (max/threshold) ){ + // MIN MID and MAX are close, disable input + consoleLog("Input is ignored"); + type = 0; + } else { + if ( (min/threshold) == (mid/threshold) ){ + // MIN and MID are close, it's a normal pot + consoleLog("Input is a normal pot"); + type = 1; + }else { + // it's a mid resting pot + consoleLog("Input is a mid-resting pot"); + type = 2; + } + + HAL_Delay(10); + #ifdef CONTROL_ADC + if ( (min - ADC_PROTECT_THRESH) > 0 && (max + ADC_PROTECT_THRESH) < 4095){ + consoleLog(" and protected"); + } + #endif } HAL_Delay(10); consoleLog("\n"); HAL_Delay(10); - - threshold = (INPUT2_MAX - INPUT2_MIN) / 10; - INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; - INPUT2_MID_CAL = INPUT2_MID_temp; - INPUT2_MAX_CAL = INPUT2_MAX_temp - input_margin; - if ( (INPUT2_MIN_temp/threshold) == (INPUT2_MAX_temp/threshold) ){ - // MIN MID and MAX are close, there is no input - INPUT2_TYPE_CAL = 0; - consoleLog("Input2 is ignored"); - } else { - if ( (INPUT2_MIN_temp/threshold) == (INPUT2_MID_temp/threshold) ){ - // MIN and MID are close, it's a normal pot - INPUT2_TYPE_CAL = 1; - consoleLog("Input2 is a normal pot"); - }else { - INPUT2_TYPE_CAL = 2; - consoleLog("Input2 is a mid-resting pot"); - } - - HAL_Delay(10); - - #ifdef CONTROL_ADC - if ( ((int16_t)INPUT2_MIN_CAL - ADC_PROTECT_THRESH) > 0 && ((int16_t)INPUT2_MAX_CAL + ADC_PROTECT_THRESH) < 4095 ){ - consoleLog(" and protected"); - } - #endif - input_cal_valid = 1; - } - - print("\n"); - print("Saved limits\n"); - print("INPUT1_MIN:%i INPUT1_MID:%i INPUT1_MAX:%i\n", (int16_t)INPUT1_MIN_CAL,(int16_t)INPUT1_MID_CAL,(int16_t)INPUT1_MAX_CAL); - print("INPUT2_MIN:%i INPUT2_MID:%i INPUT2_MAX:%i\n", (int16_t)INPUT2_MIN_CAL,(int16_t)INPUT2_MID_CAL,(int16_t)INPUT2_MAX_CAL); - print("OK\n"); - #endif + return type; } @@ -571,13 +572,13 @@ void updateCurSpdLim(void) { cur_factor = CLAMP((input1_fixdt - ((int16_t)INPUT1_MIN_CAL << 16)) / ((int16_t)INPUT1_MAX_CAL - (int16_t)INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A spd_factor = CLAMP((input2_fixdt - ((int16_t)INPUT2_MIN_CAL << 16)) / ((int16_t)INPUT2_MAX_CAL - (int16_t)INPUT2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm - if (INPUT1_TYPE != 0){ + if (INPUT1_TYPE_CAL != 0){ // Update current limit rtP_Right.i_max = rtP_Left.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) cur_spd_valid = 1; } - if (INPUT2_TYPE != 0){ + if (INPUT2_TYPE_CAL != 0){ // Update speed limit rtP_Right.n_max = rtP_Left.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) cur_spd_valid = 1; @@ -635,13 +636,22 @@ void saveConfig() { * Add Dead-band to a signal * This function realizes a dead-band around 0 and scales the input between [out_min, out_max] */ -int addDeadBand(int16_t u, int16_t deadBand, int16_t in_min, int16_t in_mid, int16_t in_max, int16_t out_min, int16_t out_max) { - if( u > in_mid - deadBand && u < in_mid + deadBand ) { - return 0; - } else if(u > in_mid) { - return CLAMP( MAP(u, in_mid + deadBand, in_max, 0, out_max), 0 , out_max); - } else { - return CLAMP( MAP(u, in_mid - deadBand, in_min, 0, out_min), out_min, 0); +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) { + switch (type){ + case 0: // Input is ignored + return 0; + case 1: // Input is a normal pot + return CLAMP(MAP( u , in_min, in_max, 0, out_max ), 0, out_max); + case 2: // Input is a mid resting pot + if( u > in_mid - deadBand && u < in_mid + deadBand ) { + return 0; + } else if(u > in_mid) { + return CLAMP( MAP(u, in_mid + deadBand, in_max, 0, out_max), 0 , out_max); + } else { + return CLAMP( MAP(u, in_mid - deadBand, in_min, 0, out_min), out_min, 0); + } + default: + return 0; } } @@ -896,38 +906,11 @@ void readCommand(void) { #endif #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - switch (INPUT1_TYPE_CAL){ - case 0: // Input1 is ignored - cmd1 = 0; - break; - case 1: // Input1 is a normal pot - cmd1 = CLAMP(MAP( input1 , INPUT1_MIN_CAL, INPUT1_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); - break; - case 2: // Input1 is a mid resting pot - cmd1 = addDeadBand(input1, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); - break; - default: - cmd1 = 0; - break; - } - + cmd1 = addDeadBand(input1, INPUT1_TYPE_CAL, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); #if !defined(VARIANT_SKATEBOARD) - switch (INPUT2_TYPE_CAL){ - case 0: // Input2 is ignored - cmd2 = 0; - break; - case 1: // Input2 is a normal pot - cmd2 = CLAMP(MAP( input2 , INPUT2_MIN_CAL, INPUT2_MAX_CAL, 0, INPUT_MAX ), 0, INPUT_MAX); - break; - case 2: // Input2 is a mid resting pot - cmd2 = addDeadBand(input2, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); - break; - default: - cmd2 = 0; - break; - } + cmd2 = addDeadBand(input2, INPUT2_TYPE_CAL, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); #else - cmd2 = addDeadBand(input2, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_OUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(input2, INPUT2_TYPE_CAL, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_OUT_MIN, INPUT_MAX); #endif #endif diff --git a/platformio.ini b/platformio.ini index 2a45d1b..9926883 100644 --- a/platformio.ini +++ b/platformio.ini @@ -11,7 +11,7 @@ src_dir = Src ; ;default_envs = VARIANT_ADC ; Variant for control via ADC input ;default_envs = VARIANT_USART ; Variant for Serial control via USART3 input -default_envs = VARIANT_NUNCHUK ; Variant for Nunchuk controlled vehicle build +;default_envs = VARIANT_NUNCHUK ; Variant for Nunchuk controlled vehicle build ;default_envs = VARIANT_PPM ; Variant for RC-Remotes with PPM-Sum signal ;default_envs = VARIANT_PWM ; Variant for RC-Remotes with PWM signal ;default_envs = VARIANT_IBUS ; Variant for RC-Remotes with FLYSKY IBUS From ec64b8b005e510d56029a44587d2564b6ffcec2c Mon Sep 17 00:00:00 2001 From: Candas1 Date: Sun, 15 Nov 2020 18:11:45 +0100 Subject: [PATCH 21/26] Revert changes in comms.c --- Src/comms.c | 1 - 1 file changed, 1 deletion(-) diff --git a/Src/comms.c b/Src/comms.c index d1626e5..61ee47d 100644 --- a/Src/comms.c +++ b/Src/comms.c @@ -1,5 +1,4 @@ #include -#include #include #include "stm32f1xx_hal.h" #include "defines.h" From 962f57a85ffadb7b165dff1139d12a1f310577b3 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Sun, 15 Nov 2020 20:04:40 +0100 Subject: [PATCH 22/26] Improve PPM --- Inc/config.h | 2 +- Src/control.c | 12 +++++++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index a287a96..6327998 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -338,7 +338,7 @@ * https://gist.github.com/peterpoetzi/1b63a4a844162196613871767189bd05 */ #define CONTROL_PPM_LEFT // use PPM-Sum as input on the LEFT cable . disable CONTROL_SERIAL_USART2! - // #define CONTROL_PPM_RIGHT // use PPM-Sum as input on the RIGHT cable. disable CONTROL_SERIAL_USART3! + //#define CONTROL_PPM_RIGHT // use PPM-Sum as input on the RIGHT cable. disable CONTROL_SERIAL_USART3! #ifdef CONTROL_PPM_RIGHT #define DEBUG_SERIAL_USART2 // left sensor cable debug #else diff --git a/Src/control.c b/Src/control.c index 8f0c541..a6c53be 100644 --- a/Src/control.c +++ b/Src/control.c @@ -34,13 +34,14 @@ void PPM_ISR_Callback(void) { if (rc_delay > 3000) { if (ppm_valid && ppm_count == PPM_NUM_CHANNELS) { ppm_timeout = 0; + timeoutCnt = 0; // added this memcpy(ppm_captured_value, ppm_captured_value_buffer, sizeof(ppm_captured_value)); } ppm_valid = true; ppm_count = 0; } else if (ppm_count < PPM_NUM_CHANNELS && IN_RANGE(rc_delay, 900, 2100)){ - timeoutCnt = 0; + //timeoutCnt = 0; ppm_captured_value_buffer[ppm_count++] = CLAMP(rc_delay, 1000, 2000) - 1000; } else { ppm_valid = false; @@ -77,9 +78,18 @@ void PPM_Init(void) { TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; HAL_TIM_Base_Init(&TimHandle); + #if defined(CONTROL_PPM_LEFT) /* EXTI interrupt init*/ HAL_NVIC_SetPriority(EXTI3_IRQn, 0, 0); HAL_NVIC_EnableIRQ(EXTI3_IRQn); + #endif + + #if defined(CONTROL_PPM_RIGHT) + /* EXTI interrupt init*/ + HAL_NVIC_SetPriority(EXTI15_10_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(EXTI15_10_IRQn); + #endif + HAL_TIM_Base_Start(&TimHandle); } #endif From 44befc480a650bca5099642d24bba29abb791721 Mon Sep 17 00:00:00 2001 From: EmanuelFeru Date: Wed, 18 Nov 2020 19:16:56 +0100 Subject: [PATCH 23/26] Input Auto-calibration - mainly rearangement of function - updated initialization in the auto-calibration function - added beep for confirmation of Input protection --- Inc/config.h | 167 +++++++++--------- Inc/util.h | 8 +- Src/control.c | 3 +- Src/main.c | 1 + Src/util.c | 455 +++++++++++++++++++++++++------------------------- 5 files changed, 307 insertions(+), 327 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index 6327998..c752b0f 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -166,9 +166,9 @@ // ############################## DEFAULT SETTINGS ############################ // Default settings will be applied at the end of this config file if not set before -#define INACTIVITY_TIMEOUT 8 // Minutes of not driving until poweroff. it is not very precise. -#define BEEPS_BACKWARD 1 // 0 or 1 -#define FLASH_WRITE_KEY 0x1234 // Flash writing key, used when writing data to flash memory +#define INACTIVITY_TIMEOUT 8 // Minutes of not driving until poweroff. it is not very precise. +#define BEEPS_BACKWARD 1 // 0 or 1 +#define FLASH_WRITE_KEY 0x1233 // Flash memory writing key. Change this key to ignore the input calibrations from the flash memory and use the ones in config.h /* FILTER is in fixdt(0,16,16): VAL_fixedPoint = VAL_floatingPoint * 2^16. In this case 6553 = 0.1 * 2^16 * Value of COEFFICIENT is in fixdt(1,16,14) @@ -201,7 +201,7 @@ // ############################### DEBUG SERIAL ############################### /* Connect GND and RX of a 3.3v uart-usb adapter to the left (USART2) or right sensor board cable (USART3) - * Be careful not to use the red wire of the cable. 15v will destroye evrything. + * Be careful not to use the red wire of the cable. 15v will destroy everything. * If you are using VARIANT_NUNCHUK, disable it temporarily. * enable DEBUG_SERIAL_USART3 or DEBUG_SERIAL_USART2 * and DEBUG_SERIAL_ASCII use asearial terminal. @@ -210,8 +210,8 @@ * DEBUG_SERIAL_ASCII output is: * // "1:345 2:1337 3:0 4:0 5:0 6:0 7:0 8:0\r\n" * - * 1: (int16_t)adc_buffer.l_tx2); ADC1 - * 2: (int16_t)adc_buffer.l_rx2); ADC2 + * 1: (int16_t)input1); raw input1: ADC1, UART, PWM, PPM, iBUS + * 2: (int16_t)input2); raw input2: ADC2, UART, PWM, PPM, iBUS * 3: (int16_t)speedR); output command: [-1000, 1000] * 4: (int16_t)speedL); output command: [-1000, 1000] * 5: (int16_t)adc_buffer.batt1); Battery adc-value measured by mainboard @@ -252,18 +252,18 @@ */ #define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2, FEEDBACK_SERIAL_USART2, DEBUG_SERIAL_USART2! #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken - #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values + #define ADC_PROTECT_THRESH 200 // ADC Protection threshold below/above the MIN/MAX ADC values #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) #define INPUT1_MID 2048 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) #define INPUT1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) #define INPUT2_MID 2048 // mid ADC2-value while poti at minimum-position (ADC2_MIN - ADC2_MAX) #define INPUT2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! #endif @@ -282,18 +282,18 @@ #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) #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #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 INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) - // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! - // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! + // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! #endif // ######################## END OF VARIANT_USART SETTINGS ######################### @@ -301,7 +301,7 @@ // ################################# VARIANT_NUNCHUK SETTINGS ############################ #ifdef VARIANT_NUNCHUK - /* left sensor board cable. USART3 + /* on Right sensor cable * keep cable short, use shielded cable, use ferrits, stabalize voltage in nunchuk, * use the right one of the 2 types of nunchuks, add i2c pullups. * use original nunchuk. most clones does not work very well. @@ -309,23 +309,23 @@ */ #define CONTROL_NUNCHUK // use nunchuk as input. disable FEEDBACK_SERIAL_USART3, DEBUG_SERIAL_USART3! // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT1_MIN -1024 // (-1024 - 0) + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_MIN -1024 // (-1024 - 0) #define INPUT1_MID 0 - #define INPUT1_MAX 1024 // (0 - 1024) + #define INPUT1_MAX 1024 // (0 - 1024) + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_MIN -1024 // (-1024 - 0) + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_MIN -1024 // (-1024 - 0) #define INPUT2_MID 0 - #define INPUT2_MAX 1024 // (0 - 1024) + #define INPUT2_MAX 1024 // (0 - 1024) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // # maybe good for ARMCHAIR # - #define FILTER 3276 // 0.05f - #define SPEED_COEFFICIENT 8192 // 0.5f - #define STEER_COEFFICIENT 62259 // -0.2f + #define FILTER 3276 // 0.05f + #define SPEED_COEFFICIENT 8192 // 0.5f + #define STEER_COEFFICIENT 62259 // -0.2f #define DEBUG_SERIAL_USART2 // left sensor cable debug - // #define SUPPORT_BUTTONS // Define for Nunchuck buttons support + // #define SUPPORT_BUTTONS // Define for Nunchuck buttons support #endif // ############################# END OF VARIANT_NUNCHUK SETTINGS ######################### @@ -338,25 +338,25 @@ * https://gist.github.com/peterpoetzi/1b63a4a844162196613871767189bd05 */ #define CONTROL_PPM_LEFT // use PPM-Sum as input on the LEFT cable . disable CONTROL_SERIAL_USART2! - //#define CONTROL_PPM_RIGHT // use PPM-Sum as input on the RIGHT cable. disable CONTROL_SERIAL_USART3! + // #define CONTROL_PPM_RIGHT // use PPM-Sum as input on the RIGHT cable. disable CONTROL_SERIAL_USART3! #ifdef CONTROL_PPM_RIGHT #define DEBUG_SERIAL_USART2 // left sensor cable debug #else #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif - #define PPM_NUM_CHANNELS 6 // total number of PPM channels to receive, even if they are not used. + #define PPM_NUM_CHANNELS 6 // total number of PPM channels to receive, even if they are not used. // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 - #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_MIN -1000 // (-1000 - 0) + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 - #define INPUT2_MAX 1000 // (0 - 1000) + #define INPUT2_MAX 1000 // (0 - 1000) + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // #define SUPPORT_BUTTONS // Define for PPM buttons support // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! @@ -378,17 +378,17 @@ #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 - #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_MIN -1000 // (-1000 - 0) + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 - #define INPUT2_MAX 1000 // (0 - 1000) + #define INPUT2_MAX 1000 // (0 - 1000) + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define FILTER 6553 // 0.1f [-] fixdt(0,16,16) lower value == softer filter [0, 65535] = [0.0 - 1.0]. #define SPEED_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 @@ -397,11 +397,6 @@ // #define INVERT_L_DIRECTION // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! // #define SUPPORT_BUTTONS_RIGHT // use right sensor board cable for button inputs. Disable DEBUG_SERIAL_USART3! - #ifdef CONTROL_PWM_RIGHT - #define DEBUG_SERIAL_USART2 // left sensor cable debug - #else - #define DEBUG_SERIAL_USART3 // right sensor cable debug - #endif #endif // ############################# END OF VARIANT_PWM SETTINGS ############################ @@ -412,29 +407,29 @@ /* CONTROL VIA RC REMOTE WITH FLYSKY IBUS PROTOCOL * Connected to Left sensor board cable. Channel 1: steering, Channel 2: speed. */ - #define CONTROL_IBUS // use IBUS as input - #define IBUS_NUM_CHANNELS 14 // total number of IBUS channels to receive, even if they are not used. + #define CONTROL_IBUS // use IBUS as input + #define IBUS_NUM_CHANNELS 14 // total number of IBUS channels to receive, even if they are not used. #define IBUS_LENGTH 0x20 #define IBUS_COMMAND 0x40 - // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT1_MIN -1000 // (-1000 - 0) - #define INPUT1_MID 0 - #define INPUT1_MAX 1000 // (0 - 1000) - - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_MIN -1000 // (-1000 - 0) - #define INPUT2_MID 0 - #define INPUT2_MAX 1000 // (0 - 1000) - #undef USART2_BAUD - #define USART2_BAUD 115200 - #define CONTROL_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! - #define FEEDBACK_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! - // #define DEBUG_SERIAL_USART3 // right sensor cable debug + #define USART2_BAUD 115200 + #define CONTROL_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! + #define FEEDBACK_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! + // #define DEBUG_SERIAL_USART3 // right sensor cable debug + + // Min / Max values of each channel (use DEBUG to determine these values) + #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_MID 0 + #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 INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_MIN -1000 // (-1000 - 0) + #define INPUT2_MID 0 + #define INPUT2_MAX 1000 // (0 - 1000) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #endif // ############################# END OF VARIANT_IBUS SETTINGS ############################ @@ -446,19 +441,19 @@ #define CTRL_MOD_REQ TRQ_MODE // HOVERCAR works best in TORQUE Mode #define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2, FEEDBACK_SERIAL_USART2, DEBUG_SERIAL_USART2! #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken - #define ADC_PROTECT_THRESH 300 // ADC Protection threshold below/above the MIN/MAX ADC values + #define ADC_PROTECT_THRESH 200 // ADC Protection threshold below/above the MIN/MAX ADC values #define INPUT1_TYPE 1 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT1_MIN 1000 // min ADC1-value while poti at minimum-position (0 - 4095) #define INPUT1_MID 0 #define INPUT1_MAX 2500 // max ADC1-value while poti at maximum-position (0 - 4095) + #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_TYPE 1 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define INPUT2_MIN 500 // min ADC2-value while poti at minimum-position (0 - 4095) #define INPUT2_MID 0 #define INPUT2_MAX 2200 // max ADC2-value while poti at maximum-position (0 - 4095) + #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) #define SPEED_COEFFICIENT 16384 // 1.0f #define STEER_COEFFICIENT 0 // 0.0f @@ -523,7 +518,7 @@ * Channel 1: steering, Channel 2: speed. */ #undef CTRL_MOD_REQ - #define CTRL_MOD_REQ TRQ_MODE // SKATEBOARD works best in TORQUE Mode + #define CTRL_MOD_REQ TRQ_MODE // SKATEBOARD works best in TORQUE Mode //#define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! #ifdef CONTROL_PWM_RIGHT @@ -532,18 +527,18 @@ #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 0 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT1_MIN -1000 // (-1000 - 0) + #define INPUT1_TYPE 0 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 - #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT1_MAX 1000 // (0 - 1000) + #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot - #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_MIN -800 // (-1000 - 0) + #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_MIN -800 // (-1000 - 0) #define INPUT2_MID 0 - #define INPUT2_MAX 700 // (0 - 1000) - #define INPUT2_OUT_MIN -400 // (-1000 - 0) Change this value to adjust the braking amount + #define INPUT2_MAX 700 // (0 - 1000) + #define INPUT2_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) + #define INPUT2_BRAKE -400 // (-1000 - 0) Change this value to adjust the braking amount #define FILTER 6553 // 0.1f [-] fixdt(0,16,16) lower value == softer filter [0, 65535] = [0.0 - 1.0]. #define SPEED_COEFFICIENT 16384 // 1.0f [-] fixdt(1,16,14) higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 @@ -711,16 +706,6 @@ // Functional checks -#if defined(ADC_PROTECT_ENA) && ((ADC1_MIN - ADC_PROTECT_THRESH) <= 0 || (ADC1_MAX + ADC_PROTECT_THRESH) >= 4095) - #warning ADC1 Protection NOT possible! Adjust the ADC thresholds. - #undef ADC_PROTECT_ENA -#endif - -#if defined(ADC_PROTECT_ENA) && ((ADC2_MIN - ADC_PROTECT_THRESH) <= 0 || (ADC2_MAX + ADC_PROTECT_THRESH) >= 4095) - #warning ADC2 Protection NOT possible! Adjust the ADC thresholds. - #undef ADC_PROTECT_ENA -#endif - #if (defined(CONTROL_PPM_LEFT) || defined(CONTROL_PPM_RIGHT)) && !defined(PPM_NUM_CHANNELS) #error Total number of PPM channels needs to be set #endif diff --git a/Inc/util.h b/Inc/util.h index 8f34635..54e0fe6 100644 --- a/Inc/util.h +++ b/Inc/util.h @@ -66,11 +66,11 @@ void shortBeep(uint8_t freq); void shortBeepMany(uint8_t cnt, int8_t dir); void longBeep(uint8_t freq); 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 checkInputType(int16_t min, int16_t mid, int16_t max); void adcCalibLim(void); -int checkInputType(int16_t min, int16_t mid, int16_t max); void updateCurSpdLim(void); void saveConfig(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); void standstillHold(void); void electricBrake(uint16_t speedBlend, uint8_t reverseDir); void cruiseControl(uint8_t button); @@ -79,9 +79,9 @@ void cruiseControl(uint8_t button); void poweroff(void); void poweroffPressCheck(void); -// Read Command Function -void readCommand(void); +// Read Functions void readInput(void); +void readCommand(void); void usart2_rx_check(void); void usart3_rx_check(void); #if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3) diff --git a/Src/control.c b/Src/control.c index a6c53be..3a82eb1 100644 --- a/Src/control.c +++ b/Src/control.c @@ -34,14 +34,13 @@ void PPM_ISR_Callback(void) { if (rc_delay > 3000) { if (ppm_valid && ppm_count == PPM_NUM_CHANNELS) { ppm_timeout = 0; - timeoutCnt = 0; // added this + timeoutCnt = 0; memcpy(ppm_captured_value, ppm_captured_value_buffer, sizeof(ppm_captured_value)); } ppm_valid = true; ppm_count = 0; } else if (ppm_count < PPM_NUM_CHANNELS && IN_RANGE(rc_delay, 900, 2100)){ - //timeoutCnt = 0; ppm_captured_value_buffer[ppm_count++] = CLAMP(rc_delay, 1000, 2000) - 1000; } else { ppm_valid = false; diff --git a/Src/main.c b/Src/main.c index abd59d9..90afd7e 100644 --- a/Src/main.c +++ b/Src/main.c @@ -210,6 +210,7 @@ int main(void) { 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 shortBeep(4); HAL_Delay(100); + steerFixdt = speedFixdt = 0; // reset filters enable = 1; // enable motors consoleLog("-- Motors enabled --\r\n"); } diff --git a/Src/util.c b/Src/util.c index 0deb562..926f83e 100644 --- a/Src/util.c +++ b/Src/util.c @@ -129,29 +129,29 @@ static int16_t INPUT_MIN; // [-] Input target minimum limitation #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - static uint8_t cur_spd_valid = 0; - static uint8_t input_cal_valid = 0; + static uint8_t cur_spd_valid = 0; + static uint8_t inp_cal_valid = 0; + static uint16_t INPUT1_TYP_CAL = INPUT1_TYPE; static uint16_t INPUT1_MIN_CAL = INPUT1_MIN; static uint16_t INPUT1_MID_CAL = INPUT1_MID; static uint16_t INPUT1_MAX_CAL = INPUT1_MAX; - static uint16_t INPUT1_TYPE_CAL = INPUT1_TYPE; + static uint16_t INPUT2_TYP_CAL = INPUT2_TYPE; static uint16_t INPUT2_MIN_CAL = INPUT2_MIN; static uint16_t INPUT2_MID_CAL = INPUT2_MID; static uint16_t INPUT2_MAX_CAL = INPUT2_MAX; - static uint16_t INPUT2_TYPE_CAL = INPUT2_TYPE; #endif #if defined(CONTROL_ADC) -static int16_t timeoutCntADC = 0; // Timeout counter for ADC Protection +static int16_t timeoutCntADC = 0; // Timeout counter for ADC Protection #endif #if defined(DEBUG_SERIAL_USART2) || defined(CONTROL_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART2) -static uint8_t rx_buffer_L[SERIAL_BUFFER_SIZE]; // USART Rx DMA circular buffer +static uint8_t rx_buffer_L[SERIAL_BUFFER_SIZE]; // USART Rx DMA circular buffer static uint32_t rx_buffer_L_len = ARRAY_LEN(rx_buffer_L); #endif #if defined(CONTROL_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART2) -static uint16_t timeoutCntSerial_L = 0; // Timeout counter for Rx Serial command -static uint8_t timeoutFlagSerial_L = 0; // Timeout Flag for Rx Serial command: 0 = OK, 1 = Problem detected (line disconnected or wrong Rx data) +static uint16_t timeoutCntSerial_L = 0; // Timeout counter for Rx Serial command +static uint8_t timeoutFlagSerial_L = 0; // Timeout Flag for Rx Serial command: 0 = OK, 1 = Problem detected (line disconnected or wrong Rx data) #endif #if defined(SIDEBOARD_SERIAL_USART2) SerialSideboard Sideboard_L; @@ -160,12 +160,12 @@ static uint32_t Sideboard_L_len = sizeof(Sideboard_L); #endif #if defined(DEBUG_SERIAL_USART3) || defined(CONTROL_SERIAL_USART3) || defined(SIDEBOARD_SERIAL_USART3) -static uint8_t rx_buffer_R[SERIAL_BUFFER_SIZE]; // USART Rx DMA circular buffer +static uint8_t rx_buffer_R[SERIAL_BUFFER_SIZE]; // USART Rx DMA circular buffer static uint32_t rx_buffer_R_len = ARRAY_LEN(rx_buffer_R); #endif #if defined(CONTROL_SERIAL_USART3) || defined(SIDEBOARD_SERIAL_USART3) -static uint16_t timeoutCntSerial_R = 0; // Timeout counter for Rx Serial command -static uint8_t timeoutFlagSerial_R = 0; // Timeout Flag for Rx Serial command: 0 = OK, 1 = Problem detected (line disconnected or wrong Rx data) +static uint16_t timeoutCntSerial_R = 0; // Timeout counter for Rx Serial command +static uint8_t timeoutFlagSerial_R = 0; // Timeout Flag for Rx Serial command: 0 = OK, 1 = Problem detected (line disconnected or wrong Rx data) #endif #if defined(SIDEBOARD_SERIAL_USART3) SerialSideboard Sideboard_R; @@ -273,32 +273,30 @@ void Input_Init(void) { #endif #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - uint16_t writeCheck, i_max, n_max; - HAL_FLASH_Unlock(); - EE_Init(); /* EEPROM Init */ + HAL_FLASH_Unlock(); + EE_Init(); /* EEPROM Init */ EE_ReadVariable(VirtAddVarTab[0], &writeCheck); if (writeCheck == FLASH_WRITE_KEY) { - EE_ReadVariable(VirtAddVarTab[1] , &INPUT1_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[2] , &INPUT1_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[3] , &INPUT1_MID_CAL); - EE_ReadVariable(VirtAddVarTab[4] , &INPUT2_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[5] , &INPUT2_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[6] , &INPUT2_MID_CAL); - EE_ReadVariable(VirtAddVarTab[7] , &i_max); - EE_ReadVariable(VirtAddVarTab[8] , &n_max); - EE_ReadVariable(VirtAddVarTab[9] , &INPUT1_TYPE_CAL); - EE_ReadVariable(VirtAddVarTab[10], &INPUT2_TYPE_CAL); + EE_ReadVariable(VirtAddVarTab[1] , &INPUT1_TYP_CAL); + EE_ReadVariable(VirtAddVarTab[2] , &INPUT1_MIN_CAL); + EE_ReadVariable(VirtAddVarTab[3] , &INPUT1_MAX_CAL); + EE_ReadVariable(VirtAddVarTab[4] , &INPUT1_MID_CAL); + EE_ReadVariable(VirtAddVarTab[5] , &INPUT2_TYP_CAL); + EE_ReadVariable(VirtAddVarTab[6] , &INPUT2_MIN_CAL); + EE_ReadVariable(VirtAddVarTab[7] , &INPUT2_MAX_CAL); + EE_ReadVariable(VirtAddVarTab[8] , &INPUT2_MID_CAL); + EE_ReadVariable(VirtAddVarTab[9] , &i_max); + EE_ReadVariable(VirtAddVarTab[10], &n_max); rtP_Left.i_max = i_max; rtP_Left.n_max = n_max; rtP_Right.i_max = i_max; rtP_Right.n_max = n_max; } HAL_FLASH_Lock(); - #endif - #ifdef VARIANT_TRANSPOTTER + #ifdef VARIANT_TRANSPOTTER enable = 1; HAL_FLASH_Unlock(); @@ -358,12 +356,9 @@ void Input_Init(void) { #if defined(DEBUG_SERIAL_USART2) || defined(CONTROL_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART2) || \ defined(DEBUG_SERIAL_USART3) || defined(CONTROL_SERIAL_USART3) || defined(SIDEBOARD_SERIAL_USART3) void UART_DisableRxErrors(UART_HandleTypeDef *huart) -{ - /* Disable PE (Parity Error) interrupts */ - CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); - - /* Disable EIE (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); +{ + CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); /* Disable PE (Parity Error) interrupts */ + CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); /* Disable EIE (Frame error, noise error, overrun error) interrupts */ } #endif @@ -421,6 +416,70 @@ void calcAvgSpeed(void) { speedAvgAbs = abs(speedAvg); } + /* + * Add Dead-band to a signal + * This function realizes a dead-band around 0 and scales the input between [out_min, 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) { + switch (type){ + case 0: // Input is ignored + return 0; + case 1: // Input is a normal pot + return CLAMP(MAP(u, in_min, in_max, 0, out_max), 0, out_max); + case 2: // Input is a mid resting pot + if( u > in_mid - deadBand && u < in_mid + deadBand ) { + return 0; + } else if(u > in_mid) { + return CLAMP(MAP(u, in_mid + deadBand, in_max, 0, out_max), 0, out_max); + } else { + return CLAMP(MAP(u, in_mid - deadBand, in_min, 0, out_min), out_min, 0); + } + default: + return 0; + } +} + + /* + * Check Input Type + * This function identifies the input type: 0: Disabled, 1: Normal Pot, 2: Middle Resting Pot + */ +int checkInputType(int16_t min, int16_t mid, int16_t max){ + + int type = 0; + #ifdef CONTROL_ADC + int16_t threshold = 400; // Threshold to define if values are too close + #else + int16_t threshold = 200; + #endif + + HAL_Delay(10); + if ((min / threshold) == (max / threshold)) { + consoleLog("Input is ignored"); // MIN and MAX are close, disable input + type = 0; + } else { + if ((min / threshold) == (mid / threshold)){ + consoleLog("Input is a normal pot"); // MIN and MID are close, it's a normal pot + type = 1; + } else { + consoleLog("Input is a mid-resting pot"); // it's a mid resting pot + type = 2; + } + HAL_Delay(10); + #ifdef CONTROL_ADC + if ((min - ADC_PROTECT_THRESH) > 0 && (max + ADC_PROTECT_THRESH) < 4095) { + consoleLog(" and protected"); + shortBeep(2); // Indicate protection by a beep + } + #endif + } + + HAL_Delay(10); + consoleLog("\n"); + HAL_Delay(10); + + return type; +} + /* * Auto-calibration of the ADC Limits * This function finds the Minimum, Maximum, and Middle for the ADC input @@ -435,23 +494,20 @@ void adcCalibLim(void) { return; } - #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) consoleLog("Input calibration started...\n"); - readInput(); - // Inititalization: MIN = a high values, MAX = a low value, - int32_t input1_fixdt = input1 << 16; - int32_t input2_fixdt = input2 << 16; + readInput(); + // Inititalization: MIN = a high value, MAX = a low value + int32_t input1_fixdt = input1 << 16; + int32_t input2_fixdt = input2 << 16; + int16_t INPUT1_MIN_temp = MAX_int16_T; + int16_t INPUT1_MID_temp = 0; + int16_t INPUT1_MAX_temp = MIN_int16_T; + int16_t INPUT2_MIN_temp = MAX_int16_T; + int16_t INPUT2_MID_temp = 0; + int16_t INPUT2_MAX_temp = MIN_int16_T; uint16_t input_cal_timeout = 0; - int16_t INPUT1_MIN_temp = INPUT1_MAX; - int16_t INPUT1_MID_temp = 0; - int16_t INPUT1_MAX_temp = INPUT1_MIN; - int16_t INPUT2_MIN_temp = INPUT2_MAX; - int16_t INPUT2_MID_temp = 0; - int16_t INPUT2_MAX_temp = INPUT2_MIN; - - input_cal_valid = 1; // Extract MIN, MAX and MID from ADC while the power button is not pressed while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && input_cal_timeout++ < 4000) { // 20 sec timeout @@ -459,90 +515,48 @@ void adcCalibLim(void) { filtLowPass32(input1, FILTER, &input1_fixdt); filtLowPass32(input2, FILTER, &input2_fixdt); - INPUT1_MID_temp = (int16_t)(input1_fixdt >> 16);// CLAMP(input1_fixdt >> 16, INPUT1_MIN, INPUT1_MAX); // convert fixed-point to integer + INPUT1_MID_temp = (int16_t)(input1_fixdt >> 16);// CLAMP(input1_fixdt >> 16, INPUT1_MIN, INPUT1_MAX); // convert fixed-point to integer INPUT2_MID_temp = (int16_t)(input2_fixdt >> 16);// CLAMP(input2_fixdt >> 16, INPUT2_MIN, INPUT2_MAX); INPUT1_MIN_temp = MIN(INPUT1_MIN_temp, INPUT1_MID_temp); - INPUT1_MAX_temp = MAX(INPUT1_MAX_temp, INPUT1_MID_temp); + INPUT1_MAX_temp = MAX(INPUT1_MAX_temp, INPUT1_MID_temp); INPUT2_MIN_temp = MIN(INPUT2_MIN_temp, INPUT2_MID_temp); INPUT2_MAX_temp = MAX(INPUT2_MAX_temp, INPUT2_MID_temp); HAL_Delay(5); } - - uint16_t input_margin = 0; + #ifdef CONTROL_ADC - input_margin = 100; + int16_t input_margin = 100; + #else + int16_t input_margin = 0; #endif INPUT1_MIN_CAL = INPUT1_MIN_temp + input_margin; INPUT1_MID_CAL = INPUT1_MID_temp; INPUT1_MAX_CAL = INPUT1_MAX_temp - input_margin; - INPUT1_TYPE_CAL = checkInputType(INPUT1_MIN_CAL,INPUT1_MID_CAL,INPUT1_MAX_CAL); + INPUT1_TYP_CAL = checkInputType(INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL); INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; INPUT2_MID_CAL = INPUT2_MID_temp; INPUT2_MAX_CAL = INPUT2_MAX_temp - input_margin; - INPUT2_TYPE_CAL = checkInputType(INPUT2_MIN_CAL,INPUT2_MID_CAL,INPUT2_MAX_CAL); + INPUT2_TYP_CAL = checkInputType(INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL); + inp_cal_valid = 1; // Mark calibration to be saved in Flash at shutdown consoleLog("Saved limits\n"); HAL_Delay(10); - setScopeChannel(0, (int16_t)INPUT1_MIN_CAL); - setScopeChannel(1, (uint16_t)INPUT1_MID_CAL); - setScopeChannel(2, (int16_t)INPUT1_MAX_CAL); - setScopeChannel(3, (int16_t)0); - setScopeChannel(4, (int16_t)INPUT2_MIN_CAL); - setScopeChannel(5, (uint16_t)INPUT2_MID_CAL); - setScopeChannel(6, (int16_t)INPUT2_MAX_CAL); - setScopeChannel(7, (int16_t)0); + setScopeChannel(0, (int16_t)INPUT1_TYP_CAL); + setScopeChannel(1, (int16_t)INPUT1_MIN_CAL); + setScopeChannel(2, (int16_t)INPUT1_MID_CAL); + setScopeChannel(3, (int16_t)INPUT1_MAX_CAL); + setScopeChannel(4, (int16_t)INPUT2_TYP_CAL); + setScopeChannel(5, (int16_t)INPUT2_MIN_CAL); + setScopeChannel(6, (int16_t)INPUT2_MID_CAL); + setScopeChannel(7, (int16_t)INPUT2_MAX_CAL); consoleScope(); HAL_Delay(20); consoleLog("OK\n"); #endif } - -int checkInputType(int16_t min, int16_t mid, int16_t max){ - - HAL_Delay(10); - - int type = 0; - - // Threshold to define if values are too close - int16_t threshold = 200; - #ifdef CONTROL_ADC - threshold = 400; - #endif - - if ( (min/threshold) == (max/threshold) ){ - // MIN MID and MAX are close, disable input - consoleLog("Input is ignored"); - type = 0; - } else { - if ( (min/threshold) == (mid/threshold) ){ - // MIN and MID are close, it's a normal pot - consoleLog("Input is a normal pot"); - type = 1; - }else { - // it's a mid resting pot - consoleLog("Input is a mid-resting pot"); - type = 2; - } - - HAL_Delay(10); - #ifdef CONTROL_ADC - if ( (min - ADC_PROTECT_THRESH) > 0 && (max + ADC_PROTECT_THRESH) < 4095){ - consoleLog(" and protected"); - } - #endif - } - - HAL_Delay(10); - consoleLog("\n"); - HAL_Delay(10); - - return type; -} - - /* * Update Maximum Motor Current Limit (via ADC1) and Maximum Speed Limit (via ADC2) * Procedure: @@ -556,14 +570,14 @@ void updateCurSpdLim(void) { } #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - consoleLog("Torque and Speed limits update started...\n"); - int32_t input1_fixdt = input1 << 16; - int32_t input2_fixdt = input2 << 16; - uint16_t cur_spd_timeout = 0; + int32_t input1_fixdt = input1 << 16; + int32_t input2_fixdt = input2 << 16; uint16_t cur_factor; // fixdt(0,16,16) uint16_t spd_factor; // fixdt(0,16,16) + uint16_t cur_spd_timeout = 0; + cur_spd_valid = 0; // Wait for the power button press while (!HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && cur_spd_timeout++ < 2000) { // 10 sec timeout @@ -573,31 +587,31 @@ void updateCurSpdLim(void) { HAL_Delay(5); } // Calculate scaling factors - cur_factor = CLAMP((input1_fixdt - ((int16_t)INPUT1_MIN_CAL << 16)) / ((int16_t)INPUT1_MAX_CAL - (int16_t)INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A - spd_factor = CLAMP((input2_fixdt - ((int16_t)INPUT2_MIN_CAL << 16)) / ((int16_t)INPUT2_MAX_CAL - (int16_t)INPUT2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm + cur_factor = CLAMP((input1_fixdt - ((int16_t)INPUT1_MIN_CAL << 16)) / ((int16_t)INPUT1_MAX_CAL - (int16_t)INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A + spd_factor = CLAMP((input2_fixdt - ((int16_t)INPUT2_MIN_CAL << 16)) / ((int16_t)INPUT2_MAX_CAL - (int16_t)INPUT2_MIN_CAL), 3276, 65535); // ADC2, MIN_spd(5%) = 50 rpm - if (INPUT1_TYPE_CAL != 0){ + if (INPUT1_TYP_CAL != 0){ // Update current limit - rtP_Right.i_max = rtP_Left.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) - cur_spd_valid = 1; + rtP_Left.i_max = rtP_Right.i_max = (int16_t)((I_MOT_MAX * A2BIT_CONV * cur_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) + cur_spd_valid = 1; // Mark update to be saved in Flash at shutdown } - if (INPUT2_TYPE_CAL != 0){ + if (INPUT2_TYP_CAL != 0){ // Update speed limit - rtP_Right.n_max = rtP_Left.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) - cur_spd_valid = 1; + rtP_Left.n_max = rtP_Right.n_max = (int16_t)((N_MOT_MAX * spd_factor) >> 12); // fixdt(0,16,16) to fixdt(1,16,4) + cur_spd_valid += 2; // Mark update to be saved in Flash at shutdown } consoleLog("Saved limits\n"); HAL_Delay(10); - setScopeChannel(0, (int16_t)input1_fixdt); - setScopeChannel(1, (uint16_t)cur_factor); - setScopeChannel(2, (int16_t)rtP_Right.i_max); - setScopeChannel(3, (int16_t)0); - setScopeChannel(4, (int16_t)input2_fixdt); - setScopeChannel(5, (uint16_t)spd_factor); - setScopeChannel(6, (int16_t)rtP_Right.n_max); - setScopeChannel(7, (int16_t)0); + setScopeChannel(0, (int16_t)cur_spd_valid); // 0 = No limit changed, 1 = Current limit changed, 2 = Speed limit changed, 3 = Both limits changed + setScopeChannel(1, (int16_t)input1_fixdt); + setScopeChannel(2, (int16_t)cur_factor); + setScopeChannel(3, (int16_t)rtP_Left.i_max); + setScopeChannel(4, (int16_t)0); + setScopeChannel(5, (int16_t)input2_fixdt); + setScopeChannel(6, (int16_t)spd_factor); + setScopeChannel(7, (int16_t)rtP_Left.n_max); consoleScope(); HAL_Delay(20); consoleLog("OK\n"); @@ -618,47 +632,24 @@ void saveConfig() { } #endif #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - if (input_cal_valid || cur_spd_valid) { + if (inp_cal_valid || cur_spd_valid) { HAL_FLASH_Unlock(); EE_WriteVariable(VirtAddVarTab[0] , FLASH_WRITE_KEY); - EE_WriteVariable(VirtAddVarTab[1] , INPUT1_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[2] , INPUT1_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[3] , INPUT1_MID_CAL); - EE_WriteVariable(VirtAddVarTab[4] , INPUT2_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[5] , INPUT2_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[6] , INPUT2_MID_CAL); - EE_WriteVariable(VirtAddVarTab[7] , rtP_Left.i_max); - EE_WriteVariable(VirtAddVarTab[8] , rtP_Left.n_max); - EE_WriteVariable(VirtAddVarTab[9] , INPUT1_TYPE_CAL); - EE_WriteVariable(VirtAddVarTab[10], INPUT2_TYPE_CAL); + EE_WriteVariable(VirtAddVarTab[1] , INPUT1_TYP_CAL); + EE_WriteVariable(VirtAddVarTab[2] , INPUT1_MIN_CAL); + EE_WriteVariable(VirtAddVarTab[3] , INPUT1_MAX_CAL); + EE_WriteVariable(VirtAddVarTab[4] , INPUT1_MID_CAL); + EE_WriteVariable(VirtAddVarTab[5] , INPUT2_TYP_CAL); + EE_WriteVariable(VirtAddVarTab[6] , INPUT2_MIN_CAL); + EE_WriteVariable(VirtAddVarTab[7] , INPUT2_MAX_CAL); + EE_WriteVariable(VirtAddVarTab[8] , INPUT2_MID_CAL); + EE_WriteVariable(VirtAddVarTab[9] , rtP_Left.i_max); + EE_WriteVariable(VirtAddVarTab[10], rtP_Left.n_max); HAL_FLASH_Lock(); } #endif } - /* - * Add Dead-band to a signal - * This function realizes a dead-band around 0 and scales the input between [out_min, 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) { - switch (type){ - case 0: // Input is ignored - return 0; - case 1: // Input is a normal pot - return CLAMP(MAP( u , in_min, in_max, 0, out_max ), 0, out_max); - case 2: // Input is a mid resting pot - if( u > in_mid - deadBand && u < in_mid + deadBand ) { - return 0; - } else if(u > in_mid) { - return CLAMP( MAP(u, in_mid + deadBand, in_max, 0, out_max), 0 , out_max); - } else { - return CLAMP( MAP(u, in_mid - deadBand, in_min, 0, out_min), out_min, 0); - } - default: - return 0; - } -} - /* * Standstill Hold Function * This function uses Cruise Control to provide an anti-roll functionality at standstill. @@ -824,13 +815,18 @@ void poweroffPressCheck(void) { #endif } + +/* =========================== Read Functions =========================== */ + + /* + * Function to read the raw Input values from various input devices + */ void readInput(void) { - #if defined(CONTROL_NUNCHUK) || defined(SUPPORT_NUNCHUK) + #if defined(CONTROL_NUNCHUK) || defined(SUPPORT_NUNCHUK) if (nunchuk_connected != 0) { Nunchuk_Read(); - input1 = (nunchuk_data[0] - 127) * 8; // X axis 0-255 - input2 = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 - + input1 = (nunchuk_data[0] - 127) * 8; // X axis 0-255 + input2 = (nunchuk_data[1] - 128) * 8; // Y axis 0-255 #ifdef SUPPORT_BUTTONS button1 = (uint8_t)nunchuk_data[5] & 1; button2 = (uint8_t)(nunchuk_data[5] >> 1) & 1; @@ -842,8 +838,8 @@ void readInput(void) { input1 = (ppm_captured_value[0] - 500) * 2; input2 = (ppm_captured_value[1] - 500) * 2; #ifdef SUPPORT_BUTTONS - button1 = ppm_captured_value[5] > 500; - button2 = 0; + button1 = ppm_captured_value[5] > 500; + button2 = 0; #endif #endif @@ -854,8 +850,9 @@ void readInput(void) { #ifdef CONTROL_ADC // ADC values range: 0-4095, see ADC-calibration in config.h - input1 = adc_buffer.l_tx2; - input2 = adc_buffer.l_rx2; + input1 = adc_buffer.l_tx2; + input2 = adc_buffer.l_rx2; + timeoutCnt = 0; #endif #if defined(CONTROL_SERIAL_USART2) || defined(CONTROL_SERIAL_USART3) @@ -866,38 +863,37 @@ void readInput(void) { } input1 = (ibus_captured_value[0] - 500) * 2; input2 = (ibus_captured_value[1] - 500) * 2; - #else - if (IN_RANGE(command.steer, INPUT_MIN, INPUT_MAX) && IN_RANGE(command.speed, INPUT_MIN, INPUT_MAX)) { + #else input1 = command.steer; input2 = command.speed; - } #endif timeoutCnt = 0; - #endif - + #endif } -/* =========================== Read Command Function =========================== */ - + /* + * Function to calculate the command to the motors. This function also manages: + * - timeout detection + * - MIN/MAX limitations and deadband + */ void readCommand(void) { readInput(); #ifdef CONTROL_ADC // If input1 or Input2 is either below MIN - Threshold or above MAX + Threshold, ADC protection timeout - if ((IN_RANGE(input1,(int16_t)INPUT1_MIN_CAL - ADC_PROTECT_THRESH,(int16_t)INPUT1_MAX_CAL + ADC_PROTECT_THRESH)) && - (IN_RANGE(input2,(int16_t)INPUT2_MIN_CAL - ADC_PROTECT_THRESH,(int16_t)INPUT2_MAX_CAL + ADC_PROTECT_THRESH))){ - if (timeoutFlagADC) { // Check for previous timeout flag - if (timeoutCntADC-- <= 0) // Timeout de-qualification - timeoutFlagADC = 0; // Timeout flag cleared + if (IN_RANGE(input1, (int16_t)INPUT1_MIN_CAL - ADC_PROTECT_THRESH, (int16_t)INPUT1_MAX_CAL + ADC_PROTECT_THRESH) && + IN_RANGE(input2, (int16_t)INPUT2_MIN_CAL - ADC_PROTECT_THRESH, (int16_t)INPUT2_MAX_CAL + ADC_PROTECT_THRESH)){ + if (timeoutFlagADC) { // Check for previous timeout flag + if (timeoutCntADC-- <= 0) // Timeout de-qualification + timeoutFlagADC = 0; // Timeout flag cleared } else { - timeoutCntADC = 0; // Reset the timeout counter + timeoutCntADC = 0; // Reset the timeout counter } } else { - if (timeoutCntADC++ >= ADC_PROTECT_TIMEOUT) { // Timeout qualification - timeoutFlagADC = 1; // Timeout detected - timeoutCntADC = ADC_PROTECT_TIMEOUT; // Limit timout counter value + if (timeoutCntADC++ >= ADC_PROTECT_TIMEOUT) { // Timeout qualification + timeoutFlagADC = 1; // Timeout detected + timeoutCntADC = ADC_PROTECT_TIMEOUT; // Limit timout counter value } - } - timeoutCnt = 0; + } #endif #if defined(CONTROL_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART2) @@ -919,23 +915,13 @@ void readCommand(void) { #endif #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) - cmd1 = addDeadBand(input1, INPUT1_TYPE_CAL, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); + cmd1 = addDeadBand(input1, INPUT1_TYP_CAL, INPUT1_DEADBAND, INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL, INPUT_MIN, INPUT_MAX); #if !defined(VARIANT_SKATEBOARD) - cmd2 = addDeadBand(input2, INPUT2_TYPE_CAL, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(input2, INPUT2_TYP_CAL, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT_MIN, INPUT_MAX); #else - cmd2 = addDeadBand(input2, INPUT2_TYPE_CAL, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_OUT_MIN, INPUT_MAX); + cmd2 = addDeadBand(input2, INPUT2_TYP_CAL, INPUT2_DEADBAND, INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL, INPUT2_BRAKE, INPUT_MAX); #endif #endif - - - #ifdef VARIANT_HOVERCAR - brakePressed = (uint8_t)(cmd1 > 50); - #endif - - #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) - button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); - button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); - #endif #ifdef VARIANT_TRANSPOTTER #ifdef GAMETRAK_CONNECTION_NORMAL @@ -948,6 +934,10 @@ void readCommand(void) { #endif #endif + #ifdef VARIANT_HOVERCAR + brakePressed = (uint8_t)(cmd1 > 50); + #endif + if (timeoutFlagADC || timeoutFlagSerial || timeoutCnt > TIMEOUT) { // In case of timeout bring the system to a Safe State ctrlModReq = OPEN_MODE; // Request OPEN_MODE. This will bring the motor power to 0 in a controlled way cmd1 = 0; @@ -956,6 +946,11 @@ void readCommand(void) { ctrlModReq = ctrlModReqRaw; // Follow the Mode request } + #if defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT) + button1 = !HAL_GPIO_ReadPin(BUTTON1_PORT, BUTTON1_PIN); + button2 = !HAL_GPIO_ReadPin(BUTTON2_PORT, BUTTON2_PIN); + #endif + #if defined(CRUISE_CONTROL_SUPPORT) && (defined(SUPPORT_BUTTONS) || defined(SUPPORT_BUTTONS_LEFT) || defined(SUPPORT_BUTTONS_RIGHT)) cruiseControl(button1); // Cruise control activation/deactivation #endif @@ -975,17 +970,17 @@ void usart2_rx_check(void) #endif #if defined(DEBUG_SERIAL_USART2) - if (pos != old_pos) { // Check change in received data + if (pos != old_pos) { // Check change in received data if (pos > old_pos) { // "Linear" buffer mode: check if current position is over previous one usart_process_debug(&rx_buffer_L[old_pos], pos - old_pos); // Process data } else { // "Overflow" buffer mode - usart_process_debug(&rx_buffer_L[old_pos], rx_buffer_L_len - old_pos); // First Process data from the end of buffer - if (pos > 0) { // Check and continue with beginning of buffer - usart_process_debug(&rx_buffer_L[0], pos); // Process remaining data + usart_process_debug(&rx_buffer_L[old_pos], rx_buffer_L_len - old_pos); // First Process data from the end of buffer + if (pos > 0) { // Check and continue with beginning of buffer + usart_process_debug(&rx_buffer_L[0], pos); // Process remaining data } } } - #endif // DEBUG_SERIAL_USART2 + #endif // DEBUG_SERIAL_USART2 #ifdef CONTROL_SERIAL_USART2 uint8_t *ptr; @@ -997,7 +992,7 @@ void usart2_rx_check(void) } else if ((rx_buffer_L_len - old_pos + pos) == command_len) { // "Overflow" buffer mode: check if data length equals expected length memcpy(ptr, &rx_buffer_L[old_pos], rx_buffer_L_len - old_pos); // First copy data from the end of buffer if (pos > 0) { // Check and continue with beginning of buffer - ptr += rx_buffer_L_len - old_pos; // Move to correct position in command_raw + ptr += rx_buffer_L_len - old_pos; // Move to correct position in command_raw memcpy(ptr, &rx_buffer_L[0], pos); // Copy remaining data } usart_process_command(&command_raw, &command, 2); // Process data @@ -1005,7 +1000,7 @@ void usart2_rx_check(void) } #endif // CONTROL_SERIAL_USART2 - #ifdef SIDEBOARD_SERIAL_USART2 + #ifdef SIDEBOARD_SERIAL_USART2 uint8_t *ptr; if (pos != old_pos) { // Check change in received data ptr = (uint8_t *)&Sideboard_L_raw; // Initialize the pointer with Sideboard_raw address @@ -1015,7 +1010,7 @@ void usart2_rx_check(void) } else if ((rx_buffer_L_len - old_pos + pos) == Sideboard_L_len) { // "Overflow" buffer mode: check if data length equals expected length memcpy(ptr, &rx_buffer_L[old_pos], rx_buffer_L_len - old_pos); // First copy data from the end of buffer if (pos > 0) { // Check and continue with beginning of buffer - ptr += rx_buffer_L_len - old_pos; // Move to correct position in Sideboard_raw + ptr += rx_buffer_L_len - old_pos; // Move to correct position in Sideboard_raw memcpy(ptr, &rx_buffer_L[0], pos); // Copy remaining data } usart_process_sideboard(&Sideboard_L_raw, &Sideboard_L, 2); // Process data @@ -1045,17 +1040,17 @@ void usart3_rx_check(void) #endif #if defined(DEBUG_SERIAL_USART3) - if (pos != old_pos) { // Check change in received data + if (pos != old_pos) { // Check change in received data if (pos > old_pos) { // "Linear" buffer mode: check if current position is over previous one usart_process_debug(&rx_buffer_R[old_pos], pos - old_pos); // Process data } else { // "Overflow" buffer mode - usart_process_debug(&rx_buffer_R[old_pos], rx_buffer_R_len - old_pos); // First Process data from the end of buffer - if (pos > 0) { // Check and continue with beginning of buffer - usart_process_debug(&rx_buffer_R[0], pos); // Process remaining data + usart_process_debug(&rx_buffer_R[old_pos], rx_buffer_R_len - old_pos); // First Process data from the end of buffer + if (pos > 0) { // Check and continue with beginning of buffer + usart_process_debug(&rx_buffer_R[0], pos); // Process remaining data } } } - #endif // DEBUG_SERIAL_USART3 + #endif // DEBUG_SERIAL_USART3 #ifdef CONTROL_SERIAL_USART3 uint8_t *ptr; @@ -1067,7 +1062,7 @@ void usart3_rx_check(void) } else if ((rx_buffer_R_len - old_pos + pos) == command_len) { // "Overflow" buffer mode: check if data length equals expected length memcpy(ptr, &rx_buffer_R[old_pos], rx_buffer_R_len - old_pos); // First copy data from the end of buffer if (pos > 0) { // Check and continue with beginning of buffer - ptr += rx_buffer_R_len - old_pos; // Move to correct position in command_raw + ptr += rx_buffer_R_len - old_pos; // Move to correct position in command_raw memcpy(ptr, &rx_buffer_R[0], pos); // Copy remaining data } usart_process_command(&command_raw, &command, 3); // Process data @@ -1075,7 +1070,7 @@ void usart3_rx_check(void) } #endif // CONTROL_SERIAL_USART3 - #ifdef SIDEBOARD_SERIAL_USART3 + #ifdef SIDEBOARD_SERIAL_USART3 uint8_t *ptr; if (pos != old_pos) { // Check change in received data ptr = (uint8_t *)&Sideboard_R_raw; // Initialize the pointer with Sideboard_raw address @@ -1085,7 +1080,7 @@ void usart3_rx_check(void) } else if ((rx_buffer_R_len - old_pos + pos) == Sideboard_R_len) { // "Overflow" buffer mode: check if data length equals expected length memcpy(ptr, &rx_buffer_R[old_pos], rx_buffer_R_len - old_pos); // First copy data from the end of buffer if (pos > 0) { // Check and continue with beginning of buffer - ptr += rx_buffer_R_len - old_pos; // Move to correct position in Sideboard_raw + ptr += rx_buffer_R_len - old_pos; // Move to correct position in Sideboard_raw memcpy(ptr, &rx_buffer_R[0], pos); // Copy remaining data } usart_process_sideboard(&Sideboard_R_raw, &Sideboard_R, 3); // Process data @@ -1098,7 +1093,7 @@ void usart3_rx_check(void) if (old_pos == rx_buffer_R_len) { // Check and manually update if we reached end of buffer old_pos = 0; } - #endif + #endif } /* @@ -1107,11 +1102,11 @@ void usart3_rx_check(void) #if defined(DEBUG_SERIAL_USART2) || defined(DEBUG_SERIAL_USART3) void usart_process_debug(uint8_t *userCommand, uint32_t len) { - for (; len > 0; len--, userCommand++) { - if (*userCommand != '\n' && *userCommand != '\r') { // Do not accept 'new line' and 'carriage return' commands - //consoleLog("-- Command received --\r\n"); - // handle_input(*userCommand); // -> Create this function to handle the user commands - } + for (; len > 0; len--, userCommand++) { + if (*userCommand != '\n' && *userCommand != '\r') { // Do not accept 'new line' and 'carriage return' commands + consoleLog("-- Command received --\r\n"); + // handle_input(*userCommand); // -> Create this function to handle the user commands + } } } #endif // SERIAL_DEBUG @@ -1146,10 +1141,10 @@ void usart_process_command(SerialCommand *command_in, SerialCommand *command_out } #else uint16_t checksum; - if (command_in->start == SERIAL_START_FRAME) { - checksum = (uint16_t)(command_in->start ^ command_in->steer ^ command_in->speed); - if (command_in->checksum == checksum) { - *command_out = *command_in; + if (command_in->start == SERIAL_START_FRAME) { + checksum = (uint16_t)(command_in->start ^ command_in->steer ^ command_in->speed); + if (command_in->checksum == checksum) { + *command_out = *command_in; if (usart_idx == 2) { // Sideboard USART2 #ifdef CONTROL_SERIAL_USART2 timeoutCntSerial_L = 0; // Reset timeout counter @@ -1173,12 +1168,12 @@ void usart_process_command(SerialCommand *command_in, SerialCommand *command_out */ #if defined(SIDEBOARD_SERIAL_USART2) || defined(SIDEBOARD_SERIAL_USART3) void usart_process_sideboard(SerialSideboard *Sideboard_in, SerialSideboard *Sideboard_out, uint8_t usart_idx) -{ +{ uint16_t checksum; - 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); - if (Sideboard_in->checksum == checksum) { - *Sideboard_out = *Sideboard_in; + 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); + if (Sideboard_in->checksum == checksum) { + *Sideboard_out = *Sideboard_in; if (usart_idx == 2) { // Sideboard USART2 #ifdef SIDEBOARD_SERIAL_USART2 timeoutCntSerial_L = 0; // Reset timeout counter @@ -1191,7 +1186,7 @@ void usart_process_sideboard(SerialSideboard *Sideboard_in, SerialSideboard *Sid #endif } } - } + } } #endif From 8dc6eb68eb34f188c4fd07f6bf882bfc5b8e5d01 Mon Sep 17 00:00:00 2001 From: EmanuelFeru Date: Wed, 18 Nov 2020 19:44:23 +0100 Subject: [PATCH 24/26] Updated Flash write order --- Src/util.c | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Src/util.c b/Src/util.c index 926f83e..8c9177f 100644 --- a/Src/util.c +++ b/Src/util.c @@ -280,12 +280,12 @@ void Input_Init(void) { if (writeCheck == FLASH_WRITE_KEY) { EE_ReadVariable(VirtAddVarTab[1] , &INPUT1_TYP_CAL); EE_ReadVariable(VirtAddVarTab[2] , &INPUT1_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[3] , &INPUT1_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[4] , &INPUT1_MID_CAL); + EE_ReadVariable(VirtAddVarTab[3] , &INPUT1_MID_CAL); + EE_ReadVariable(VirtAddVarTab[4] , &INPUT1_MAX_CAL); EE_ReadVariable(VirtAddVarTab[5] , &INPUT2_TYP_CAL); EE_ReadVariable(VirtAddVarTab[6] , &INPUT2_MIN_CAL); - EE_ReadVariable(VirtAddVarTab[7] , &INPUT2_MAX_CAL); - EE_ReadVariable(VirtAddVarTab[8] , &INPUT2_MID_CAL); + EE_ReadVariable(VirtAddVarTab[7] , &INPUT2_MID_CAL); + EE_ReadVariable(VirtAddVarTab[8] , &INPUT2_MAX_CAL); EE_ReadVariable(VirtAddVarTab[9] , &i_max); EE_ReadVariable(VirtAddVarTab[10], &n_max); rtP_Left.i_max = i_max; @@ -637,14 +637,14 @@ void saveConfig() { EE_WriteVariable(VirtAddVarTab[0] , FLASH_WRITE_KEY); EE_WriteVariable(VirtAddVarTab[1] , INPUT1_TYP_CAL); EE_WriteVariable(VirtAddVarTab[2] , INPUT1_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[3] , INPUT1_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[4] , INPUT1_MID_CAL); + EE_WriteVariable(VirtAddVarTab[3] , INPUT1_MID_CAL); + EE_WriteVariable(VirtAddVarTab[4] , INPUT1_MAX_CAL); EE_WriteVariable(VirtAddVarTab[5] , INPUT2_TYP_CAL); EE_WriteVariable(VirtAddVarTab[6] , INPUT2_MIN_CAL); - EE_WriteVariable(VirtAddVarTab[7] , INPUT2_MAX_CAL); - EE_WriteVariable(VirtAddVarTab[8] , INPUT2_MID_CAL); + EE_WriteVariable(VirtAddVarTab[7] , INPUT2_MID_CAL); + EE_WriteVariable(VirtAddVarTab[8] , INPUT2_MAX_CAL); EE_WriteVariable(VirtAddVarTab[9] , rtP_Left.i_max); - EE_WriteVariable(VirtAddVarTab[10], rtP_Left.n_max); + EE_WriteVariable(VirtAddVarTab[10], rtP_Left.n_max); HAL_FLASH_Lock(); } #endif From 44cf0c8f1ff86b72ed6adddd79403fa6b2878b75 Mon Sep 17 00:00:00 2001 From: EmanuelFeru Date: Thu, 19 Nov 2020 17:49:14 +0100 Subject: [PATCH 25/26] update Auto-calibration - implemented forced potentiometer type - extended the INPUTx_TYPE to 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect --- Inc/config.h | 43 ++++++++++++++++------------- Src/util.c | 78 +++++++++++++++++++++++++++------------------------- 2 files changed, 64 insertions(+), 57 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index c752b0f..1f9dc87 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -253,15 +253,15 @@ #define CONTROL_ADC // use ADC as input. disable CONTROL_SERIAL_USART2, FEEDBACK_SERIAL_USART2, DEBUG_SERIAL_USART2! #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken #define ADC_PROTECT_THRESH 200 // ADC Protection threshold below/above the MIN/MAX ADC values - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN 0 // min ADC1-value while poti at minimum-position (0 - 4095) - #define INPUT1_MID 2048 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) + #define INPUT1_MID 0 // mid ADC1-value while poti at minimum-position (ADC1_MIN - ADC1_MAX) #define INPUT1_MAX 4095 // max ADC1-value while poti at maximum-position (0 - 4095) #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN 0 // min ADC2-value while poti at minimum-position (0 - 4095) - #define INPUT2_MID 2048 // mid ADC2-value while poti at minimum-position (ADC2_MIN - ADC2_MAX) + #define INPUT2_MID 0 // mid ADC2-value while poti at minimum-position (ADC2_MIN - ADC2_MAX) #define INPUT2_MAX 4095 // max ADC2-value while poti at maximum-position (0 - 4095) #define INPUT2_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) // #define SUPPORT_BUTTONS_LEFT // use left sensor board cable for button inputs. Disable DEBUG_SERIAL_USART2! @@ -281,13 +281,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 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) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #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 INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) @@ -309,13 +309,13 @@ */ #define CONTROL_NUNCHUK // use nunchuk as input. disable FEEDBACK_SERIAL_USART3, DEBUG_SERIAL_USART3! // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 2 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN -1024 // (-1024 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1024 // (0 - 1024) #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 2 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN -1024 // (-1024 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1024 // (0 - 1024) @@ -346,13 +346,13 @@ #endif #define PPM_NUM_CHANNELS 6 // total number of PPM channels to receive, even if they are not used. // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN -1000 // (-1000 - 0) - #define INPUT1_MID 0 + #define INPUT1_MID 3 #define INPUT1_MAX 1000 // (0 - 1000) #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 2 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) @@ -378,13 +378,13 @@ #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) @@ -419,13 +419,13 @@ // #define DEBUG_SERIAL_USART3 // right sensor cable debug // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #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 INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 3 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN -1000 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 1000 // (0 - 1000) @@ -443,13 +443,13 @@ #define ADC_PROTECT_TIMEOUT 100 // ADC Protection: number of wrong / missing input commands before safety state is taken #define ADC_PROTECT_THRESH 200 // ADC Protection threshold below/above the MIN/MAX ADC values - #define INPUT1_TYPE 1 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 1 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN 1000 // min ADC1-value while poti at minimum-position (0 - 4095) #define INPUT1_MID 0 #define INPUT1_MAX 2500 // max ADC1-value while poti at maximum-position (0 - 4095) #define INPUT1_DEADBAND 0 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 1 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 1 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN 500 // min ADC2-value while poti at minimum-position (0 - 4095) #define INPUT2_MID 0 #define INPUT2_MAX 2200 // max ADC2-value while poti at maximum-position (0 - 4095) @@ -527,13 +527,13 @@ #define DEBUG_SERIAL_USART3 // right sensor cable debug #endif // Min / Max values of each channel (use DEBUG to determine these values) - #define INPUT1_TYPE 0 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT1_TYPE 0 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT1_MIN -1000 // (-1000 - 0) #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) - #define INPUT2_TYPE 2 // 0:Disabled 1:Normal POT 2:Middle Resting Pot + #define INPUT2_TYPE 2 // 0:Disabled, 1:Normal Pot, 2:Middle Resting Pot, 3:Auto-detect #define INPUT2_MIN -800 // (-1000 - 0) #define INPUT2_MID 0 #define INPUT2_MAX 700 // (0 - 1000) @@ -587,6 +587,11 @@ #ifndef STEER_COEFFICIENT #define STEER_COEFFICIENT DEFAULT_STEER_COEFFICIENT #endif +#ifdef CONTROL_ADC + #define INPUT_MARGIN 100 // Input margin applied on the raw ADC min and max to make sure the motor MIN and MAX values are reached even in the presence of noise +#else + #define INPUT_MARGIN 0 +#endif // ########################### END OF APPLY DEFAULT SETTING ############################ diff --git a/Src/util.c b/Src/util.c index 8c9177f..bd795f1 100644 --- a/Src/util.c +++ b/Src/util.c @@ -292,6 +292,9 @@ void Input_Init(void) { rtP_Left.n_max = n_max; rtP_Right.i_max = i_max; rtP_Right.n_max = n_max; + } else { // Else If Input type is 3 (auto), identify the input type based on the values from config.h + if (INPUT1_TYPE == 3) { INPUT1_TYP_CAL = checkInputType(INPUT1_MIN, INPUT1_MID, INPUT1_MAX); } + if (INPUT2_TYPE == 3) { INPUT2_TYP_CAL = checkInputType(INPUT2_MIN, INPUT2_MID, INPUT2_MAX); } } HAL_FLASH_Lock(); #endif @@ -453,22 +456,22 @@ int checkInputType(int16_t min, int16_t mid, int16_t max){ #endif HAL_Delay(10); - if ((min / threshold) == (max / threshold)) { - consoleLog("Input is ignored"); // MIN and MAX are close, disable input + if ((min / threshold) == (max / threshold) || (mid / threshold) == (max / threshold)) { type = 0; + consoleLog("Input is ignored"); // (MIN and MAX) OR (MID and MAX) are close, disable input } else { if ((min / threshold) == (mid / threshold)){ - consoleLog("Input is a normal pot"); // MIN and MID are close, it's a normal pot type = 1; - } else { + consoleLog("Input is a normal pot"); // MIN and MID are close, it's a normal pot + } else { + type = 2; consoleLog("Input is a mid-resting pot"); // it's a mid resting pot - type = 2; } HAL_Delay(10); #ifdef CONTROL_ADC - if ((min - ADC_PROTECT_THRESH) > 0 && (max + ADC_PROTECT_THRESH) < 4095) { + if ((min + INPUT_MARGIN - ADC_PROTECT_THRESH) > 0 && (max - INPUT_MARGIN + ADC_PROTECT_THRESH) < 4095) { consoleLog(" and protected"); - shortBeep(2); // Indicate protection by a beep + longBeep(2); // Indicate protection by a beep } #endif } @@ -494,11 +497,11 @@ void adcCalibLim(void) { return; } - #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) + #if !defined(VARIANT_HOVERBOARD) && !defined(VARIANT_TRANSPOTTER) consoleLog("Input calibration started...\n"); readInput(); - // Inititalization: MIN = a high value, MAX = a low value + // Inititalization: MIN = a high value, MAX = a low value int32_t input1_fixdt = input1 << 16; int32_t input2_fixdt = input2 << 16; int16_t INPUT1_MIN_temp = MAX_int16_T; @@ -524,37 +527,39 @@ void adcCalibLim(void) { HAL_Delay(5); } - #ifdef CONTROL_ADC - int16_t input_margin = 100; - #else - int16_t input_margin = 0; - #endif - - INPUT1_MIN_CAL = INPUT1_MIN_temp + input_margin; - INPUT1_MID_CAL = INPUT1_MID_temp; - INPUT1_MAX_CAL = INPUT1_MAX_temp - input_margin; - INPUT1_TYP_CAL = checkInputType(INPUT1_MIN_CAL, INPUT1_MID_CAL, INPUT1_MAX_CAL); + INPUT1_TYP_CAL = checkInputType(INPUT1_MIN_temp, INPUT1_MID_temp, INPUT1_MAX_temp); + if (INPUT1_TYP_CAL == INPUT1_TYPE || INPUT1_TYPE == 3) { // Accept calibration only if the type is correct OR type was set to 3 (auto) + INPUT1_MIN_CAL = INPUT1_MIN_temp + INPUT_MARGIN; + INPUT1_MID_CAL = INPUT1_MID_temp; + INPUT1_MAX_CAL = INPUT1_MAX_temp - INPUT_MARGIN; + consoleLog("Input1 OK\n"); HAL_Delay(10); + } else { + INPUT1_TYP_CAL = 0; // Disable input + consoleLog("Input1 Fail\n"); HAL_Delay(10); + } - INPUT2_MIN_CAL = INPUT2_MIN_temp + input_margin; - INPUT2_MID_CAL = INPUT2_MID_temp; - INPUT2_MAX_CAL = INPUT2_MAX_temp - input_margin; - INPUT2_TYP_CAL = checkInputType(INPUT2_MIN_CAL, INPUT2_MID_CAL, INPUT2_MAX_CAL); - - inp_cal_valid = 1; // Mark calibration to be saved in Flash at shutdown - consoleLog("Saved limits\n"); - HAL_Delay(10); + INPUT2_TYP_CAL = checkInputType(INPUT2_MIN_temp, INPUT2_MID_temp, INPUT2_MAX_temp); + if (INPUT2_TYP_CAL == INPUT2_TYPE || INPUT2_TYPE == 3) { // Accept calibration only if the type is correct OR type was set to 3 (auto) + INPUT2_MIN_CAL = INPUT2_MIN_temp + INPUT_MARGIN; + INPUT2_MID_CAL = INPUT2_MID_temp; + INPUT2_MAX_CAL = INPUT2_MAX_temp - INPUT_MARGIN; + consoleLog("Input2 OK\n"); HAL_Delay(10); + } else { + INPUT2_TYP_CAL = 0; // Disable input + consoleLog("Input2 Fail\n"); HAL_Delay(10); + } + + inp_cal_valid = 1; // Mark calibration to be saved in Flash at shutdown + consoleLog("Limits: "); HAL_Delay(10); setScopeChannel(0, (int16_t)INPUT1_TYP_CAL); setScopeChannel(1, (int16_t)INPUT1_MIN_CAL); setScopeChannel(2, (int16_t)INPUT1_MID_CAL); setScopeChannel(3, (int16_t)INPUT1_MAX_CAL); - setScopeChannel(4, (int16_t)INPUT2_TYP_CAL); + setScopeChannel(4, (int16_t)INPUT2_TYP_CAL); setScopeChannel(5, (int16_t)INPUT2_MIN_CAL); setScopeChannel(6, (int16_t)INPUT2_MID_CAL); - setScopeChannel(7, (int16_t)INPUT2_MAX_CAL); + setScopeChannel(7, (int16_t)INPUT2_MAX_CAL); consoleScope(); - HAL_Delay(20); - consoleLog("OK\n"); - #endif } /* @@ -584,7 +589,7 @@ void updateCurSpdLim(void) { readInput(); filtLowPass32(input1, FILTER, &input1_fixdt); filtLowPass32(input2, FILTER, &input2_fixdt); - HAL_Delay(5); + HAL_Delay(5); } // Calculate scaling factors cur_factor = CLAMP((input1_fixdt - ((int16_t)INPUT1_MIN_CAL << 16)) / ((int16_t)INPUT1_MAX_CAL - (int16_t)INPUT1_MIN_CAL), 6553, 65535); // ADC1, MIN_cur(10%) = 1.5 A @@ -602,8 +607,7 @@ void updateCurSpdLim(void) { cur_spd_valid += 2; // Mark update to be saved in Flash at shutdown } - consoleLog("Saved limits\n"); - HAL_Delay(10); + consoleLog("Limits: "); HAL_Delay(10); setScopeChannel(0, (int16_t)cur_spd_valid); // 0 = No limit changed, 1 = Current limit changed, 2 = Speed limit changed, 3 = Both limits changed setScopeChannel(1, (int16_t)input1_fixdt); setScopeChannel(2, (int16_t)cur_factor); @@ -611,10 +615,8 @@ void updateCurSpdLim(void) { setScopeChannel(4, (int16_t)0); setScopeChannel(5, (int16_t)input2_fixdt); setScopeChannel(6, (int16_t)spd_factor); - setScopeChannel(7, (int16_t)rtP_Left.n_max); + setScopeChannel(7, (int16_t)rtP_Left.n_max); consoleScope(); - HAL_Delay(20); - consoleLog("OK\n"); #endif } From 925008467bb55d97291ef23cac069cc8e520fe59 Mon Sep 17 00:00:00 2001 From: EmanuelFeru Date: Thu, 19 Nov 2020 21:51:15 +0100 Subject: [PATCH 26/26] Minor updates RC - moved all the RC inputs (PPM, PWM, iBUS) to Right cable - updated timing to enter torque and speed update from 300ms to 1000ms --- Inc/config.h | 34 ++++++++++++++++++++-------------- Src/util.c | 8 ++++---- 2 files changed, 24 insertions(+), 18 deletions(-) diff --git a/Inc/config.h b/Inc/config.h index 1f9dc87..8cb1715 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -334,11 +334,11 @@ // ################################# VARIANT_PPM SETTINGS ############################## #ifdef VARIANT_PPM /* ###### CONTROL VIA RC REMOTE ###### - * left sensor board cable. Channel 1: steering, Channel 2: speed. + * Right sensor board cable. Channel 1: steering, Channel 2: speed. * https://gist.github.com/peterpoetzi/1b63a4a844162196613871767189bd05 */ - #define CONTROL_PPM_LEFT // use PPM-Sum as input on the LEFT cable . disable CONTROL_SERIAL_USART2! - // #define CONTROL_PPM_RIGHT // use PPM-Sum as input on the RIGHT cable. disable CONTROL_SERIAL_USART3! + // #define CONTROL_PPM_LEFT // use PPM-Sum as input on the LEFT cable . disable CONTROL_SERIAL_USART2! + #define CONTROL_PPM_RIGHT // use PPM-Sum as input on the RIGHT cable. disable CONTROL_SERIAL_USART3! #ifdef CONTROL_PPM_RIGHT #define DEBUG_SERIAL_USART2 // left sensor cable debug #else @@ -348,7 +348,7 @@ // 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_MIN -1000 // (-1000 - 0) - #define INPUT1_MID 3 + #define INPUT1_MID 0 #define INPUT1_MAX 1000 // (0 - 1000) #define INPUT1_DEADBAND 100 // How much of the center position is considered 'center' (100 = values -100 to 100 are considered 0) @@ -367,11 +367,11 @@ // ################################# VARIANT_PWM SETTINGS ############################## #ifdef VARIANT_PWM /* ###### CONTROL VIA RC REMOTE ###### - * left sensor board cable. Connect PA2 to channel 1 and PA3 to channel 2 on receiver. + * Right sensor board cable. Connect PA2 to channel 1 and PA3 to channel 2 on receiver. * Channel 1: steering, Channel 2: speed. */ - #define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! - // #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! + // #define CONTROL_PWM_LEFT // use RC PWM as input on the LEFT cable. disable DEBUG_SERIAL_USART2! + #define CONTROL_PWM_RIGHT // use RC PWM as input on the RIGHT cable. disable DEBUG_SERIAL_USART3! #ifdef CONTROL_PWM_RIGHT #define DEBUG_SERIAL_USART2 // left sensor cable debug #else @@ -405,18 +405,22 @@ // ################################# VARIANT_IBUS SETTINGS ############################## #ifdef VARIANT_IBUS /* CONTROL VIA RC REMOTE WITH FLYSKY IBUS PROTOCOL -* Connected to Left sensor board cable. Channel 1: steering, Channel 2: speed. +* Connected to Right sensor board cable. Channel 1: steering, Channel 2: speed. */ #define CONTROL_IBUS // use IBUS as input #define IBUS_NUM_CHANNELS 14 // total number of IBUS channels to receive, even if they are not used. #define IBUS_LENGTH 0x20 #define IBUS_COMMAND 0x40 - #undef USART2_BAUD - #define USART2_BAUD 115200 - #define CONTROL_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! - #define FEEDBACK_SERIAL_USART2 // left sensor board cable, disable if ADC or PPM is used! - // #define DEBUG_SERIAL_USART3 // right sensor cable debug + #undef USART3_BAUD + #define USART3_BAUD 115200 + #define CONTROL_SERIAL_USART3 // left 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! + #ifdef CONTROL_SERIAL_USART3 + #define DEBUG_SERIAL_USART2 // left sensor cable debug + #else + #define DEBUG_SERIAL_USART3 // right sensor cable debug + #endif // 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 @@ -567,7 +571,9 @@ #define USART2_WORDLENGTH UART_WORDLENGTH_8B // UART_WORDLENGTH_8B or UART_WORDLENGTH_9B #endif #if defined(FEEDBACK_SERIAL_USART3) || defined(CONTROL_SERIAL_USART3) || defined(DEBUG_SERIAL_USART3) || defined(SIDEBOARD_SERIAL_USART3) - #define USART3_BAUD 38400 // UART3 baud rate (short wired cable) + #ifndef USART3_BAUD + #define USART3_BAUD 38400 // UART3 baud rate (short wired cable) + #endif #define USART3_WORDLENGTH UART_WORDLENGTH_8B // UART_WORDLENGTH_8B or UART_WORDLENGTH_9B #endif // ########################### UART SETIINGS ############################ diff --git a/Src/util.c b/Src/util.c index bd795f1..26d8e35 100644 --- a/Src/util.c +++ b/Src/util.c @@ -456,7 +456,7 @@ int checkInputType(int16_t min, int16_t mid, int16_t max){ #endif HAL_Delay(10); - if ((min / threshold) == (max / threshold) || (mid / threshold) == (max / threshold)) { + if ((min / threshold) == (max / threshold) || (mid / threshold) == (max / threshold) || min > max || mid > max) { type = 0; consoleLog("Input is ignored"); // (MIN and MAX) OR (MID and MAX) are close, disable input } else { @@ -769,12 +769,12 @@ void poweroffPressCheck(void) { uint16_t cnt_press = 0; while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); - if (cnt_press++ == 5 * 100) { shortBeep(5); } + if (cnt_press++ == 5 * 100) { shortBeep(5); } } if (cnt_press >= 5 * 100) { // Check if press is more than 5 sec - HAL_Delay(300); + HAL_Delay(1000); 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); updateCurSpdLim(); shortBeep(5);