31#define __AVR_ATmega32U4__ 1
41#ifdef __INTELLISENSE__
42#define ISR(vector) void vector(void)
44#include <avr/interrupt.h>
49#ifdef __INTELLISENSE__
52#include <avr/pgmspace.h>
66#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
201#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
228#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
235 Serial.begin(115200);
259 TIMSK4 |= (1 << TOIE4);
276 if (Serial.available() > 0)
341 PLLFRQ = (0 << PINMUX) | (1 << PLLUSB) |
PLL_POSTSCALER_DIV_1_5 | (1 << PDIV3) | (0 << PDIV2) | (1 << PDIV1) | (0 << PDIV0);
344 PLLCSR = (1 << PINDIV) | (1 << PLLE);
347 while ((PLLCSR & (1 << PLOCK)) == 0)
363#if (EMULATE_HALL == TRUE)
371#if ((HALL_PULLUP_ENABLE == TRUE) && (EMULATE_HALL != TRUE))
408 TCCR1A = (1 << WGM11) | (0 << WGM10);
409 TCCR1B = (0 << WGM13) | (1 << WGM12);
410 TIMSK1 = (1 << TOIE1);
415#if (EMULATE_HALL == TRUE)
417 TCCR3A = (1 << WGM31) | (1 << WGM30);
418 TCCR3B = (1 << WGM33) | (1 << WGM32);
419 TIMSK3 = (1 << TOIE3);
423 OCR3AL = (uint8_t)(0xff &
TIM3_TOP);
429 TCCR4A = (0 << COM4A1) | (1 << COM4A0) | (0 << COM4B1) | (1 << COM4B0) | (1 << PWM4A) | (1 << PWM4B);
431 TCCR4C |= (0 << COM4D1) | (1 << COM4D0) | (1 << PWM4D);
432 TCCR4E = (1 << ENHC4);
454 EICRA = (0 << ISC21) | (1 << ISC20) | (0 << ISC01) | (1 << ISC00);
455 EIMSK = (1 << INT2) | (1 << INT0);
458 PCMSK0 = (1 << PCINT3) | (1 << PCINT2) | (1 << PCINT1);
461 PCICR = (1 << PCIE0);
489 ADCSRA = (1 << ADEN);
512 if ((adc_reading < 223) || (adc_reading > 227))
533 while (adc_reading == 0x3ff)
542 PORTF &= ~(1 << PF0);
545 ADMUX &= ~ADC_MUX_L_BITS;
551 ADCSRA = (1 << ADEN) | (1 << ADSC) | (1 << ADATE) | (1 << ADIF) | (1 << ADIE) |
ADC_PRESCALER;
564 ADCSRA |= (1 << ADSC);
567 while (ADCSRA & (1 << ADSC))
573 uint16_t value = (ADCL >> 6);
574 value |= 0x3ff & (ADCH << 2);
604#if (TURN_OFF_MODE == TURN_OFF_MODE_COAST)
612#if (TURN_OFF_MODE == TURN_OFF_MODE_BRAKE)
615 TimersSetModeBrake();
668#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
673 uint16_t outputValue;
677 if (outputValue > 255)
785 TCCR4A = (0 << COM4A1) | (1 << COM4A0) | (0 << COM4B1) | (1 << COM4B0) | (1 << PWM4A) | (1 << PWM4B);
786 TCCR4C |= (0 << COM4D1) | (1 << COM4D0) | (1 << PWM4D);
787 TCCR4D = (1 << WGM41) | (1 << WGM40);
801#if (TURN_OFF_MODE == TURN_OFF_MODE_BRAKE)
826 TCCR4A = (0 << COM4A1) | (1 << COM4A0) | (0 << COM4B1) | (1 << COM4B0) | (1 << PWM4A) | (1 << PWM4B);
827 TCCR4C |= (0 << COM4D1) | (1 << COM4D0) | (1 << PWM4D);
828 TCCR4D = (1 << WGM41) | (1 << WGM40);
835 TCCR4E &= ~0b00111111;
858 while (!(TIFR4 & (1 << TOV4)))
910 const uint8_t *tableAddress;
920 tableAddress += (hall * 4);
923 TCCR4E &= ~0b00111111;
927 PORTB |= (uint8_t)pgm_read_byte_near(tableAddress++);
928 PORTC |= (uint8_t)pgm_read_byte_near(tableAddress++);
929 PORTD |= (uint8_t)pgm_read_byte_near(tableAddress++);
930 TCCR4E |= (uint8_t)pgm_read_byte_near(tableAddress);
1043 DDRB &= ~PWM_PATTERN_PORTB;
1044 DDRC &= ~PWM_PATTERN_PORTC;
1045 DDRD &= ~PWM_PATTERN_PORTD;
1056 PORTB &= ~PWM_PATTERN_PORTB;
1057 PORTC &= ~PWM_PATTERN_PORTC;
1058 PORTD &= ~PWM_PATTERN_PORTD;
1087 if ((hall == 0) || (hall == 0b111))
1094#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
1100#if (TURN_OFF_MODE == TURN_OFF_MODE_BRAKE)
1131 static uint8_t lastHall = 0xff;
1179#if (TURN_OFF_MODE == TURN_OFF_MODE_COAST)
1188#if (TURN_OFF_MODE == TURN_OFF_MODE_BRAKE)
1192 TimersSetModeBrake();
1220 static uint8_t speedRegTicks = 0;
1230#if (EMULATE_HALL == TRUE)
1302 ADMUX &= ~ADC_MUX_L_BITS;
1304 ADCSRB &= ~ADC_MUX_H_BITS;
1311 ADMUX &= ~ADC_MUX_L_BITS;
1313 ADCSRB &= ~ADC_MUX_H_BITS;
1334 ADMUX &= ~ADC_MUX_L_BITS;
1336 ADCSRB &= ~ADC_MUX_H_BITS;
1346 TIFR0 = (1 << TOV0);
void SweepLEDsBlocking(void)
Sweeps through all LEDs individually with a delay.
void faultSequentialStateMachine(volatile faultflags_t *faultFlags, volatile motorflags_t *motorFlags)
Sequential State Machine for Handling Fault Flags.
int16_t calculateEMA(uint16_t currentSample, uint16_t previousEMA, uint8_t alphaExponent)
Exponential Moving Average (EMA) calculation algorithm.
#define ADC_MUX_H_1V1
High ADC channel selection bit (MUX5) - 1.1V (Vbandgap).
#define ADC_MUX_H_0V
High ADC channel selection bit (MUX5) - 0V (GND).
#define ADC_MUX_L_1V1
Lower ADC channel selection bits (MUX4:0) - 1.1V (Vbandgap).
#define ADC_MUX_L_0V
Lower ADC channel selection bits (MUX4:0) - 0V (GND).
#define ADC_MUX_H_BITS
High ADC channel selection bit (MUX5) mask.
#define ADC_MUX_L_BITS
Lower ADC channel selection bits (MUX4:0) mask.
#define TIM4_TOP(tim4Freq)
#define DEAD_TIME_HALF(deadTime)
This value specifies half the dead time in number of clock cycles. Divide by frequency to get duratio...
#define DT_PRESCALER_DIV_PATTERN(dtPrescaler)
Deadtime generator pre-scaler selection bits based on pre-scaler value.
#define TIM3_TOP
Calculated top value for Timer 3.
#define TIM4_PRESCALER_DIV_PATTERN(tim4Prescaler)
Timer 4 clock select bits based on pre-scaler value.
#define PLL_POSTSCALER_DIV_1_5
PLL Post-scaler - division factor 1.5.
#define ADC_MUX_L_CURRENT
Lower analog channel selection bits (MUX4:0) for motor current measurement.
#define H2_PIN
Pin where H2 is connected.
#define WAVEFORM_BLOCK_COMMUTATION
Waveform constant for block commutation.
#define ADC_MUX_H_GATEVREF
High analog channel selection bit (MUX5) for for motor gateVref measurement.
#define DIRECTION_FORWARD
Forward direction flag value.
#define WAVEFORM_UNDEFINED
Waveform status flag used for coasting.
#define FAULT_PIN_2
Fault Pin 2.
#define DIRECTION_COMMAND_PIN
Pin where direction command input is located.
#define SPEED_INPUT_SOURCE_LOCAL
Speed input source - Local or speed input pin.
#define ADC_MUX_L_BREF
Lower analog channel selection bits (MUX4:0) for motor bref measurement.
#define FAST_ACCESS(register_address)
Assign a specific memory address to a variable for fast access.
#define CHOOSE_DT_PRESCALER(deadTime)
Macro to choose Timer4 dead time pre-scaler based on the dead time.
#define SPEED_CONTROLLER_MAX_INPUT
Maximum Speed Reference Input.
#define DIRECTION_REVERSE
Reverse direction flag value.
#define ENABLE_PIN
Enable input pin.
#define ADC_MUX_H_CURRENT
High analog channel selection bit (MUX5) for for motor current measurement.
#define PWM_PATTERN_PORTC
Bit pattern of PWM pins placed on PORTC (Phase B).
#define ADC_TRIGGER
ADC trigger used in this application.
#define HALL_PIN
PIN register for Hall sensor input.
#define ADC_MUX_L_GATEVREF
Lower analog channel selection bits (MUX4:0) for motor gateVref measurement.
#define ADC_MUX_H_BREF
High analog channel selection bit (MUX5) for for motor bref measurement.
#define WAVEFORM_BRAKING
Waveform status flag for braking.
#define TRUE
TRUE constant value, defined to be compatible with comparisons.
#define FALSE
FALSE constant value.
#define CHOOSE_TIM4_PRESCALER(tim4Freq)
Macro to choose Timer4 pre-scaler.
#define ADC_PRESCALER
ADC clock pre-scaler used in this application.
#define REMOTE_PIN
Remote input pin.
#define FORCE_INLINE
Macro for forcing inline expansion of functions.
#define PWM_PATTERN_PORTB
Bit pattern of PWM pins placed on PORTB (Phase A).
#define PWM_PATTERN_PORTD
Bit pattern of PWM pins placed on PORTD (Phase C).
#define FAULT_PIN_3
Fault Pin 3.
#define DIRECTION_UNKNOWN
Unknown direction flag value.
#define H3_PIN
Pin where H3 is connected.
#define H1_PIN
Pin where H1 is connected.
#define ADC_REFERENCE_VOLTAGE
ADC voltage reference used in this application.
#define FAULT_PIN_1
Fault Pin 1.
#define TIM1_CLOCK_DIV_64
Timer1 clock - i/o clk with division factor 64.
#define TIM1_CLOCK_DIV_8
Timer1 clock - i/o clk with division factor 8.
#define PID_K_P
PID Controller Proportional Gain Constant (Only for Closed Loop)
#define CURRENT_WARNING_THRESHOLD
Current Warning Threshold (Register Value)
#define CURRENT_ERROR_THRESHOLD
Current Error Threshold (Register Value)
#define TIM4_FREQ
Desired Switching Frequency for MOSFET Gate Signals.
#define SPEED_CONTROLLER_MAX_DELTA
Speed Controller Maximum Delta (Applicable for Open Loop Control)
#define PID_K_D
PID Controller Derivative Gain Constant (Only for Closed Loop)
#define SPEED_CONTROLLER_MAX_SPEED
Speed Controller Maximum Speed.
#define SPEED_CONTROLLER_TIME_BASE
Speed Controller Time Base.
#define COMMUTATION_TICKS_STOPPED
Commutation Stopped Limit.
#define PID_K_I
PID Controller Integral Gain Constant (Only for Closed Loop)
#define DEAD_TIME
Dead Time Specification.
Motor control header file.
static void BlockCommutate(const uint8_t direction, uint8_t hall)
Perform block commutation based on direction and hall sensor input.
static uint8_t GetActualDirection(void)
Retrieve the current motor direction.
static uint8_t GetHall(void)
Read the hall sensor inputs and decode the hall state.
static uint8_t GetDesiredDirection(void)
Retrieve the intended motor direction.
static void PortsInit(void)
Initialize I/O port directions and pull-up resistors.
static void TimersSetModeBlockCommutation(void)
Configures timers for block commutation.
static void TimersWaitForNextPWMCycle(void)
Wait for the start of the next PWM cycle.
static void ADCInit(void)
Initializes the ADC.
volatile motorflags_t motorFlags
Motor control flags placed in I/O space for fast access.
static void SpeedController(void)
Speed regulator loop.
static void DisablePWMOutputs(void)
Disable PWM output pins.
volatile uint8_t speedInput
The most recent "speed" input measurement.
static void FatalError(uint8_t code)
Handle a fatal error and enter a fault state.
static void FlagsInit(void)
Initializes motorFlags and faultFlags.
volatile motorconfigs_t motorConfigs
Motor Configs.
static void PinChangeIntInit(void)
Initialize pin change interrupts.
void setup(void)
Main initialization function.
static void PLLInit(void)
Initialize PLL (Phase-Locked Loop)
static void ActualDirectionUpdate(uint8_t lastHall, const uint8_t newHall)
Update the global actual direction flag based on the two latest hall values.
volatile uint16_t current
Current measurement (Register Value).
static void ReverseRotationSignalUpdate(void)
Update the reverse rotation flag.
volatile uint16_t commutationTicks
The number of 'ticks' between two hall sensor changes (counter).
static void CommutationTicksUpdate(void)
Update the 'tick' counter and check for a stopped motor.
static void DesiredDirectionUpdate(void)
Updates global desired direction flag.
volatile uint8_t speedOutput
The most recent "speed" output from the speed controller.
volatile faultflags_t faultFlags
Fault flags placed in I/O space for fast access.
static void SetDuty(const uint16_t duty)
Set duty cycle for TIM4.
static void EnablePWMOutputs(void)
Enable PWM output pins.
volatile uint16_t lastCommutationTicks
The number of 'ticks' between two hall sensor changes (store).
void TimersInit(void)
Initializes and synchronizes Timers.
static void EnableUpdate(void)
Check whether the enable pin is set and update flags accordingly.
static uint16_t ADCSingleConversion(void)
Perform a single ADC conversion.
static void ClearPWMPorts(void)
Clear PWM output ports.
char incoming_byte
Buffer for incoming serial data.
static void ConfigsInit(void)
Initializes motorConfigs.
volatile uint16_t gateVref
Gate voltage measurement (Register Value)
static void RemoteUpdate(void)
Check whether the remote pin is set and update flags accordingly.
void loop()
Main Loop Function.
ISR(INT0_vect)
Enable interrupt service routine.
void PIDInit(int16_t p_factor, int16_t i_factor, int16_t d_factor, pidData_t *pid)
Initialisation of PID controller parameters.
uint16_t PIDController(int16_t setPoint, int16_t processValue, pidData_t *pid_st)
PID control algorithm.
void PIDResetIntegrator(pidData_t *pid_st)
Resets the integrator in the PID regulator.
PID controller header file.
scpi_interface_t scpi_interface
SCPI interface structure.
const scpi_command_t scpi_commands[]
Array of SCPI commands.
scpi_error_t scpi_error_queue_data[4]
SCPI error queue data array.
char scpi_input_buffer[64]
SCPI input buffer.
scpi_t scpi_context
SCPI context structure.
SCPI implementation header file.
#define SCPI_INPUT_BUFFER_LENGTH
#define SCPI_IDN4
The software verion for the identification SCPI query.
#define SCPI_IDN1
The manufacturer's name for the identification SCPI query.
#define SCPI_IDN2
The device's model number for the identification SCPI query.
#define SCPI_IDN3
The device's serial number for the identification SCPI query.
#define SCPI_ERROR_QUEUE_SIZE
The SCPI error queue size or the maximum number of error retained in memory.
Collection of all fault flags.
uint8_t userFlag2
Is user flag 2 set?
uint8_t motorStopped
Is motor stopped?
uint8_t userFlag3
Is user flag 3 set?
uint8_t noHallConnections
Is there no hall connections?
uint8_t overCurrent
Has it tripped the over current limit?
uint8_t reverseDirection
Is motor spinning in an unexpected direction?
uint8_t userFlag1
Is user flag 1 set?
Collection of motor configurations.
uint16_t tim4Top
Corresponding TIM4 top value for TIM4 frequency.
uint8_t speedInputSource
SpeedInput source select (only for remote mode).
uint16_t tim4DeadTime
Corresponding dead time for TIM4 output.
uint32_t tim4Freq
TIM4 or gate switching frequency.
Collection of all motor control flags.
uint8_t desiredDirection
The desired direction of rotation.
uint8_t enable
Is the motor enabled?
uint8_t actualDirection
The actual direction of rotation.
uint8_t driveWaveform
The current waveform that should be produced.
uint8_t remote
Is the remote enabled?
uint8_t speedControllerRun
Should speed controller run?
const uint8_t expectedHallSequenceReverse[7]
Table of Expected Hall Sensor Values in Reverse Direction.
const uint8_t expectedHallSequenceForward[7]
Table of Expected Hall Sensor Values in Forward Direction.
const uint8_t blockCommutationTableReverse[32]
Block Commutation Port Direction Masks for Reverse Driving.
const uint8_t blockCommutationTableForward[32]
Block Commutation Port Direction Masks for Forward Driving.