initial branch commit

This commit is contained in:
Nicolas Trimborn
2021-04-28 09:26:14 +02:00
parent e533db6ce8
commit db49ec9cf3
6 changed files with 308 additions and 233 deletions

23
BLDC_E54/.gitignore vendored Normal file
View File

@@ -0,0 +1,23 @@
## Ignore Atmel Studio temporary files and build results
# https://www.microchip.com/mplab/avr-support/atmel-studio-7
# Atmel Studio is powered by an older version of Visual Studio,
# so most of the project and solution files are the same as VS files,
# only prefixed by an `at`.
#Build Directories
[Dd]ebug/
[Rr]elease/
#Build Results
*.o
*.d
*.eep
*.elf
*.hex
*.map
*.srec
#User Specific Files
*.atsuo

Binary file not shown.

View File

@@ -1011,6 +1011,9 @@
<Compile Include="main.c"> <Compile Include="main.c">
<SubType>compile</SubType> <SubType>compile</SubType>
</Compile> </Compile>
<Compile Include="motor_params.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="pins.h"> <Compile Include="pins.h">
<SubType>compile</SubType> <SubType>compile</SubType>
</Compile> </Compile>

View File

@@ -79,7 +79,7 @@ void BLDC_init(BLDCMotor_t *motor)
motor->VdcBus_pu = DEVICE_DC_VOLTAGE_V; motor->VdcBus_pu = DEVICE_DC_VOLTAGE_V;
motor->VoneByDcBus_pu = 1.0f/DEVICE_DC_VOLTAGE_V; motor->VoneByDcBus_pu = 1.0f/DEVICE_DC_VOLTAGE_V;
motor->motor_commutation_Pattern = COMMUTATION_PATTERN; motor->motor_commutation_Pattern = COMMUTATION_PATTERN_M1;
motor->desired_torque = 0.0; motor->desired_torque = 0.0;
motor->desired_speed = 0; motor->desired_speed = 0;
@@ -225,7 +225,7 @@ void exec_commutation(void)
//} //}
TCC1->PATTBUF.reg = COMMUTATION_PATTERN[(Motor1.currentHallPattern + Motor1.directionOffset)]; TCC1->PATTBUF.reg = COMMUTATION_PATTERN_M1[(Motor1.currentHallPattern + Motor1.directionOffset)];
TCC1->CCBUF->reg = (uint16_t)Motor1.duty_cycle; TCC1->CCBUF->reg = (uint16_t)Motor1.duty_cycle;
//hri_tcc_write_PATTBUF_reg(TCC1, (COMMUTATION_PATTERN[(Motor1.currentHallPattern + Motor1.directionOffset)])); //hri_tcc_write_PATTBUF_reg(TCC1, (COMMUTATION_PATTERN[(Motor1.currentHallPattern + Motor1.directionOffset)]));

View File

