mirror of https://github.com/rusefi/bldc.git
First implementation of DC motor support
This commit is contained in:
parent
2ccb52514e
commit
bc0415c1bb
|
@ -169,6 +169,7 @@ void commands_process_packet(unsigned char *data, unsigned char len) {
|
||||||
ind = 0;
|
ind = 0;
|
||||||
mcconf.pwm_mode = data[ind++];
|
mcconf.pwm_mode = data[ind++];
|
||||||
mcconf.comm_mode = data[ind++];
|
mcconf.comm_mode = data[ind++];
|
||||||
|
mcconf.motor_type = data[ind++];
|
||||||
|
|
||||||
mcconf.l_current_max = (float)buffer_get_int32(data, &ind) / 1000.0;
|
mcconf.l_current_max = (float)buffer_get_int32(data, &ind) / 1000.0;
|
||||||
mcconf.l_current_min = (float)buffer_get_int32(data, &ind) / 1000.0;
|
mcconf.l_current_min = (float)buffer_get_int32(data, &ind) / 1000.0;
|
||||||
|
@ -229,6 +230,7 @@ void commands_process_packet(unsigned char *data, unsigned char len) {
|
||||||
|
|
||||||
send_buffer[ind++] = mcconf.pwm_mode;
|
send_buffer[ind++] = mcconf.pwm_mode;
|
||||||
send_buffer[ind++] = mcconf.comm_mode;
|
send_buffer[ind++] = mcconf.comm_mode;
|
||||||
|
send_buffer[ind++] = mcconf.motor_type;
|
||||||
|
|
||||||
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_current_max * 1000.0), &ind);
|
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_current_max * 1000.0), &ind);
|
||||||
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_current_min * 1000.0), &ind);
|
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_current_min * 1000.0), &ind);
|
||||||
|
|
|
@ -36,6 +36,9 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Parameters that can be overridden
|
// Parameters that can be overridden
|
||||||
|
#ifndef MC_DEFAULT_MOTOR_TYPE
|
||||||
|
#define MC_DEFAULT_MOTOR_TYPE MOTOR_TYPE_BLDC
|
||||||
|
#endif
|
||||||
#ifndef MCPWM_PWM_MODE
|
#ifndef MCPWM_PWM_MODE
|
||||||
#define MCPWM_PWM_MODE PWM_MODE_SYNCHRONOUS // Default PWM mode
|
#define MCPWM_PWM_MODE PWM_MODE_SYNCHRONOUS // Default PWM mode
|
||||||
#endif
|
#endif
|
||||||
|
@ -244,6 +247,7 @@ void conf_general_read_mc_configuration(mc_configuration *conf) {
|
||||||
if (!is_ok) {
|
if (!is_ok) {
|
||||||
conf->pwm_mode = MCPWM_PWM_MODE;
|
conf->pwm_mode = MCPWM_PWM_MODE;
|
||||||
conf->comm_mode = MCPWM_COMM_MODE;
|
conf->comm_mode = MCPWM_COMM_MODE;
|
||||||
|
conf->motor_type = MC_DEFAULT_MOTOR_TYPE;
|
||||||
|
|
||||||
conf->l_current_max = MCPWM_CURRENT_MAX;
|
conf->l_current_max = MCPWM_CURRENT_MAX;
|
||||||
conf->l_current_min = MCPWM_CURRENT_MIN;
|
conf->l_current_min = MCPWM_CURRENT_MIN;
|
||||||
|
|
|
@ -48,6 +48,11 @@ typedef enum {
|
||||||
COMM_MODE_DELAY
|
COMM_MODE_DELAY
|
||||||
} mc_comm_mode;
|
} mc_comm_mode;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
MOTOR_TYPE_BLDC = 0,
|
||||||
|
MOTOR_TYPE_DC,
|
||||||
|
} mc_motor_type;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
FAULT_CODE_NONE = 0,
|
FAULT_CODE_NONE = 0,
|
||||||
FAULT_CODE_OVER_VOLTAGE,
|
FAULT_CODE_OVER_VOLTAGE,
|
||||||
|
@ -80,6 +85,7 @@ typedef struct {
|
||||||
// Switching and drive
|
// Switching and drive
|
||||||
mc_pwm_mode pwm_mode;
|
mc_pwm_mode pwm_mode;
|
||||||
mc_comm_mode comm_mode;
|
mc_comm_mode comm_mode;
|
||||||
|
mc_motor_type motor_type;
|
||||||
// Limits
|
// Limits
|
||||||
float l_current_max;
|
float l_current_max;
|
||||||
float l_current_min;
|
float l_current_min;
|
||||||
|
|
120
mcpwm.c
120
mcpwm.c
|
@ -643,6 +643,13 @@ void mcpwm_set_brake_current(float current) {
|
||||||
if (state != MC_STATE_RUNNING && state != MC_STATE_FULL_BRAKE) {
|
if (state != MC_STATE_RUNNING && state != MC_STATE_FULL_BRAKE) {
|
||||||
// In case the motor is already spinning, set the state to running
|
// In case the motor is already spinning, set the state to running
|
||||||
// so that it can be ramped down before the full brake is applied.
|
// so that it can be ramped down before the full brake is applied.
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
if (fabsf(dutycycle_now) > 0.1) {
|
||||||
|
state = MC_STATE_RUNNING;
|
||||||
|
} else {
|
||||||
|
full_brake_ll();
|
||||||
|
}
|
||||||
|
} else {
|
||||||
if (fabsf(rpm_now) > conf.l_max_erpm_fbrake) {
|
if (fabsf(rpm_now) > conf.l_max_erpm_fbrake) {
|
||||||
state = MC_STATE_RUNNING;
|
state = MC_STATE_RUNNING;
|
||||||
} else {
|
} else {
|
||||||
|
@ -650,6 +657,7 @@ void mcpwm_set_brake_current(float current) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stop the motor and use braking.
|
* Stop the motor and use braking.
|
||||||
|
@ -1067,6 +1075,13 @@ static void set_duty_cycle_hl(float dutyCycle) {
|
||||||
} else {
|
} else {
|
||||||
// In case the motor is already spinning, set the state to running
|
// In case the motor is already spinning, set the state to running
|
||||||
// so that it can be ramped down before the full brake is applied.
|
// so that it can be ramped down before the full brake is applied.
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
if (fabsf(dutycycle_now) > 0.1) {
|
||||||
|
state = MC_STATE_RUNNING;
|
||||||
|
} else {
|
||||||
|
full_brake_ll();
|
||||||
|
}
|
||||||
|
} else {
|
||||||
if (fabsf(rpm_now) > conf.l_max_erpm_fbrake) {
|
if (fabsf(rpm_now) > conf.l_max_erpm_fbrake) {
|
||||||
state = MC_STATE_RUNNING;
|
state = MC_STATE_RUNNING;
|
||||||
} else {
|
} else {
|
||||||
|
@ -1075,6 +1090,7 @@ static void set_duty_cycle_hl(float dutyCycle) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Low-level duty cycle setter. Will update the state of the application
|
* Low-level duty cycle setter. Will update the state of the application
|
||||||
|
@ -1116,6 +1132,11 @@ static void set_duty_cycle_ll(float dutyCycle) {
|
||||||
|
|
||||||
set_duty_cycle_hw(dutyCycle);
|
set_duty_cycle_hw(dutyCycle);
|
||||||
|
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
state = MC_STATE_RUNNING;
|
||||||
|
set_next_comm_step(comm_step);
|
||||||
|
commutate(1);
|
||||||
|
} else {
|
||||||
if (conf.sl_is_sensorless) {
|
if (conf.sl_is_sensorless) {
|
||||||
if (state != MC_STATE_RUNNING) {
|
if (state != MC_STATE_RUNNING) {
|
||||||
if (state == MC_STATE_OFF) {
|
if (state == MC_STATE_OFF) {
|
||||||
|
@ -1140,6 +1161,7 @@ static void set_duty_cycle_ll(float dutyCycle) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Lowest level (hardware) duty cycle setter. Will set the hardware timer to
|
* Lowest level (hardware) duty cycle setter. Will set the hardware timer to
|
||||||
|
@ -1158,19 +1180,23 @@ static void set_duty_cycle_hw(float dutyCycle) {
|
||||||
|
|
||||||
utils_truncate_number(&dutyCycle, MCPWM_MIN_DUTY_CYCLE, MCPWM_MAX_DUTY_CYCLE);
|
utils_truncate_number(&dutyCycle, MCPWM_MIN_DUTY_CYCLE, MCPWM_MAX_DUTY_CYCLE);
|
||||||
|
|
||||||
if (conf.pwm_mode == PWM_MODE_BIPOLAR && !IS_DETECTING()) {
|
if (conf.motor_type == MOTOR_TYPE_BLDC && conf.pwm_mode == PWM_MODE_BIPOLAR && !IS_DETECTING()) {
|
||||||
timer_tmp.duty = (uint16_t) (((float) timer_tmp.top / 2.0) * dutyCycle
|
timer_tmp.duty = (uint16_t) (((float) timer_tmp.top / 2.0) * dutyCycle
|
||||||
+ ((float) timer_tmp.top / 2.0));
|
+ ((float) timer_tmp.top / 2.0));
|
||||||
} else {
|
} else {
|
||||||
timer_tmp.duty = (uint16_t)((float)timer_tmp.top * dutyCycle);
|
timer_tmp.duty = (uint16_t)((float)timer_tmp.top * dutyCycle);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
switching_frequency_now = MCPWM_SWITCH_FREQUENCY_DC_MOTOR;
|
||||||
|
} else {
|
||||||
if (IS_DETECTING() || conf.pwm_mode == PWM_MODE_BIPOLAR) {
|
if (IS_DETECTING() || conf.pwm_mode == PWM_MODE_BIPOLAR) {
|
||||||
switching_frequency_now = MCPWM_SWITCH_FREQUENCY_MAX;
|
switching_frequency_now = MCPWM_SWITCH_FREQUENCY_MAX;
|
||||||
} else {
|
} else {
|
||||||
switching_frequency_now = (float)MCPWM_SWITCH_FREQUENCY_MIN * (1.0 - fabsf(dutyCycle)) +
|
switching_frequency_now = (float)MCPWM_SWITCH_FREQUENCY_MIN * (1.0 - fabsf(dutyCycle)) +
|
||||||
(float)MCPWM_SWITCH_FREQUENCY_MAX * fabsf(dutyCycle);
|
(float)MCPWM_SWITCH_FREQUENCY_MAX * fabsf(dutyCycle);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
timer_tmp.top = SYSTEM_CORE_CLOCK / (int)switching_frequency_now;
|
timer_tmp.top = SYSTEM_CORE_CLOCK / (int)switching_frequency_now;
|
||||||
update_adc_sample_pos(&timer_tmp);
|
update_adc_sample_pos(&timer_tmp);
|
||||||
|
@ -1316,6 +1342,14 @@ static msg_t timer_thread(void *arg) {
|
||||||
(float*)amp_fir_coeffs, AMP_FIR_TAPS_BITS, amp_fir_index);
|
(float*)amp_fir_coeffs, AMP_FIR_TAPS_BITS, amp_fir_index);
|
||||||
|
|
||||||
// Direction tracking
|
// Direction tracking
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
if (amp > 0) {
|
||||||
|
direction = 0;
|
||||||
|
} else {
|
||||||
|
direction = 1;
|
||||||
|
amp = -amp;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
if (conf.sl_is_sensorless) {
|
if (conf.sl_is_sensorless) {
|
||||||
min_s = 9999999999999.0;
|
min_s = 9999999999999.0;
|
||||||
max_s = 0.0;
|
max_s = 0.0;
|
||||||
|
@ -1364,6 +1398,7 @@ static msg_t timer_thread(void *arg) {
|
||||||
tachometer_for_direction = 0;
|
tachometer_for_direction = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (direction == 1) {
|
if (direction == 1) {
|
||||||
dutycycle_now = amp / (float)ADC_Value[ADC_IND_VIN_SENS];
|
dutycycle_now = amp / (float)ADC_Value[ADC_IND_VIN_SENS];
|
||||||
|
@ -1427,8 +1462,6 @@ static msg_t timer_thread(void *arg) {
|
||||||
void mcpwm_adc_inj_int_handler(void) {
|
void mcpwm_adc_inj_int_handler(void) {
|
||||||
TIM12->CNT = 0;
|
TIM12->CNT = 0;
|
||||||
|
|
||||||
static int detect_now = 0;
|
|
||||||
|
|
||||||
int curr0 = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_1);
|
int curr0 = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_1);
|
||||||
int curr1 = ADC_GetInjectedConversionValue(ADC2, ADC_InjectedChannel_1);
|
int curr1 = ADC_GetInjectedConversionValue(ADC2, ADC_InjectedChannel_1);
|
||||||
|
|
||||||
|
@ -1448,6 +1481,15 @@ void mcpwm_adc_inj_int_handler(void) {
|
||||||
|
|
||||||
float curr_tot_sample = 0;
|
float curr_tot_sample = 0;
|
||||||
|
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
if (direction) {
|
||||||
|
curr_tot_sample = -(float)(ADC_Value[ADC_IND_CURR2] - curr1_offset);
|
||||||
|
} else {
|
||||||
|
curr_tot_sample = -(float)(ADC_Value[ADC_IND_CURR1] - curr0_offset);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
static int detect_now = 0;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Commutation Steps FORWARDS
|
* Commutation Steps FORWARDS
|
||||||
* STEP BR1 BR2 BR3
|
* STEP BR1 BR2 BR3
|
||||||
|
@ -1551,6 +1593,7 @@ void mcpwm_adc_inj_int_handler(void) {
|
||||||
set_next_comm_step(detect_step + 1);
|
set_next_comm_step(detect_step + 1);
|
||||||
TIM_GenerateEvent(TIM1, TIM_EventSource_COM);
|
TIM_GenerateEvent(TIM1, TIM_EventSource_COM);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
last_current_sample = curr_tot_sample;
|
last_current_sample = curr_tot_sample;
|
||||||
filter_add_sample((float*) current_fir_samples, curr_tot_sample,
|
filter_add_sample((float*) current_fir_samples, curr_tot_sample,
|
||||||
|
@ -1604,6 +1647,8 @@ void mcpwm_adc_int_handler(void *p, uint32_t flags) {
|
||||||
wrong_voltage_iterations = 0;
|
wrong_voltage_iterations = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_BLDC) {
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Calculate the virtual ground, depending on the state.
|
* Calculate the virtual ground, depending on the state.
|
||||||
*/
|
*/
|
||||||
|
@ -1760,6 +1805,24 @@ void mcpwm_adc_int_handler(void *p, uint32_t flags) {
|
||||||
commutate(0);
|
commutate(0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
float amp = 0.0;
|
||||||
|
|
||||||
|
if (has_commutated) {
|
||||||
|
amp = dutycycle_now * (float)ADC_Value[ADC_IND_VIN_SENS];
|
||||||
|
} else {
|
||||||
|
amp = ADC_V_L3 - ADC_V_L1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Fill the amplitude FIR filter
|
||||||
|
filter_add_sample((float*)amp_fir_samples, amp,
|
||||||
|
AMP_FIR_TAPS_BITS, (uint32_t*)&_fir_index);
|
||||||
|
|
||||||
|
if (state == MC_STATE_RUNNING && !has_commutated) {
|
||||||
|
set_next_comm_step(comm_step);
|
||||||
|
commutate(0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
const float current = mcpwm_get_tot_current_filtered();
|
const float current = mcpwm_get_tot_current_filtered();
|
||||||
const float current_in = current * fabsf(dutycycle_now);
|
const float current_in = current * fabsf(dutycycle_now);
|
||||||
|
@ -2129,6 +2192,23 @@ static void update_adc_sample_pos(mc_timer_struct *timer_tmp) {
|
||||||
|
|
||||||
curr_samp_volt = 0;
|
curr_samp_volt = 0;
|
||||||
|
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
curr1_sample = top - 10; // Not used anyway
|
||||||
|
curr2_sample = top - 10;
|
||||||
|
|
||||||
|
if (duty > 1000) {
|
||||||
|
val_sample = duty / 2;
|
||||||
|
} else {
|
||||||
|
val_sample = duty + 800;
|
||||||
|
curr_samp_volt = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// if (duty < (top / 2)) {
|
||||||
|
// val_sample = (top - duty) / 2 + duty;
|
||||||
|
// } else {
|
||||||
|
// val_sample = duty / 2;
|
||||||
|
// }
|
||||||
|
} else {
|
||||||
// Sample the ADC at an appropriate time during the pwm cycle
|
// Sample the ADC at an appropriate time during the pwm cycle
|
||||||
if (IS_DETECTING()) {
|
if (IS_DETECTING()) {
|
||||||
// Voltage samples
|
// Voltage samples
|
||||||
|
@ -2234,6 +2314,7 @@ static void update_adc_sample_pos(mc_timer_struct *timer_tmp) {
|
||||||
curr2_sample = curr1_sample;
|
curr2_sample = curr1_sample;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
timer_tmp->val_sample = val_sample;
|
timer_tmp->val_sample = val_sample;
|
||||||
timer_tmp->curr1_sample = curr1_sample;
|
timer_tmp->curr1_sample = curr1_sample;
|
||||||
|
@ -2270,7 +2351,7 @@ static void update_rpm_tacho(void) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static void commutate(int steps) {
|
static void commutate(int steps) {
|
||||||
if (conf.sl_is_sensorless) {
|
if (conf.motor_type == MOTOR_TYPE_BLDC && conf.sl_is_sensorless) {
|
||||||
last_pwm_cycles_sum = pwm_cycles_sum;
|
last_pwm_cycles_sum = pwm_cycles_sum;
|
||||||
last_pwm_cycles_sums[comm_step - 1] = pwm_cycles_sum;
|
last_pwm_cycles_sums[comm_step - 1] = pwm_cycles_sum;
|
||||||
pwm_cycles_sum = 0;
|
pwm_cycles_sum = 0;
|
||||||
|
@ -2359,6 +2440,37 @@ static void set_switching_frequency(float frequency) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static void set_next_comm_step(int next_step) {
|
static void set_next_comm_step(int next_step) {
|
||||||
|
if (conf.motor_type == MOTOR_TYPE_DC) {
|
||||||
|
// 0
|
||||||
|
TIM_SelectOCxM(TIM1, TIM_Channel_2, TIM_OCMode_Inactive);
|
||||||
|
TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Enable);
|
||||||
|
TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Disable);
|
||||||
|
|
||||||
|
if (direction) {
|
||||||
|
// +
|
||||||
|
TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_OCMode_PWM1);
|
||||||
|
TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
|
||||||
|
TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Enable);
|
||||||
|
|
||||||
|
// -
|
||||||
|
TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_OCMode_Inactive);
|
||||||
|
TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
|
||||||
|
TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Enable);
|
||||||
|
} else {
|
||||||
|
// +
|
||||||
|
TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_OCMode_PWM1);
|
||||||
|
TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
|
||||||
|
TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Enable);
|
||||||
|
|
||||||
|
// -
|
||||||
|
TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_OCMode_Inactive);
|
||||||
|
TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
|
||||||
|
TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Enable);
|
||||||
|
}
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
uint16_t positive_oc_mode = TIM_OCMode_PWM1;
|
uint16_t positive_oc_mode = TIM_OCMode_PWM1;
|
||||||
uint16_t negative_oc_mode = TIM_OCMode_Inactive;
|
uint16_t negative_oc_mode = TIM_OCMode_Inactive;
|
||||||
|
|
||||||
|
|
1
mcpwm.h
1
mcpwm.h
|
@ -92,6 +92,7 @@ extern volatile int mcpwm_vzero;
|
||||||
*/
|
*/
|
||||||
#define MCPWM_SWITCH_FREQUENCY_MIN 3000 // The lowest switching frequency in Hz
|
#define MCPWM_SWITCH_FREQUENCY_MIN 3000 // The lowest switching frequency in Hz
|
||||||
#define MCPWM_SWITCH_FREQUENCY_MAX 35000 // The highest switching frequency in Hz
|
#define MCPWM_SWITCH_FREQUENCY_MAX 35000 // The highest switching frequency in Hz
|
||||||
|
#define MCPWM_SWITCH_FREQUENCY_DC_MOTOR 25000 // The DC motor switching frequency
|
||||||
#define MCPWM_DEAD_TIME_CYCLES 80 // Dead time
|
#define MCPWM_DEAD_TIME_CYCLES 80 // Dead time
|
||||||
#define MCPWM_RPM_TIMER_FREQ 1000000.0 // Frequency of the RPM measurement timer
|
#define MCPWM_RPM_TIMER_FREQ 1000000.0 // Frequency of the RPM measurement timer
|
||||||
#define MCPWM_MIN_DUTY_CYCLE 0.005 // Minimum duty cycle
|
#define MCPWM_MIN_DUTY_CYCLE 0.005 // Minimum duty cycle
|
||||||
|
|
Loading…
Reference in New Issue