Compare commits
3 Commits
master
...
test_firmw
Author | SHA1 | Date | |
---|---|---|---|
2ab9fe6a5c | |||
985cfdd802 | |||
23612d410d |
2
config.h
2
config.h
@ -1,6 +1,6 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define PWM_FREQ 16000 // PWM frequency in Hz
|
#define PWM_FREQ 10000 // PWM frequency in Hz
|
||||||
#define DEAD_TIME 48 // PWM deadtime
|
#define DEAD_TIME 48 // PWM deadtime
|
||||||
#ifdef VARIANT_TRANSPOTTER
|
#ifdef VARIANT_TRANSPOTTER
|
||||||
#define DELAY_IN_MAIN_LOOP 2
|
#define DELAY_IN_MAIN_LOOP 2
|
||||||
|
17
defines.h
17
defines.h
@ -39,22 +39,25 @@
|
|||||||
#define RIGHT_HALL_W_PORT GPIOC
|
#define RIGHT_HALL_W_PORT GPIOC
|
||||||
|
|
||||||
#define LEFT_TIM TIM8
|
#define LEFT_TIM TIM8
|
||||||
|
|
||||||
#define LEFT_TIM_U CCR1
|
#define LEFT_TIM_U CCR1
|
||||||
#define LEFT_TIM_UH_PIN GPIO_PIN_6
|
#define LEFT_TIM_UH_PIN GPIO_PIN_6
|
||||||
#define LEFT_TIM_UH_PORT GPIOC
|
#define LEFT_TIM_UH_PORT GPIOC
|
||||||
#define LEFT_TIM_UL_PIN GPIO_PIN_7
|
#define LEFT_TIM_UL_PIN GPIO_PIN_7
|
||||||
#define LEFT_TIM_UL_PORT GPIOA
|
#define LEFT_TIM_UL_PORT GPIOA
|
||||||
|
|
||||||
#define LEFT_TIM_V CCR2
|
#define LEFT_TIM_V CCR2
|
||||||
#define LEFT_TIM_VH_PIN GPIO_PIN_7
|
#define LEFT_TIM_WH_PIN GPIO_PIN_7
|
||||||
#define LEFT_TIM_VH_PORT GPIOC
|
|
||||||
#define LEFT_TIM_VL_PIN GPIO_PIN_0
|
|
||||||
#define LEFT_TIM_VL_PORT GPIOB
|
|
||||||
#define LEFT_TIM_W CCR3
|
|
||||||
#define LEFT_TIM_WH_PIN GPIO_PIN_8
|
|
||||||
#define LEFT_TIM_WH_PORT GPIOC
|
#define LEFT_TIM_WH_PORT GPIOC
|
||||||
#define LEFT_TIM_WL_PIN GPIO_PIN_1
|
#define LEFT_TIM_WL_PIN GPIO_PIN_0
|
||||||
#define LEFT_TIM_WL_PORT GPIOB
|
#define LEFT_TIM_WL_PORT GPIOB
|
||||||
|
|
||||||
|
#define LEFT_TIM_W CCR3
|
||||||
|
#define LEFT_TIM_VH_PIN GPIO_PIN_8
|
||||||
|
#define LEFT_TIM_VH_PORT GPIOC
|
||||||
|
#define LEFT_TIM_VL_PIN GPIO_PIN_1
|
||||||
|
#define LEFT_TIM_VL_PORT GPIOB
|
||||||
|
|
||||||
#define RIGHT_TIM TIM1
|
#define RIGHT_TIM TIM1
|
||||||
#define RIGHT_TIM_U CCR1
|
#define RIGHT_TIM_U CCR1
|
||||||
#define RIGHT_TIM_UH_PIN GPIO_PIN_8
|
#define RIGHT_TIM_UH_PIN GPIO_PIN_8
|
||||||
|
72
main.cpp
72
main.cpp
@ -165,7 +165,7 @@ int main()
|
|||||||
HAL_ADC_Start(&hadc2);
|
HAL_ADC_Start(&hadc2);
|
||||||
|
|
||||||
left.rtP = rtP_Left;
|
left.rtP = rtP_Left;
|
||||||
left.rtP.b_selPhaABCurrMeas = 1; // Left motor measured current phases = {iA, iB} -> do NOT change
|
left.rtP.b_selPhaABCurrMeas = 0; // Left motor measured current phases = {iA, iB} -> do NOT change
|
||||||
left.rtP.z_ctrlTypSel = uint8_t(left.state.ctrlTyp);
|
left.rtP.z_ctrlTypSel = uint8_t(left.state.ctrlTyp);
|
||||||
left.rtP.b_diagEna = DIAG_ENA;
|
left.rtP.b_diagEna = DIAG_ENA;
|
||||||
left.rtP.i_max = (left.state.iMotMax * A2BIT_CONV) << 4; // fixdt(1,16,4)
|
left.rtP.i_max = (left.state.iMotMax * A2BIT_CONV) << 4; // fixdt(1,16,4)
|
||||||
@ -212,34 +212,54 @@ int main()
|
|||||||
//#define UART_DMA_CHANNEL DMA1_Channel2
|
//#define UART_DMA_CHANNEL DMA1_Channel2
|
||||||
//UART3_Init();
|
//UART3_Init();
|
||||||
|
|
||||||
HAL_UART_Receive_DMA(&huart2, (uint8_t *)&command, sizeof(command));
|
int pwm = 0;
|
||||||
|
int8_t dir = 1;
|
||||||
|
|
||||||
|
const int pwmMax = 400;
|
||||||
|
|
||||||
for (;;) {
|
for (;;) {
|
||||||
HAL_Delay(DELAY_IN_MAIN_LOOP); //delay in ms
|
HAL_Delay(DELAY_IN_MAIN_LOOP ); //delay in ms
|
||||||
|
|
||||||
parseCommand();
|
|
||||||
|
|
||||||
timeout = 0;
|
timeout = 0;
|
||||||
|
|
||||||
|
left.state.enable = true;
|
||||||
|
left.state.ctrlMod = ControlMode::Voltage;//FieldOrientedControl
|
||||||
|
left.state.ctrlTyp = ControlType::FieldOrientedControl;//Sinusoidal;
|
||||||
|
left.state.pwm = pwm;
|
||||||
|
left.state.iMotMax = 10;
|
||||||
|
|
||||||
|
right.state.enable = true;
|
||||||
|
right.state.ctrlMod = ControlMode::Voltage;
|
||||||
|
right.state.ctrlTyp = ControlType::FieldOrientedControl;
|
||||||
|
right.state.pwm = pwm;
|
||||||
|
right.state.iMotMax = 10;
|
||||||
|
|
||||||
|
pwm += dir;
|
||||||
|
if (pwm > pwmMax) {
|
||||||
|
pwm = pwmMax;
|
||||||
|
dir = -1;
|
||||||
|
} else if (pwm < -pwmMax) {
|
||||||
|
pwm = -pwmMax;
|
||||||
|
dir = 1;
|
||||||
|
}
|
||||||
|
|
||||||
// ####### CALC BOARD TEMPERATURE #######
|
// ####### CALC BOARD TEMPERATURE #######
|
||||||
filtLowPass32(adc_buffer.temp, TEMP_FILT_COEF, &board_temp_adcFixdt);
|
filtLowPass32(adc_buffer.temp, TEMP_FILT_COEF, &board_temp_adcFixdt);
|
||||||
board_temp_adcFilt = (int16_t)(board_temp_adcFixdt >> 20); // convert fixed-point to integer
|
board_temp_adcFilt = (int16_t)(board_temp_adcFixdt >> 20); // convert fixed-point to integer
|
||||||
board_temp_deg_c = (TEMP_CAL_HIGH_DEG_C - TEMP_CAL_LOW_DEG_C) * (board_temp_adcFilt - TEMP_CAL_LOW_ADC) / (TEMP_CAL_HIGH_ADC - TEMP_CAL_LOW_ADC) + TEMP_CAL_LOW_DEG_C;
|
board_temp_deg_c = (TEMP_CAL_HIGH_DEG_C - TEMP_CAL_LOW_DEG_C) * (board_temp_adcFilt - TEMP_CAL_LOW_ADC) / (TEMP_CAL_HIGH_ADC - TEMP_CAL_LOW_ADC) + TEMP_CAL_LOW_DEG_C;
|
||||||
|
|
||||||
sendFeedback();
|
// if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN))
|
||||||
|
// {
|
||||||
if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN))
|
// left.state.enable = right.state.enable = 0; // disable motors
|
||||||
{
|
//
|
||||||
left.state.enable = right.state.enable = 0; // disable motors
|
// while (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {} // wait until button is released
|
||||||
|
//
|
||||||
while (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {} // wait until button is released
|
// if(__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST)) { // do not power off after software reset (from a programmer/debugger)
|
||||||
|
// __HAL_RCC_CLEAR_RESET_FLAGS(); // clear reset flags
|
||||||
if(__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST)) { // do not power off after software reset (from a programmer/debugger)
|
// } else {
|
||||||
__HAL_RCC_CLEAR_RESET_FLAGS(); // clear reset flags
|
// poweroff(); // release power-latch
|
||||||
} else {
|
// }
|
||||||
poweroff(); // release power-latch
|
// }
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
main_loop_counter++;
|
main_loop_counter++;
|
||||||
timeout++;
|
timeout++;
|
||||||
@ -268,13 +288,13 @@ void updateMotors()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Get Left motor currents
|
// Get Left motor currents
|
||||||
int16_t curL_phaA = (int16_t)(offsetrl1 - adc_buffer.rl1);
|
int16_t curL_phaA = (int16_t)(offsetrl1 - adc_buffer.rl1)*2;
|
||||||
int16_t curL_phaB = (int16_t)(offsetrl2 - adc_buffer.rl2);
|
int16_t curL_phaB = (int16_t)(offsetrl2 - adc_buffer.rl2)*2;
|
||||||
int16_t curL_DC = (int16_t)(offsetdcl - adc_buffer.dcl);
|
int16_t curL_DC = (int16_t)(offsetdcl - adc_buffer.dcl);
|
||||||
|
|
||||||
// Get Right motor currents
|
// Get Right motor currents
|
||||||
int16_t curR_phaB = (int16_t)(offsetrr1 - adc_buffer.rr1);
|
int16_t curR_phaB = (int16_t)(offsetrr1 - adc_buffer.rr1)*2;
|
||||||
int16_t curR_phaC = (int16_t)(offsetrr2 - adc_buffer.rr2);
|
int16_t curR_phaC = (int16_t)(offsetrr2 - adc_buffer.rr2)*2;
|
||||||
int16_t curR_DC = (int16_t)(offsetdcr - adc_buffer.dcr);
|
int16_t curR_DC = (int16_t)(offsetdcr - adc_buffer.dcr);
|
||||||
|
|
||||||
const int8_t chopL = std::abs(curL_DC) > (left.state.iDcMax * A2BIT_CONV);
|
const int8_t chopL = std::abs(curL_DC) > (left.state.iDcMax * A2BIT_CONV);
|
||||||
@ -323,7 +343,7 @@ void updateMotors()
|
|||||||
constexpr int32_t pwm_margin = 100; /* This margin allows to always have a window in the PWM signal for proper Phase currents measurement */
|
constexpr int32_t pwm_margin = 100; /* This margin allows to always have a window in the PWM signal for proper Phase currents measurement */
|
||||||
|
|
||||||
/* Make sure to stop BOTH motors in case of an error */
|
/* Make sure to stop BOTH motors in case of an error */
|
||||||
const bool enableLFin = left.state.enable && left.rtY.z_errCode == 0 && right.rtY.z_errCode == 0;
|
const bool enableLFin = left.state.enable && left.rtY.z_errCode == 0 && left.rtY.z_errCode == 0;
|
||||||
const bool enableRFin = right.state.enable && left.rtY.z_errCode == 0 && right.rtY.z_errCode == 0;
|
const bool enableRFin = right.state.enable && left.rtY.z_errCode == 0 && right.rtY.z_errCode == 0;
|
||||||
|
|
||||||
// ========================= LEFT MOTOR ============================
|
// ========================= LEFT MOTOR ============================
|
||||||
@ -772,7 +792,7 @@ void MX_TIM_Init() {
|
|||||||
sConfigOC.OCMode = TIM_OCMODE_PWM1;
|
sConfigOC.OCMode = TIM_OCMODE_PWM1;
|
||||||
sConfigOC.Pulse = 0;
|
sConfigOC.Pulse = 0;
|
||||||
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
|
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
|
||||||
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW;
|
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
|
||||||
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
|
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
|
||||||
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
|
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
|
||||||
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET;
|
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET;
|
||||||
@ -813,7 +833,7 @@ void MX_TIM_Init() {
|
|||||||
sConfigOC.OCMode = TIM_OCMODE_PWM1;
|
sConfigOC.OCMode = TIM_OCMODE_PWM1;
|
||||||
sConfigOC.Pulse = 0;
|
sConfigOC.Pulse = 0;
|
||||||
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
|
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
|
||||||
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW;
|
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
|
||||||
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
|
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
|
||||||
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
|
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
|
||||||
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET;
|
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET;
|
||||||
|
Reference in New Issue
Block a user