@@ -1,234 +1,157 @@
/* /*
* bldc.h * bldc.h
* *
* Created: 10/03/2021 14:38:14 * Created: 10/03/2021 14:38:14
* Author: Nick-XMG * Author: Nick-XMG
*/ */
#ifndef BLDC_H_ #ifndef BLDC_H_
#define BLDC_H_ #define BLDC_H_
// ---------------------------------------------------------------------- // ----------------------------------------------------------------------
// header files // header files
// ---------------------------------------------------------------------- // ----------------------------------------------------------------------
#include "arm_math.h" #include "arm_math.h"
#include "atmel_start.h" #include "atmel_start.h"
#include "control.h" #include "control.h"
#include "motor_params.h"
// ---------------------------------------------------------------------- /* if the Hall sensor reads 0x0 or 0x7 that means either one of the hall sensor is damaged or disconnected*/
// Current Sensor #define INVALID_HALL_0 (0U)
// ---------------------------------------------------------------------- #define INVALID_HALL_7 (7U)
#define DRV_ISEN_A_CH ADC_INPUTCTRL_MUXPOS_AIN2_Val // ----------------------------------------------------------------------
#define DRV_ISEN_B_CH ADC_INPUTCTRL_MUXPOS_AIN1_Val // ADC Parameters
// ----------------------------------------------------------------------
// ---------------------------------------------------------------------- #define ADC_VOLTAGE_REFERENCE (3.3f)
// Hall Parameters #define ADC_RESOLUTION (12)
// ---------------------------------------------------------------------- #define ADC_MAX_COUNTS (1<<ADC_RESOLUTION)
#define ADC_LSB_SIZE (ADC_VOLTAGE_REFERENCE/ADC_MAX_COUNTS)
#define HALL_A_PIN GPIO(GPIO_PORTA, 6)
#define HALL_A_PORT PORT_PA06 // ----------------------------------------------------------------------
#define HALL_A_MASK ~(1<<2) // Define the control and PWM frequencies:
#define HALL_A_LSR HALL_A_PIN - HALL_A_GROUP*32 -2 // ----------------------------------------------------------------------
#define HALL_A_GROUP HALL_A_PIN/32 // 16kHz is the maximum frequency according to the calculation duration in the mode run and spin.
#define DEVICE_MCU_FREQUENCY_Hz (100000000U)
#define HALL_B_PIN GPIO(GPIO_PORTA, 5) #define DEVICE_SPEEDTC_DIV (4U)
#define HALL_B_PORT PORT_PA05 #define DEVICE_SPEEDTC_FREQUENCY_Hz (100000000U/DEVICE_SPEEDTC_DIV)
#define HALL_B_MASK ~(1<<1) #define DEVICE_PWM_FREQUENCY_kHz (25.0f)
#define HALL_B_LSR HALL_B_PIN - HALL_B_GROUP*32 -1 #define DEVICE_ISR_FREQUENCY_kHz DEVICE_PWM_FREQUENCY_kHz
#define HALL_B_GROUP HALL_B_PIN/32 #define DEVICE_ISR_PERIOD_Sec (0.001f/DEVICE_ISR_FREQUENCY_kHz)
#define HALL_C_PIN GPIO(GPIO_PORTA, 4)
#define HALL_C_PORT PORT_PA04 // ----------------------------------------------------------------------
#define HALL_C_MASK ~(1<<0) // Define the device quantities (voltage, current, speed)
#define HALL_C_LSR HALL_C_PIN - HALL_C_GROUP*32 -0 // ----------------------------------------------------------------------
#define HALL_C_GROUP HALL_C_PIN/32 #define DEVICE_DC_VOLTAGE_V 24.0f // max. ADC bus voltage(PEAK) [V]
#define DEVICE_SHUNT_CURRENT_A 2.5f // phase current(PEAK) [A]
/* if the Hall sensor reads 0x0 or 0x7 that means either one of the hall sensor is damaged or disconnected*/ #define CURRENT_SENSOR_SENSITIVITY 0.4f //V/A
#define INVALID_HALL_0 (0U) #define ONEON_CURRENT_SENSOR_SENSITIVITY 2.5f //V/A
#define INVALID_HALL_7 (7U) // ----------------------------------------------------------------------
// global variables
// ---------------------------------------------------------------------- // ----------------------------------------------------------------------
// ADC Parameters volatile typedef struct
// ---------------------------------------------------------------------- {
#define ADC_VOLTAGE_REFERENCE (3.3f) volatile float32_t A; // Phase A
#define ADC_RESOLUTION (12) volatile float32_t B; // Phase B
#define ADC_MAX_COUNTS (1<<ADC_RESOLUTION) volatile float32_t C; // Phase C
#define ADC_LSB_SIZE (ADC_VOLTAGE_REFERENCE/ADC_MAX_COUNTS) volatile float32_t Bus; // Currently Active Phase Current
// ---------------------------------------------------------------------- } MOTOR_3PHASES_t;
// Motor Parameters
// ---------------------------------------------------------------------- volatile typedef struct
// these values fit for an Faulhaber 3216W024BXTR motor {
#define MOTOR_POLES (14U) volatile int16_t A; // Phase A measured offset
#define MOTOR_POLEPAIRS (MOTOR_POLES/2) volatile int16_t B; // Phase B measured offset
#define MOTOR_COMUTATION_STATES (MOTOR_POLEPAIRS*6) } MOTOR_phase_offset_t;
#define MOTOR_RS_OHM (3.37f)
#define MOTOR_LD_H (0.001290f) volatile typedef struct timerflags
#define MOTOR_LQ_H (0.001290f) {
#define MOTOR_FLUX_WB (0.0063879968f) volatile bool pwm_cycle_tic;
#define MOTOR_MAX_SPD_RPM (4200.0f) volatile bool current_loop_tic;
#define MOTOR_MAX_SPD_ELEC ((MOTOR_MAX_SPD_RPM/60)*MOTOR_POLEPAIRS) volatile bool control_loop_tic; //! Is motor synchronized? Does not have any meaning when motorStopped is TRUE.
#define MOTOR_MEASURINGRANGE_RPM (1.2f * MOTOR_MAX_SPD_RPM)f // give 20% headroom volatile bool motor_telemetry_flag;
#define MOTOR_MAX_CURRENT_IDC_A (1.2f) } TIMERflags_t;
#define PWM_TOP 1000 volatile typedef struct
#define MAX_PWM 700 {
#define MAX_VEL 3800 volatile PI_t Pi_Idc;
volatile PID_t Pid_Speed;
#define CW 0 //CBA volatile PI_t Pi_Pos;
#define DIRECTION_CW_OFFSET 0 //CBA } MOTOR_Control_Structs;
#define CCW 1 //ABC
#define DIRECTION_CCW_OFFSET 8 //CBA volatile typedef struct BLDCmotor
{
#define AVERAGE_SPEED_MEASURE /* Hardware */
#define COUNTEQUIVTO25RPM 892857142 const Tcc *hw;
#define n_SAMPLE 8 uint16_t *motor_commutation_Pattern;
static uint32_t speed_average = 0; /* Status */
static uint8_t count = 1; volatile uint8_t actualDirection; //! The actual direction of rotation.
volatile uint8_t desiredDirection; //! The desired direction of rotation.
volatile uint16_t duty_cycle;
// ---------------------------------------------------------------------- volatile float32_t calc_rpm;
// Define the control and PWM frequencies: volatile int32_t Num_Steps; // Total Step Count
// ---------------------------------------------------------------------- /* Commutation State */
// 16kHz is the maximum frequency according to the calculation duration in the mode run and spin. volatile uint8_t cur_comm_step;
#define DEVICE_MCU_FREQUENCY_Hz (100000000U) volatile uint8_t prev_comm_step;
#define DEVICE_SPEEDTC_DIV (4U) /* Hall States */
#define DEVICE_SPEEDTC_FREQUENCY_Hz (100000000U/DEVICE_SPEEDTC_DIV) volatile uint8_t prevHallPattern;
#define DEVICE_PWM_FREQUENCY_kHz (25.0f) volatile uint8_t currentHallPattern;
#define DEVICE_ISR_FREQUENCY_kHz DEVICE_PWM_FREQUENCY_kHz volatile uint8_t nextHallPattern;
#define DEVICE_ISR_PERIOD_Sec (0.001f/DEVICE_ISR_FREQUENCY_kHz) volatile uint8_t dir_hall_code; //DIR_ABC
volatile uint8_t directionOffset;
/* Measured Values */
// ---------------------------------------------------------------------- volatile MOTOR_3PHASES_t Iphase_pu;
// Define the device quantities (voltage, current, speed) volatile MOTOR_phase_offset_t Voffset_lsb;
// ---------------------------------------------------------------------- volatile float32_t VdcBus_pu;
#define DEVICE_DC_VOLTAGE_V 24.0f // max. ADC bus voltage(PEAK) [V] volatile float32_t VoneByDcBus_pu;
#define DEVICE_SHUNT_CURRENT_A 2.5f // phase current(PEAK) [A] /* Motor Flags */
#define CURRENT_SENSOR_SENSITIVITY 0.4f //V/A volatile TIMERflags_t timerflags;
#define ONEON_CURRENT_SENSOR_SENSITIVITY 2.5f //V/A volatile uint8_t regulation_loop_count;
// ---------------------------------------------------------------------- /* Controllers */
// global variables volatile MOTOR_Control_Structs controllers;
// ---------------------------------------------------------------------- /* Setpoints */
volatile typedef struct volatile float32_t desired_torque;
{ volatile int16_t desired_speed;
volatile float32_t A; // Phase A volatile int16_t desired_position;
volatile float32_t B; // Phase B volatile float32_t max_current;
volatile float32_t C; // Phase C volatile float32_t max_torque;
volatile float32_t Bus; // Currently Active Phase Current volatile int16_t max_velocity;
} MOTOR_3PHASES_t;
} BLDCMotor_t;
volatile typedef struct
{
volatile int16_t A; // Phase A measured offset // ----------------------------------------------------------------------
volatile int16_t B; // Phase B measured offset // global variables
} MOTOR_phase_offset_t; // ----------------------------------------------------------------------
volatile typedef struct timerflags static const uint8_t HALL_PATTERN_ARRAY[16] = {0, 5, 3, 1, 6, 4, 2, 0, 0, 3, 6, 2, 5, 1, 4, 0 };
{ static const uint8_t MOTOR_COMMUTATION_STEPS[8] = {20,1,3,2,5,6,4,20};
volatile bool pwm_cycle_tic;
volatile bool current_loop_tic; volatile BLDCMotor_t Motor1;
volatile bool control_loop_tic; //! Is motor synchronized? Does not have any meaning when motorStopped is TRUE.
volatile bool motor_telemetry_flag; // ----------------------------------------------------------------------
} TIMERflags_t; // all controller objects, variables and helpers:
// ----------------------------------------------------------------------
volatile typedef struct
{
volatile PI_t Pi_Idc; // ----------------------------------------------------------------------
volatile PID_t Pid_Speed; // functions
volatile PI_t Pi_Pos; // ----------------------------------------------------------------------
} MOTOR_Control_Structs; void select_active_phase(BLDCMotor_t *Motor, uint8_t hall_state);
void BLDC_init(BLDCMotor_t *motor);
volatile typedef struct BLDCmotor void read_zero_current_offset_value(void);
{ int32_t adc_sync_read_channel(struct adc_async_descriptor *const descr, const uint8_t channel, uint8_t *const buffer, const uint16_t length);
/* Hardware */ static uint16_t adc_read(struct adc_async_descriptor *const descr, const uint8_t channel);
const Tcc * hw; void exec_commutation(void);
uint16_t * motor_commutation_Pattern; uint8_t get_dir_hall_code(void);
/* Status */ uint8_t get_hall_state(void);
volatile uint8_t actualDirection; //! The actual direction of rotation.
volatile uint8_t desiredDirection; //! The desired direction of rotation. uint8_t HALLPatternGet(void);
volatile uint16_t duty_cycle; uint8_t PDEC_HALLPatternGet(void);
volatile float32_t calc_rpm; void calculate_motor_speed(void);
volatile int32_t Num_Steps; // Total Step Count
/* Commutation State */
volatile uint8_t cur_comm_step;
volatile uint8_t prev_comm_step;
/* Hall States */
volatile uint8_t prevHallPattern;
volatile uint8_t currentHallPattern;
volatile uint8_t nextHallPattern;
volatile uint8_t dir_hall_code; //DIR_ABC
volatile uint8_t directionOffset;
/* Measured Values */
volatile MOTOR_3PHASES_t Iphase_pu;
volatile MOTOR_phase_offset_t Voffset_lsb;
volatile float32_t VdcBus_pu;
volatile float32_t VoneByDcBus_pu;
/* Motor Flags */
volatile TIMERflags_t timerflags;
volatile uint8_t regulation_loop_count;
/* Controllers */
volatile MOTOR_Control_Structs controllers;
/* Setpoints */
volatile float32_t desired_torque;
volatile int16_t desired_speed;
volatile int16_t desired_position;
volatile float32_t max_current;
volatile float32_t max_torque;
volatile int16_t max_velocity;
} BLDCMotor_t;
// ----------------------------------------------------------------------
// global variables
// ----------------------------------------------------------------------
static const uint8_t HALL_PATTERN_ARRAY[16] = {0, 5, 3, 1, 6, 4, 2, 0, 0, 3, 6, 2, 5, 1, 4, 0 };
static const uint8_t MOTOR_COMMUTATION_STEPS[8] = {20,1,3,2,5,6,4,20};
static const uint16_t COMMUTATION_PATTERN[] = {
0x00FC, // invalid state (0)
0x30F8, // CB_CW (1)
0x50F4, // CA_CW (2)
0x60F8, // BA_CW (3)
0x607C, // AB_CW (4)
0x507C, // BC_CW (5)
0x30F4, // AC_CW (6)
0x00FC, // invalid state
0x00FC, // invalid state
0x30F4, // BC_CCW (9)
0x507C, // AB_CCW (10)
0x607C, // AC_CCW (11)
0x60F8, // CA_CCW (12)
0x50F4, // BA_CCW (13)
0x30F8, // CB_CCW (14)
0x00FC
};//Based on Hall State Dir_A_B_C
volatile BLDCMotor_t Motor1;
// ----------------------------------------------------------------------
// all controller objects, variables and helpers:
// ----------------------------------------------------------------------
//volatile PI_t Pi_Idc;
//volatile PI_t Pi_Speed;
// ----------------------------------------------------------------------
// functions
// ----------------------------------------------------------------------
void select_active_phase(BLDCMotor_t *Motor, uint8_t hall_state);
void BLDC_init(BLDCMotor_t *motor);
void read_zero_current_offset_value(void);
int32_t adc_sync_read_channel(struct adc_async_descriptor *const descr, const uint8_t channel, uint8_t *const buffer, const uint16_t length);
static uint16_t adc_read(struct adc_async_descriptor *const descr, const uint8_t channel);
void exec_commutation(void);
uint8_t get_dir_hall_code(void);
void DisableGateDrivers(BLDCMotor_t *motor); void DisableGateDrivers(BLDCMotor_t *motor);
void BLDC_runSpeedCntl(BLDCMotor_t *motor, volatile float speedfbk, volatile float speedRef);
void BLDC_runCurrentCntl(BLDCMotor_t *motor, volatile float curfbk, volatile float curRef); void BLDC_runCurrentCntl(BLDCMotor_t *motor, volatile float curfbk, volatile float curRef);
uint8_t PDEC_HALLPatternGet(void); void BLDC_runPosCntl(BLDCMotor_t *motor, int16_t posfbk, int16_t posRef);
void calculate_motor_speed(void);
#endif /* BLDC_H_ */ #endif /* BLDC_H_ */

View File

@@ -0,0 +1,126 @@
/*
* motor_params.h
*
* Created: 28/04/2021 09:13:40
* Author: Nick-XMG
*/
#ifndef MOTOR_PARAMS_H_
#define MOTOR_PARAMS_H_
// ----------------------------------------------------------------------
// Current Sensor
// ----------------------------------------------------------------------
#define DRV_ISEN_A_CH ADC_INPUTCTRL_MUXPOS_AIN2_Val
#define DRV_ISEN_B_CH ADC_INPUTCTRL_MUXPOS_AIN1_Val
// ----------------------------------------------------------------------
// Hall Parameters
// ----------------------------------------------------------------------
#define HALL_A_PIN GPIO(GPIO_PORTA, 6)
#define HALL_A_PORT PORT_PA06
#define HALL_A_MASK ~(1<<2)
#define HALL_A_LSR HALL_A_PIN - HALL_A_GROUP*32 -2
#define HALL_A_GROUP HALL_A_PIN/32
#define HALL_B_PIN GPIO(GPIO_PORTA, 5)
#define HALL_B_PORT PORT_PA05
#define HALL_B_MASK ~(1<<1)
#define HALL_B_LSR HALL_B_PIN - HALL_B_GROUP*32 -1
#define HALL_B_GROUP HALL_B_PIN/32
#define HALL_C_PIN GPIO(GPIO_PORTA, 4)
#define HALL_C_PORT PORT_PA04
#define HALL_C_MASK ~(1<<0)
#define HALL_C_LSR HALL_C_PIN - HALL_C_GROUP*32 -0
#define HALL_C_GROUP HALL_C_PIN/32
// ----------------------------------------------------------------------
// Motor Parameters
// ----------------------------------------------------------------------
// these values fit for an Faulhaber 3216W024BXTR motor
#define MOTOR_POLES (14U)
#define MOTOR_POLEPAIRS (MOTOR_POLES/2)
#define MOTOR_COMUTATION_STATES (MOTOR_POLEPAIRS*6)
#define MOTOR_RS_OHM (3.37f)
#define MOTOR_LD_H (0.001290f)
#define MOTOR_LQ_H (0.001290f)
#define MOTOR_FLUX_WB (0.0063879968f)
#define MOTOR_MAX_SPD_RPM (4200.0f)
#define MOTOR_MAX_SPD_ELEC ((MOTOR_MAX_SPD_RPM/60)*MOTOR_POLEPAIRS)
#define MOTOR_MEASURINGRANGE_RPM (1.2f * MOTOR_MAX_SPD_RPM)f // give 20% headroom
#define MOTOR_MAX_CURRENT_IDC_A (1.2f)
#define PWM_TOP 1000
#define MAX_PWM 700
#define MAX_VEL 3800
#define CW 0 //CBA
#define DIRECTION_CW_OFFSET 0 //CBA
#define CCW 1 //ABC
#define DIRECTION_CCW_OFFSET 8 //CBA
#define AVERAGE_SPEED_MEASURE
#define COUNTEQUIVTO25RPM 892857142
#define n_SAMPLE 8
static uint32_t speed_average = 0;
static uint8_t count = 1;
static const uint16_t COMMUTATION_PATTERN_M1[] = {
0x00FC, // invalid state (0)
0x30F8, // CB_CW (1)
0x50F4, // CA_CW (2)
0x60F8, // BA_CW (3)
0x607C, // AB_CW (4)
0x507C, // BC_CW (5)
0x30F4, // AC_CW (6)
0x00FC, // invalid state
0x00FC, // invalid state
0x30F4, // BC_CCW (9)
0x507C, // AB_CCW (10)
0x607C, // AC_CCW (11)
0x60F8, // CA_CCW (12)
0x50F4, // BA_CCW (13)
0x30F8, // CB_CCW (14)
0x00FC
};
static const uint16_t COMMUTATION_PATTERN_M2[] = {
0x00FC, // invalid state (0)
0x30F8, // CB_CW (1)
0x50F4, // CA_CW (2)
0x60F8, // BA_CW (3)
0x607C, // AB_CW (4)
0x507C, // BC_CW (5)
0x30F4, // AC_CW (6)
0x00FC, // invalid state
0x00FC, // invalid state
0x30F4, // BC_CCW (9)
0x507C, // AB_CCW (10)
0x607C, // AC_CCW (11)
0x60F8, // CA_CCW (12)
0x50F4, // BA_CCW (13)
0x30F8, // CB_CCW (14)
0x00FC
};
static const uint16_t COMMUTATION_PATTERN_M3[] = {
0x00FC, // invalid state (0)
0x30F8, // CB_CW (1)
0x50F4, // CA_CW (2)
0x60F8, // BA_CW (3)
0x607C, // AB_CW (4)
0x507C, // BC_CW (5)
0x30F4, // AC_CW (6)
0x00FC, // invalid state
0x00FC, // invalid state
0x30F4, // BC_CCW (9)
0x507C, // AB_CCW (10)
0x607C, // AC_CCW (11)
0x60F8, // CA_CCW (12)
0x50F4, // BA_CCW (13)