Motor Evaluation Kit NEVC-MCTRL-100-t01-1.0.0
Firmware for NEVB-MCTRL-100-01 for trapezoidal control of BLDC motors using Hall-effect sensors
Loading...
Searching...
No Matches
main.ino File Reference

Motor control implementation. More...

#include <Arduino.h>
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <stdint.h>
#include "main.h"
#include "tables.h"
#include "fault.h"
#include "scpi.h"
#include "filter.h"
Include dependency graph for main.ino:

Go to the source code of this file.

Macros

#define __AVR_ATmega32U4__   1
 Define macro for ATmega32U4 micro controller.
 

Functions

void setup (void)
 Main initialization function.
 
void loop ()
 Main Loop Function.
 
static void FlagsInit (void)
 Initializes motorFlags and faultFlags.
 
static void ConfigsInit (void)
 Initializes motorConfigs.
 
static void PLLInit (void)
 Initialize PLL (Phase-Locked Loop)
 
static void PortsInit (void)
 Initialize I/O port directions and pull-up resistors.
 
void TimersInit (void)
 Initializes and synchronizes Timers.
 
static void PinChangeIntInit (void)
 Initialize pin change interrupts.
 
static void ADCInit (void)
 Initializes the ADC.
 
static uint16_t ADCSingleConversion (void)
 Perform a single ADC conversion.
 
static void EnableUpdate (void)
 Check whether the enable pin is set and update flags accordingly.
 
static void RemoteUpdate (void)
 Check whether the remote pin is set and update flags accordingly.
 
static void SpeedController (void)
 Speed regulator loop.
 
static void FatalError (uint8_t code)
 Handle a fatal error and enter a fault state.
 
static void SetDuty (const uint16_t duty)
 Set duty cycle for TIM4.
 
static void TimersSetModeBlockCommutation (void)
 Configures timers for block commutation.
 
static void TimersWaitForNextPWMCycle (void)
 Wait for the start of the next PWM cycle.
 
static uint8_t GetDesiredDirection (void)
 Retrieve the intended motor direction.
 
static uint8_t GetActualDirection (void)
 Retrieve the current motor direction.
 
static void BlockCommutate (const uint8_t direction, uint8_t hall)
 Perform block commutation based on direction and hall sensor input.
 
static uint8_t GetHall (void)
 Read the hall sensor inputs and decode the hall state.
 
static void DesiredDirectionUpdate (void)
 Updates global desired direction flag.
 
static void ActualDirectionUpdate (uint8_t lastHall, const uint8_t newHall)
 Update the global actual direction flag based on the two latest hall values.
 
static void ReverseRotationSignalUpdate (void)
 Update the reverse rotation flag.
 
static void EnablePWMOutputs (void)
 Enable PWM output pins.
 
static void DisablePWMOutputs (void)
 Disable PWM output pins.
 
static void ClearPWMPorts (void)
 Clear PWM output ports.
 
static void CommutationTicksUpdate (void)
 Update the 'tick' counter and check for a stopped motor.
 
 ISR (INT0_vect)
 Enable interrupt service routine.
 
 ISR (PCINT0_vect)
 Hall sensor change interrupt service routine.
 
 ISR (INT2_vect)
 Direction input change interrupt service routine.
 
 ISR (TIMER4_OVF_vect)
 Timer4 Overflow Event Interrupt Service Routine.
 
 ISR (TIMER1_OVF_vect)
 Timer1 Overflow Interrupt Service Routine.
 
 ISR (ADC_vect)
 ADC Conversion Complete Interrupt Service Routine.
 

Variables

volatile motorflags_t motorFlags
 Motor control flags placed in I/O space for fast access.
 
volatile faultflags_t faultFlags
 Fault flags placed in I/O space for fast access.
 
volatile motorconfigs_t motorConfigs
 Motor Configs.
 
volatile uint16_t commutationTicks = 0
 The number of 'ticks' between two hall sensor changes (counter).
 
volatile uint16_t lastCommutationTicks = 0xffff
 The number of 'ticks' between two hall sensor changes (store).
 
volatile uint8_t speedInput = 0
 The most recent "speed" input measurement.
 
volatile uint8_t speedOutput = 0
 The most recent "speed" output from the speed controller.
 
volatile uint16_t current = 0
 Current measurement (Register Value).
 
volatile uint16_t gateVref = 0
 Gate voltage measurement (Register Value)
 
char incoming_byte = 0
 Buffer for incoming serial data.
 

Detailed Description

Motor control implementation.

This file contains the full implementation of the motor control, except the PID-controller, filter, fault, SCPI and table implementations and definitions.

User Manual:
ANxxx: Trapezoidal Control of BLDC Motors Using Hall Effect Sensors
Documentation
For comprehensive code documentation, supported compilers, compiler settings and supported devices see readme.html
Author
Nexperia: http://www.nexperia.com
Support Page
For additional support, visit: https://www.nexperia.com/support
Author
Aanas Sayed
Date
2024/03/08


Definition in file main.ino.

Macro Definition Documentation

◆ __AVR_ATmega32U4__

#define __AVR_ATmega32U4__   1

Define macro for ATmega32U4 micro controller.

Definition at line 31 of file main.ino.

Function Documentation

◆ ActualDirectionUpdate()

static void ActualDirectionUpdate ( uint8_t lastHall,
const uint8_t newHall )
static

Update the global actual direction flag based on the two latest hall values.

Calling this function with the last two hall sensor values as parameters triggers an update of the global actualDirection flag.

Parameters
lastHallThe previous hall sensor value.
newHallThe current hall sensor value.

Definition at line 982 of file main.ino.

983{
984 // Ensure that lastHall is within the bounds of the table. If not, set it to
985 // 0, which is also an illegal hall value but a legal table index.
986 if (lastHall > 6)
987 {
988 lastHall = 0;
989 }
990
991 if (pgm_read_byte_near(&expectedHallSequenceForward[lastHall]) == newHall)
992 {
994 }
995 else if (pgm_read_byte_near(&expectedHallSequenceReverse[lastHall]) == newHall)
996 {
998 }
999 else
1000 {
1002 }
1003}
#define DIRECTION_FORWARD
Forward direction flag value.
Definition main.h:575
#define DIRECTION_REVERSE
Reverse direction flag value.
Definition main.h:577
#define DIRECTION_UNKNOWN
Unknown direction flag value.
Definition main.h:579
volatile motorflags_t motorFlags
Motor control flags placed in I/O space for fast access.
Definition main.ino:76
uint8_t actualDirection
The actual direction of rotation.
Definition main.h:987
const uint8_t expectedHallSequenceReverse[7]
Table of Expected Hall Sensor Values in Reverse Direction.
Definition tables.h:163
const uint8_t expectedHallSequenceForward[7]
Table of Expected Hall Sensor Values in Forward Direction.
Definition tables.h:149
Here is the caller graph for this function:

◆ ADCInit()

static void ADCInit ( void )
static

Initializes the ADC.

This function initializes the ADC for speed reference, current and gate voltage measurements.

The function performs self-tests to ensure the ADC's accuracy:

  • It measures 0V to verify the ADC's ability to read close to zero.
  • It measures 1.1V to ensure the ADC's accuracy within a specified range.
  • It measures BREF and waits for any board to be connected.

If any of the self-tests fail, a fatal error is indicated.

After self-testing, the ADC is configured for speed reference measurements and set to trigger on ADC_TRIGGER.

See also
ADC_TRIGGER

Definition at line 481 of file main.ino.

482{
483 // Select initial AD conversion channel [0V for self-test].
484 ADMUX = (ADC_REFERENCE_VOLTAGE | (1 << ADLAR) | ADC_MUX_L_0V);
485 ADCSRB = ADC_MUX_H_0V;
486 _delay_ms(1);
487
488 // Enable ADC
489 ADCSRA = (1 << ADEN);
490
491 // Start ADC single conversion and discard first measurement.
492 uint16_t adc_reading = ADCSingleConversion();
493
494 // Start ADC single conversion to measure 0V, this time it is correct.
495 adc_reading = ADCSingleConversion();
496
497 // Check if ADC can measure 0V within 10mV.
498 if (adc_reading > 2)
499 {
500 FatalError((uint8_t)0b0000111);
501 }
502
503 // Select next AD conversion channel [1V1 for self-test].
504 ADMUX = (ADC_REFERENCE_VOLTAGE | (1 << ADLAR) | ADC_MUX_L_1V1);
505 ADCSRB = ADC_MUX_H_1V1;
506 _delay_ms(1);
507
508 // Start ADC single conversion to measure 1V1.
509 adc_reading = ADCSingleConversion();
510
511 // Check if ADC can measure 1.1V within 1% (1.09 to 1.1V).
512 if ((adc_reading < 223) || (adc_reading > 227))
513 {
514 FatalError((uint8_t)0b0000111);
515 }
516
517 // Select next AD conversion channel [BREF].
518 ADMUX = (ADC_REFERENCE_VOLTAGE | (1 << ADLAR) | ADC_MUX_L_BREF);
519 ADCSRB = ADC_MUX_H_BREF;
520
521 // Enable pull up resistor
522 PORTF |= (1 << PF0);
523
524 _delay_ms(1);
526
527 // Start ADC single conversion to measure BREF.
528 adc_reading = ADCSingleConversion();
529
530 // Wait to check if any board is connected. Should be anything other than
531 // 0x3ff if any board is connected assuming BREF of the board is not equal to
532 // IOREF.
533 while (adc_reading == 0x3ff)
534 {
536
537 // Start ADC single conversion to measure BREF.
538 adc_reading = ADCSingleConversion();
539 }
540
541 // Disable pull up resistor
542 PORTF &= ~(1 << PF0);
543
544 // Re-initialize ADC mux channel select.
545 ADMUX &= ~ADC_MUX_L_BITS;
546 ADMUX |= ADC_MUX_L_SPEED;
547 // Set trigger source to ADC_TRIGGER.
548 ADCSRB = ADC_MUX_H_SPEED | ADC_TRIGGER;
549
550 // Re-initialize ADC to work with interrupts.
551 ADCSRA = (1 << ADEN) | (1 << ADSC) | (1 << ADATE) | (1 << ADIF) | (1 << ADIE) | ADC_PRESCALER;
552}
void SweepLEDsBlocking(void)
Sweeps through all LEDs individually with a delay.
Definition fault.cpp:144
#define ADC_MUX_H_1V1
High ADC channel selection bit (MUX5) - 1.1V (Vbandgap).
Definition main.h:898
#define ADC_MUX_H_0V
High ADC channel selection bit (MUX5) - 0V (GND).
Definition main.h:902
#define ADC_MUX_L_1V1
Lower ADC channel selection bits (MUX4:0) - 1.1V (Vbandgap).
Definition main.h:896
#define ADC_MUX_L_0V
Lower ADC channel selection bits (MUX4:0) - 0V (GND).
Definition main.h:900
#define ADC_MUX_L_BREF
Lower analog channel selection bits (MUX4:0) for motor bref measurement.
Definition main.h:607
#define ADC_MUX_L_SPEED
Definition main.h:594
#define ADC_TRIGGER
ADC trigger used in this application.
Definition main.h:617
#define ADC_MUX_H_BREF
High analog channel selection bit (MUX5) for for motor bref measurement.
Definition main.h:609
#define ADC_PRESCALER
ADC clock pre-scaler used in this application.
Definition main.h:613
#define ADC_MUX_H_SPEED
Definition main.h:597
#define ADC_REFERENCE_VOLTAGE
ADC voltage reference used in this application.
Definition main.h:615
static void FatalError(uint8_t code)
Handle a fatal error and enter a fault state.
Definition main.ino:728
static uint16_t ADCSingleConversion(void)
Perform a single ADC conversion.
Definition main.ino:561
Here is the call graph for this function:
Here is the caller graph for this function:

◆ ADCSingleConversion()

static uint16_t ADCSingleConversion ( void )
static

Perform a single ADC conversion.

This function initiates a single ADC conversion to measure a voltage. It waits for the conversion to complete and then reads the ADC result.

Returns
The 16-bit ADC result representing the measured voltage.

Definition at line 561 of file main.ino.

562{
563 // Initialize ADC for one-time conversion.
564 ADCSRA |= (1 << ADSC);
565
566 // Wait for the conversion to complete.
567 while (ADCSRA & (1 << ADSC))
568 {
569 // Wait until the conversion is finished.
570 }
571
572 // Read the ADC result and combine ADCH and ADCL into a 16-bit value.
573 uint16_t value = (ADCL >> 6);
574 value |= 0x3ff & (ADCH << 2);
575
576 return value;
577}
Here is the caller graph for this function:

◆ BlockCommutate()

static void BlockCommutate ( const uint8_t direction,
uint8_t hall )
static

Perform block commutation based on direction and hall sensor input.

This function performs block commutation according to the specified direction of rotation and the hall sensor input. Block commutation is used to control motor phases during operation.

Parameters
directionDirection of rotation (DIRECTION_FORWARD or DIRECTION_REVERSE).
hallHall sensor input value corresponding to the rotor position.

Definition at line 908 of file main.ino.

909{
910 const uint8_t *tableAddress;
911
912 if (direction == DIRECTION_FORWARD)
913 {
914 tableAddress = blockCommutationTableForward;
915 }
916 else
917 {
918 tableAddress = blockCommutationTableReverse;
919 }
920 tableAddress += (hall * 4);
921
923 TCCR4E &= ~0b00111111;
924
926
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);
931
933}
static void DisablePWMOutputs(void)
Disable PWM output pins.
Definition main.ino:1041
static void EnablePWMOutputs(void)
Enable PWM output pins.
Definition main.ino:1028
static void ClearPWMPorts(void)
Clear PWM output ports.
Definition main.ino:1054
const uint8_t blockCommutationTableReverse[32]
Block Commutation Port Direction Masks for Reverse Driving.
Definition tables.h:128
const uint8_t blockCommutationTableForward[32]
Block Commutation Port Direction Masks for Forward Driving.
Definition tables.h:80
Here is the call graph for this function:
Here is the caller graph for this function:

◆ ClearPWMPorts()

static void ClearPWMPorts ( void )
static

Clear PWM output ports.

This function clears the PWM output ports by setting the corresponding bits of the port registers to low. It effectively turns off the PWM signals on the specified ports while leaving the port directions unchanged.

Definition at line 1054 of file main.ino.

1055{
1056 PORTB &= ~PWM_PATTERN_PORTB;
1057 PORTC &= ~PWM_PATTERN_PORTC;
1058 PORTD &= ~PWM_PATTERN_PORTD;
1059}
Here is the caller graph for this function:

◆ CommutationTicksUpdate()

static void CommutationTicksUpdate ( void )
static

Update the 'tick' counter and check for a stopped motor.

This function should be called at every PWM timer overflow to update the 'tick' counter. It increments the 'tick' counter until it reaches the maximum tick limit, indicating a potentially stopped or stalled motor. If the limit is reached, the global motor stopped flag is set.

Note
This function can be used to detect a stalled motor and take appropriate actions.
If the motor is determined to be stopped, it may change the motor drive waveform and disable PWM outputs as necessary.
See also
COMMUTATION_TICKS_STOPPED, TURN_OFF_MODE

Definition at line 1076 of file main.ino.

1077{
1079 {
1081 }
1082 else
1083 {
1085 lastCommutationTicks = 0xffff;
1086 uint8_t hall = GetHall();
1087 if ((hall == 0) || (hall == 0b111))
1088 {
1090 }
1092 {
1093 speedOutput = 0;
1094#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
1095 PIDResetIntegrator(&pidParameters);
1096#endif
1099 }
1100#if (TURN_OFF_MODE == TURN_OFF_MODE_BRAKE)
1101 else if (motorFlags.enable == FALSE)
1102 {
1105 ClearPWMPorts();
1106 }
1107#endif
1108 }
1109}
#define WAVEFORM_BLOCK_COMMUTATION
Waveform constant for block commutation.
Definition main.h:643
#define WAVEFORM_UNDEFINED
Waveform status flag used for coasting.
Definition main.h:647
#define TRUE
TRUE constant value, defined to be compatible with comparisons.
Definition main.h:537
#define FALSE
FALSE constant value.
Definition main.h:535
#define COMMUTATION_TICKS_STOPPED
Commutation Stopped Limit.
Definition main.h:188
static void BlockCommutate(const uint8_t direction, uint8_t hall)
Perform block commutation based on direction and hall sensor input.
Definition main.ino:908
static uint8_t GetHall(void)
Read the hall sensor inputs and decode the hall state.
Definition main.ino:946
static uint8_t GetDesiredDirection(void)
Retrieve the intended motor direction.
Definition main.ino:873
static void TimersSetModeBlockCommutation(void)
Configures timers for block commutation.
Definition main.ino:779
volatile uint16_t commutationTicks
The number of 'ticks' between two hall sensor changes (counter).
Definition main.ino:105
volatile uint8_t speedOutput
The most recent "speed" output from the speed controller.
Definition main.ino:132
volatile faultflags_t faultFlags
Fault flags placed in I/O space for fast access.
Definition main.ino:84
volatile uint16_t lastCommutationTicks
The number of 'ticks' between two hall sensor changes (store).
Definition main.ino:118
void PIDResetIntegrator(pidData_t *pid_st)
Resets the integrator in the PID regulator.
Definition pid.cpp:130
uint8_t motorStopped
Is motor stopped?
Definition main.h:1005
uint8_t noHallConnections
Is there no hall connections?
Definition main.h:1009
uint8_t enable
Is the motor enabled?
Definition main.h:985
uint8_t driveWaveform
The current waveform that should be produced.
Definition main.h:991
Here is the call graph for this function:
Here is the caller graph for this function:

◆ ConfigsInit()

static void ConfigsInit ( void )
static

Initializes motorConfigs.

This function initializes motorConfigs to their default values.

Definition at line 320 of file main.ino.

321{
322 motorConfigs.tim4Freq = (uint32_t)TIM4_FREQ;
326}
#define TIM4_TOP(tim4Freq)
Definition main.h:1059
#define SPEED_INPUT_SOURCE_LOCAL
Speed input source - Local or speed input pin.
Definition main.h:629
#define TIM4_FREQ
Desired Switching Frequency for MOSFET Gate Signals.
Definition main.h:99
#define DEAD_TIME
Dead Time Specification.
Definition main.h:128
volatile motorconfigs_t motorConfigs
Motor Configs.
Definition main.ino:90
uint16_t tim4Top
Corresponding TIM4 top value for TIM4 frequency.
Definition main.h:1028
uint8_t speedInputSource
SpeedInput source select (only for remote mode).
Definition main.h:1032
uint16_t tim4DeadTime
Corresponding dead time for TIM4 output.
Definition main.h:1030
uint32_t tim4Freq
TIM4 or gate switching frequency.
Definition main.h:1026
Here is the caller graph for this function:

◆ DesiredDirectionUpdate()

static void DesiredDirectionUpdate ( void )
static

Updates global desired direction flag.

Running this function triggers a reading of the direction input pin. The desiredDirection flag is set accordingly.

Definition at line 961 of file main.ino.

962{
963 if ((PIND & (1 << DIRECTION_COMMAND_PIN)) != 0)
964 {
966 }
967 else
968 {
970 }
971}
#define DIRECTION_COMMAND_PIN
Pin where direction command input is located.
Definition main.h:621
uint8_t desiredDirection
The desired direction of rotation.
Definition main.h:989
Here is the caller graph for this function:

◆ DisablePWMOutputs()

static void DisablePWMOutputs ( void )
static

Disable PWM output pins.

This function disables PWM outputs by setting the port direction for all PWM pins as inputs. This action overrides the PWM signals, effectively stopping the generation of PWM. The PWM configuration itself remains unchanged.

Definition at line 1041 of file main.ino.

1042{
1043 DDRB &= ~PWM_PATTERN_PORTB;
1044 DDRC &= ~PWM_PATTERN_PORTC;
1045 DDRD &= ~PWM_PATTERN_PORTD;
1046}
Here is the caller graph for this function:

◆ EnablePWMOutputs()

static void EnablePWMOutputs ( void )
static

Enable PWM output pins.

This function sets the port direction for all PWM pins as output, allowing PWM signals to be generated on these pins. It does not modify the PWM configuration itself.

Definition at line 1028 of file main.ino.

1029{
1030 DDRB |= PWM_PATTERN_PORTB;
1031 DDRC |= PWM_PATTERN_PORTC;
1032 DDRD |= PWM_PATTERN_PORTD;
1033}
#define PWM_PATTERN_PORTC
Bit pattern of PWM pins placed on PORTC (Phase B).
Definition main.h:560
#define PWM_PATTERN_PORTB
Bit pattern of PWM pins placed on PORTB (Phase A).
Definition main.h:558
#define PWM_PATTERN_PORTD
Bit pattern of PWM pins placed on PORTD (Phase C).
Definition main.h:562
Here is the caller graph for this function:

◆ EnableUpdate()

static void EnableUpdate ( void )
static

Check whether the enable pin is set and update flags accordingly.

This function checks the state of the enable pin and updates the motorFlags and faultFlags accordingly. If the enable pin is not set, it can perform specific actions based on the TURN_OFF_MODE configuration:

Note
The behavior of this function depends on the TURN_OFF_MODE configuration.
See also
TURN_OFF_MODE, TimersSetModeBrake()

Definition at line 594 of file main.ino.

595{
596 if ((PIND & (1 << ENABLE_PIN)) != 0)
597 {
599 }
600 else
601 {
603
604#if (TURN_OFF_MODE == TURN_OFF_MODE_COAST)
605 // Disable driver signals to let the motor coast.
610#endif
611
612#if (TURN_OFF_MODE == TURN_OFF_MODE_BRAKE)
613 // Set the motor in brake mode.
615 TimersSetModeBrake();
616#endif
617 }
618}
#define ENABLE_PIN
Enable input pin.
Definition main.h:623
Here is the call graph for this function:
Here is the caller graph for this function:

◆ FatalError()

static void FatalError ( uint8_t code)
static

Handle a fatal error and enter a fault state.

This function is called in response to a fatal error condition. It performs the following actions:

  • Detaches all interrupts to prevent further operation.
  • Disables PWM outputs.
  • Sets fault flags based on the provided error code.
  • Enters a loop, continuously executing the fault sequential state machine and delaying for 2 milliseconds between each iteration.
Parameters
codeThe error code indicating the nature of the fatal error. Each bit of the code corresponds to a specific fault condition: - Bit 0: User Flag 3 - Bit 1: User Flag 2 - Bit 2: User Flag 1 - Bit 3: Reverse Direction - Bit 4: Motor Stopped - Bit 5: Over Current - Bit 6: No Hall Connections

Definition at line 728 of file main.ino.

729{
730 // Detach all interrupts
731 cli();
732
733 // Disable outputs
735
736 // Set faultFlags based on the provided error code
737 faultFlags.userFlag3 = (code & 0x01) != 0;
738 faultFlags.userFlag2 = (code & 0x02) != 0;
739 faultFlags.userFlag1 = (code & 0x04) != 0;
740 faultFlags.reverseDirection = (code & 0x08) != 0;
741 faultFlags.motorStopped = (code & 0x10) != 0;
742 faultFlags.overCurrent = (code & 0x20) != 0;
743 faultFlags.noHallConnections = (code & 0x40) != 0;
744
745 // loop forever
746 while (1)
747 {
749 _delay_ms(2);
750 }
751}
void faultSequentialStateMachine(volatile faultflags_t *faultFlags, volatile motorflags_t *motorFlags)
Sequential State Machine for Handling Fault Flags.
Definition fault.cpp:181
uint8_t userFlag2
Is user flag 2 set?
Definition main.h:1013
uint8_t userFlag3
Is user flag 3 set?
Definition main.h:1015
uint8_t overCurrent
Has it tripped the over current limit?
Definition main.h:1007
uint8_t reverseDirection
Is motor spinning in an unexpected direction?
Definition main.h:1003
uint8_t userFlag1
Is user flag 1 set?
Definition main.h:1011
Here is the call graph for this function:
Here is the caller graph for this function:

◆ FlagsInit()

static void FlagsInit ( void )
static

Initializes motorFlags and faultFlags.

This function initializes both motorFlags and faultFlags to their default values.

Definition at line 294 of file main.ino.

295{
296 // Initialize motorFlags with default values.
303
304 // Initialize faultFlags with default values. Set motorStopped to FALSE at
305 // startup. This will make sure that the motor is not started if it is not
306 // really stopped. If it is stopped, this variable will quickly be updated.
314}
uint8_t remote
Is the remote enabled?
Definition main.h:983
uint8_t speedControllerRun
Should speed controller run?
Definition main.h:981
Here is the caller graph for this function:

◆ GetActualDirection()

static uint8_t GetActualDirection ( void )
static

Retrieve the current motor direction.

This function returns the current operating direction of the motor.

Note
To accurately determine the direction, two consecutive hall sensor changes in the same direction are required.
Returns
The current motor direction.
Return values
DIRECTION_FORWARDMotor is currently running forward.
DIRECTION_REVERSEMotor is currently running in reverse.
DIRECTION_UNKNOWNThe current motor direction cannot be determined, which may indicate the motor is stopped, changing direction, or that the hall sensors are providing incorrect information.

Definition at line 893 of file main.ino.

894{
896}
Here is the caller graph for this function:

◆ GetDesiredDirection()

static uint8_t GetDesiredDirection ( void )
static

Retrieve the intended motor direction.

This function provides the current intended direction for the motor.

Note
The direction input is not directly read at this point. Instead, a separate pin change interrupt is responsible for monitoring the input.
Return values
DIRECTION_FORWARDForward direction is the intended direction.
DIRECTION_REVERSEReverse direction is the intended direction.

Definition at line 873 of file main.ino.

874{
875 return (uint8_t)motorFlags.desiredDirection;
876}
Here is the caller graph for this function:

◆ GetHall()

static uint8_t GetHall ( void )
static

Read the hall sensor inputs and decode the hall state.

This function reads the hall sensor inputs and converts them into a number ranging from 1 to 6, where the hall sensors' states are represented as bits: H3|H2|H1.

Returns
The decoded hall sensor value.
Return values
0Illegal hall state. Possible hardware error.
1-6Valid hall sensor values.
7Illegal hall state. Possible hardware error.

Definition at line 946 of file main.ino.

947{
948 uint8_t hall;
949
950 hall = HALL_PIN & ((1 << H3_PIN) | (1 << H2_PIN) | (1 << H1_PIN));
951 hall >>= H1_PIN;
952
953 return hall;
954}
#define H2_PIN
Pin where H2 is connected.
Definition main.h:587
#define HALL_PIN
PIN register for Hall sensor input.
Definition main.h:583
#define H3_PIN
Pin where H3 is connected.
Definition main.h:589
#define H1_PIN
Pin where H1 is connected.
Definition main.h:585
Here is the caller graph for this function:

◆ ISR() [1/6]

ISR ( ADC_vect )

ADC Conversion Complete Interrupt Service Routine.

This interrupt service routine is automatically executed every time an AD conversion is finished, and the converted result is available in the ADC data register.

The switch/case construct ensures that the converted value is stored in the variable corresponding to the selected channel and changes the channel for the next ADC measurement.

Additional ADC measurements can be added to the cycle by extending the switch/case construct.

Definition at line 1292 of file main.ino.

1293{
1294 switch ((ADMUX & ADC_MUX_L_BITS) | (ADCSRB & ADC_MUX_H_BITS))
1295 {
1297 // Handle ADC conversion result for speed measurement.
1299 {
1300 speedInput = ADCH;
1301 }
1302 ADMUX &= ~ADC_MUX_L_BITS;
1303 ADMUX |= ADC_MUX_L_CURRENT;
1304 ADCSRB &= ~ADC_MUX_H_BITS;
1305 ADCSRB |= ADC_MUX_H_CURRENT;
1306 break;
1308 // Handle ADC conversion result for current measurement.
1309 current = ADCL >> 6;
1310 current |= (ADCH << 2);
1311 ADMUX &= ~ADC_MUX_L_BITS;
1312 ADMUX |= ADC_MUX_L_GATEVREF;
1313 ADCSRB &= ~ADC_MUX_H_BITS;
1314 ADCSRB |= ADC_MUX_H_GATEVREF;
1315
1316 // Check for over current conditions and set fault flags.
1318 {
1319 FatalError((uint8_t)0b0100111);
1320 }
1322 {
1324 }
1325 else
1326 {
1328 }
1329 break;
1331 // Handle ADC conversion result for gate voltage reference measurement.
1332 gateVref = ADCL >> 6;
1333 gateVref |= (ADCH << 2);
1334 ADMUX &= ~ADC_MUX_L_BITS;
1335 ADMUX |= ADC_MUX_L_SPEED;
1336 ADCSRB &= ~ADC_MUX_H_BITS;
1337 ADCSRB |= ADC_MUX_H_SPEED;
1338 break;
1339 default:
1340 // This is probably an error and should be handled.
1341 FatalError((uint8_t)0b0000111);
1342 break;
1343 }
1344
1345 // Clear Timer/Counter0 overflow flag.
1346 TIFR0 = (1 << TOV0);
1347}
#define ADC_MUX_H_BITS
High ADC channel selection bit (MUX5) mask.
Definition main.h:842
#define ADC_MUX_L_BITS
Lower ADC channel selection bits (MUX4:0) mask.
Definition main.h:840
#define ADC_MUX_L_CURRENT
Lower analog channel selection bits (MUX4:0) for motor current measurement.
Definition main.h:599
#define ADC_MUX_H_GATEVREF
High analog channel selection bit (MUX5) for for motor gateVref measurement.
Definition main.h:605
#define ADC_MUX_H_CURRENT
High analog channel selection bit (MUX5) for for motor current measurement.
Definition main.h:601
#define ADC_MUX_L_GATEVREF
Lower analog channel selection bits (MUX4:0) for motor gateVref measurement.
Definition main.h:603
#define CURRENT_WARNING_THRESHOLD
Current Warning Threshold (Register Value)
Definition main.h:273
#define CURRENT_ERROR_THRESHOLD
Current Error Threshold (Register Value)
Definition main.h:312
volatile uint8_t speedInput
The most recent "speed" input measurement.
Definition main.ino:125
volatile uint16_t current
Current measurement (Register Value).
Definition main.ino:161
volatile uint16_t gateVref
Gate voltage measurement (Register Value)
Definition main.ino:190
Here is the call graph for this function:

◆ ISR() [2/6]

ISR ( INT0_vect )

Enable interrupt service routine.

This interrupt service routine is called if the enable pin changes state.

Definition at line 1115 of file main.ino.

1116{
1117 EnableUpdate();
1118}
static void EnableUpdate(void)
Check whether the enable pin is set and update flags accordingly.
Definition main.ino:594
Here is the call graph for this function:

◆ ISR() [3/6]

ISR ( INT2_vect )

Direction input change interrupt service routine.

This interrupt service routine is called every time the direction input pin changes state. The desired direction flag is updated accordingly. The motor control then goes into a state where it needs a stopped motor before any driving of the motor is performed.

Note
Depending on the TURN_OFF_MODE configuration, it will either coast or brake.
See also
TURN_OFF_MODE

Definition at line 1168 of file main.ino.

1169{
1170 // Update desired direction flag.
1173 {
1174 }
1176 {
1177 };
1178
1179#if (TURN_OFF_MODE == TURN_OFF_MODE_COAST)
1180 // Disable driver signals to let motor coast. The motor will automatically
1181 // start once it stopped.
1184 ClearPWMPorts();
1186#endif
1187
1188#if (TURN_OFF_MODE == TURN_OFF_MODE_BRAKE)
1189 // Set motor in brake mode. The motor will automatically start once it is
1190 // stopped.
1192 TimersSetModeBrake(); // Automatically sets driveWaveform.
1193#endif
1194}
static void DesiredDirectionUpdate(void)
Updates global desired direction flag.
Definition main.ino:961
Here is the call graph for this function:

◆ ISR() [4/6]

ISR ( PCINT0_vect )

Hall sensor change interrupt service routine.

This interrupt service routine is called every time any of the hall sensors change. The actual direction, the reverse rotation and no hall connections flags are updated.

The motor stopped flag is also set to FALSE, since the motor is obviously not stopped when there is a hall change.

Definition at line 1129 of file main.ino.

1130{
1131 static uint8_t lastHall = 0xff;
1132 uint8_t hall;
1133
1134 hall = GetHall();
1135
1137 {
1139 }
1140
1141 // Update flags that depend on hall sensor value.
1142 ActualDirectionUpdate(lastHall, hall);
1144
1145 lastHall = hall;
1146
1147 // Reset commutation timer.
1149 commutationTicks = 0;
1150
1151 // Since the hall sensors are changing, the motor can not be stopped.
1154}
int16_t calculateEMA(uint16_t currentSample, uint16_t previousEMA, uint8_t alphaExponent)
Exponential Moving Average (EMA) calculation algorithm.
Definition filter.cpp:34
static void ActualDirectionUpdate(uint8_t lastHall, const uint8_t newHall)
Update the global actual direction flag based on the two latest hall values.
Definition main.ino:982
static void ReverseRotationSignalUpdate(void)
Update the reverse rotation flag.
Definition main.ino:1010
Here is the call graph for this function:

◆ ISR() [5/6]

ISR ( TIMER1_OVF_vect )

Timer1 Overflow Interrupt Service Routine.

This interrupt service routine (ISR) is triggered on Timer1 overflow. It calls the faultSequentialStateMachine() function to handle motor fault reporting.

See also
faultSequentialStateMachine()

Definition at line 1273 of file main.ino.

Here is the call graph for this function:

◆ ISR() [6/6]

ISR ( TIMER4_OVF_vect )

Timer4 Overflow Event Interrupt Service Routine.

This interrupt service routine is trigger on Timer4 overflow. It manages the commutation ticks, which determines motor status. It also controls the execution of the speed regulation loop at constant intervals.

Definition at line 1202 of file main.ino.

1203{
1205 {
1206 uint16_t dutyCycle = ((uint32_t)speedOutput * motorConfigs.tim4Top) >> 7;
1207
1208 if (dutyCycle > (uint16_t)(motorConfigs.tim4Top << 1))
1209 {
1210 dutyCycle = (uint16_t)(motorConfigs.tim4Top << 1);
1211 }
1212
1213 SetDuty(dutyCycle);
1214 }
1215
1217
1218 {
1219 // Run the speed regulation loop with constant intervals.
1220 static uint8_t speedRegTicks = 0;
1221 speedRegTicks++;
1222 if (speedRegTicks >= SPEED_CONTROLLER_TIME_BASE)
1223 {
1225 speedRegTicks -= SPEED_CONTROLLER_TIME_BASE;
1226 }
1227 }
1228}
#define SPEED_CONTROLLER_TIME_BASE
Speed Controller Time Base.
Definition main.h:354
static void CommutationTicksUpdate(void)
Update the 'tick' counter and check for a stopped motor.
Definition main.ino:1076
static void SetDuty(const uint16_t duty)
Set duty cycle for TIM4.
Definition main.ino:761
Here is the call graph for this function:

◆ loop()

void loop ( )

Main Loop Function.

The main loop function is executed continuously in normal operation after the program has configured everything. It continually checks if the speed controller needs to be run.

Definition at line 271 of file main.ino.

272{
273 if (motorFlags.remote == TRUE)
274 {
275 // send data to SCPI parser only when you receive data:
276 if (Serial.available() > 0)
277 {
278 incoming_byte = Serial.read();
279 SCPI_Input(&scpi_context, &incoming_byte, 1);
280 }
281 }
283 {
286 }
287}
static void SpeedController(void)
Speed regulator loop.
Definition main.ino:664
char incoming_byte
Buffer for incoming serial data.
Definition main.ino:199
scpi_t scpi_context
SCPI context structure.
Definition scpi.cpp:681
Here is the call graph for this function:

◆ PinChangeIntInit()

static void PinChangeIntInit ( void )
static

Initialize pin change interrupts.

This function initializes pin change interrupt on hall sensor input pins input, shutdown input and motor direction control input.

Definition at line 450 of file main.ino.

451{
452 // Initialize external interrupt on shutdown pin (INT0) and direction input
453 // (INT2) pin.
454 EICRA = (0 << ISC21) | (1 << ISC20) | (0 << ISC01) | (1 << ISC00);
455 EIMSK = (1 << INT2) | (1 << INT0);
456
457 // Initialize pin change interrupt on hall sensor inputs (PCINT1..3).
458 PCMSK0 = (1 << PCINT3) | (1 << PCINT2) | (1 << PCINT1);
459
460 // Enable pin change interrupt on ports with pin change signals
461 PCICR = (1 << PCIE0);
462}
Here is the caller graph for this function:

◆ PLLInit()

static void PLLInit ( void )
static

Initialize PLL (Phase-Locked Loop)

This function configures and initializes the PLL for clock generation. It sets the PLL frequency control register and waits until the PLL is locked and stable before returning.

Definition at line 335 of file main.ino.

336{
337 // Configure PLL Frequency Control Register to output 48MHz for USB Module and
338 // 64MHz for the High-Speed Clock Timer with a base speed of 96MHz for PLL
339 // Output Frequency.
340
341 PLLFRQ = (0 << PINMUX) | (1 << PLLUSB) | PLL_POSTSCALER_DIV_1_5 | (1 << PDIV3) | (0 << PDIV2) | (1 << PDIV1) | (0 << PDIV0);
342
343 // Enable PLL.
344 PLLCSR = (1 << PINDIV) | (1 << PLLE);
345
346 // Wait until PLOCK bit is set, indicating PLL is locked and stable.
347 while ((PLLCSR & (1 << PLOCK)) == 0)
348 {
349 // Wait for PLL lock
350 ;
351 }
352}
#define PLL_POSTSCALER_DIV_1_5
PLL Post-scaler - division factor 1.5.
Definition main.h:770
Here is the caller graph for this function:

◆ PortsInit()

static void PortsInit ( void )
static

Initialize I/O port directions and pull-up resistors.

This function initializes all I/O ports with the correct directions and enables pull-up resistors, if needed, for various pins and signals used in the motor control.

Definition at line 361 of file main.ino.

362{
363#if (EMULATE_HALL == TRUE)
364 // Configure and set hall sensor pins for motor emulation
365 PORTB &= ~((1 << H1_PIN) | (1 << H2_PIN) | (1 << H3_PIN));
366 PORTB |= (0x07 & pgm_read_byte_near(&expectedHallSequenceForward[1]));
367 // Set hall sensor pins as outputs.
368 DDRB |= (1 << H1_PIN) | (1 << H2_PIN) | (1 << H3_PIN);
369#endif
370
371#if ((HALL_PULLUP_ENABLE == TRUE) && (EMULATE_HALL != TRUE))
372 // Configure and set hall sensor pins as input with pull-ups enabled
373 PORTB |= (1 << H1_PIN) | (1 << H2_PIN) | (1 << H3_PIN);
374#endif
375
376 // Configure and set pins FAULT_PIN_3, FAULT_PIN_2, and FAULT_PIN_1 as outputs
377 PORTB &= ~((1 << FAULT_PIN_3) | (1 << FAULT_PIN_2));
378 DDRB |= (1 << FAULT_PIN_3) | (1 << FAULT_PIN_2);
379 PORTD &= ~(1 << FAULT_PIN_1);
380 DDRD |= (1 << FAULT_PIN_1);
381
382 // If remote mode, set enable and direction pin as output to allow software
383 // triggered interrupts
384 if (motorFlags.remote == TRUE)
385 {
386 PORTD &= ~((1 << ENABLE_PIN) | (1 << DIRECTION_COMMAND_PIN));
387 DDRD |= (1 << ENABLE_PIN) | (1 << DIRECTION_COMMAND_PIN);
388 }
389}
#define FAULT_PIN_2
Fault Pin 2.
Definition main.h:637
#define FAULT_PIN_3
Fault Pin 3.
Definition main.h:639
#define FAULT_PIN_1
Fault Pin 1.
Definition main.h:635
Here is the caller graph for this function:

◆ RemoteUpdate()

static void RemoteUpdate ( void )
static

Check whether the remote pin is set and update flags accordingly.

This function checks the state of the remote pin and updates the motorFlags.

Note
This is only called during setup so any further pin changes are not detected.

Definition at line 627 of file main.ino.

628{
629 if ((PIND & (1 << REMOTE_PIN)) != 0)
630 {
632 }
633 else
634 {
636 }
637}
#define REMOTE_PIN
Remote input pin.
Definition main.h:625
Here is the caller graph for this function:

◆ ReverseRotationSignalUpdate()

static void ReverseRotationSignalUpdate ( void )
static

Update the reverse rotation flag.

This function compares the actual and desired direction flags to determine if the motor is running in the opposite direction of what is requested.

Definition at line 1010 of file main.ino.

1011{
1013 {
1015 }
1016 else
1017 {
1019 }
1020}
static uint8_t GetActualDirection(void)
Retrieve the current motor direction.
Definition main.ino:893
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetDuty()

static void SetDuty ( const uint16_t duty)
static

Set duty cycle for TIM4.

This function sets the duty cycle for block commutation, where the duty range is 0-1023 (not in percentage). To convert to percentage, use: duty * 100 / 1023.

Parameters
dutyNew duty cycle, range 0-1023.

Definition at line 761 of file main.ino.

762{
763 TC4H = duty >> 8;
764 OCR4A = 0xFF & duty;
765}
Here is the caller graph for this function:

◆ setup()

void setup ( void )

Main initialization function.

The main initialization function initializes all subsystems needed for motor control.

Definition at line 211 of file main.ino.

212{
213 // Load motor configs
214 ConfigsInit();
215
216 // Initialize flags.
217 FlagsInit();
218
219 // Check if remote mode requested.
220 RemoteUpdate();
221
222 // Initialize peripherals.
223 PortsInit(); // depends on motorFlags.remote
224 ADCInit(); // include self-test + loop until board detected must be before TimersInit
225 PLLInit();
226 TimersInit();
227
228#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
229 PIDInit(PID_K_P, PID_K_I, PID_K_D, &pidParameters);
230#endif
231
232 if (motorFlags.remote == TRUE)
233 {
234 // Start serial interface with 115200 bauds.
235 Serial.begin(115200);
236 // while (!Serial); // wait for serial to finish initializing
237
238 // Initialise SCPI subsystem if remote mode.
239 SCPI_Init(&scpi_context,
242 scpi_units_def,
246 }
247 else
248 {
249 // Update direction before enable flag.
251 // Do not update enable flag until everything is ready.
252 EnableUpdate();
253 }
254
255 // Set up pin change interrupts.
257
258 // Enable Timer4 overflow event interrupt.
259 TIMSK4 |= (1 << TOIE4);
260
261 // Enable interrupts globally and let motor driver take over.
262 sei();
263}
#define PID_K_P
PID Controller Proportional Gain Constant (Only for Closed Loop)
Definition main.h:415
#define PID_K_D
PID Controller Derivative Gain Constant (Only for Closed Loop)
Definition main.h:472
#define PID_K_I
PID Controller Integral Gain Constant (Only for Closed Loop)
Definition main.h:434
static void PortsInit(void)
Initialize I/O port directions and pull-up resistors.
Definition main.ino:361
static void ADCInit(void)
Initializes the ADC.
Definition main.ino:481
static void FlagsInit(void)
Initializes motorFlags and faultFlags.
Definition main.ino:294
static void PinChangeIntInit(void)
Initialize pin change interrupts.
Definition main.ino:450
static void PLLInit(void)
Initialize PLL (Phase-Locked Loop)
Definition main.ino:335
void TimersInit(void)
Initializes and synchronizes Timers.
Definition main.ino:405
static void ConfigsInit(void)
Initializes motorConfigs.
Definition main.ino:320
static void RemoteUpdate(void)
Check whether the remote pin is set and update flags accordingly.
Definition main.ino:627
void PIDInit(int16_t p_factor, int16_t i_factor, int16_t d_factor, pidData_t *pid)
Initialisation of PID controller parameters.
Definition pid.cpp:31
scpi_interface_t scpi_interface
SCPI interface structure.
Definition scpi.cpp:651
const scpi_command_t scpi_commands[]
Array of SCPI commands.
Definition scpi.cpp:504
scpi_error_t scpi_error_queue_data[4]
SCPI error queue data array.
Definition scpi.cpp:673
char scpi_input_buffer[64]
SCPI input buffer.
Definition scpi.cpp:665
#define SCPI_INPUT_BUFFER_LENGTH
Definition scpi.h:47
#define SCPI_IDN4
The software verion for the identification SCPI query.
Definition scpi.h:59
#define SCPI_IDN1
The manufacturer's name for the identification SCPI query.
Definition scpi.h:53
#define SCPI_IDN2
The device's model number for the identification SCPI query.
Definition scpi.h:55
#define SCPI_IDN3
The device's serial number for the identification SCPI query.
Definition scpi.h:57
#define SCPI_ERROR_QUEUE_SIZE
The SCPI error queue size or the maximum number of error retained in memory.
Definition scpi.h:50
Here is the call graph for this function:

◆ SpeedController()

static void SpeedController ( void )
static

Speed regulator loop.

This function is called periodically every SPEED_CONTROLLER_TIME_BASE ticks. In this implementation, a simple PID controller loop is called, but this function could be replaced by any speed or other regulator.

If the SPEED_CONTROL_METHOD is set to SPEED_CONTROL_CLOSED_LOOP, a PID controller is used to regulate the speed. The speed input is converted into an increment set point, and a PID controller computes the output value. The output is limited to a maximum value of 255.

If the SPEED_CONTROL_METHOD is not set to SPEED_CONTROL_CLOSED_LOOP, a simple speed control mechanism is applied. If the motor is enabled, the function calculates the delta between the speed input and the current speed output. If the delta exceeds the maximum allowed change, it limits the change to SPEED_CONTROLLER_MAX_DELTA. If the motor is disabled, the speed output is set to 0.

Note
The behavior of this function depends on the SPEED_CONTROL_METHOD configuration.
See also
SPEED_CONTROL_METHOD, SPEED_CONTROLLER_TIME_BASE, SPEED_CONTROLLER_MAX_DELTA, SPEED_CONTROLLER_MAX_SPEED, PID_K_P, PID_K_I, PID_K_D_ENABLE, PID_K_D

Definition at line 664 of file main.ino.

665{
666 if (motorFlags.enable == TRUE)
667 {
668#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
669 // Calculate an increment set point from the analog speed input.
670 int16_t incrementSetpoint = ((int32_t)speedInput * SPEED_CONTROLLER_MAX_SPEED) / SPEED_CONTROLLER_MAX_INPUT;
671
672 // PID regulator with feed forward from speed input.
673 uint16_t outputValue;
674
675 outputValue = PIDController(incrementSetpoint, (motorConfigs.tim4Freq / (lastCommutationTicks * 3)) >> 1, &pidParameters);
676
677 if (outputValue > 255)
678 {
679 outputValue = 255;
680 }
681
682 speedOutput = outputValue;
683
684 // Without the delay PID does not reset when needed
685 _delay_us(1);
686#else
687 // Calculate the delta in speedInput
688 int16_t delta = speedInput - speedOutput;
689 // If delta exceeds the maximum allowed change, limit it and update
690 // speedOutput
691 if (delta > SPEED_CONTROLLER_MAX_DELTA)
692 {
694 }
695 else if (delta < -SPEED_CONTROLLER_MAX_DELTA)
696 {
698 }
699 else
700 {
702 }
703#endif
704 }
705 else
706 {
707 speedOutput = 0;
708 }
709}
#define SPEED_CONTROLLER_MAX_INPUT
Maximum Speed Reference Input.
Definition main.h:674
#define SPEED_CONTROLLER_MAX_DELTA
Speed Controller Maximum Delta (Applicable for Open Loop Control)
Definition main.h:375
#define SPEED_CONTROLLER_MAX_SPEED
Speed Controller Maximum Speed.
Definition main.h:396
uint16_t PIDController(int16_t setPoint, int16_t processValue, pidData_t *pid_st)
PID control algorithm.
Definition pid.cpp:54
Here is the call graph for this function:
Here is the caller graph for this function:

◆ TimersInit()

void TimersInit ( void )

Initializes and synchronizes Timers.

This function sets the correct pre-scaler and starts all required timers.

Timer 1 is used to trigger the fault multiplexing on overflow. Timer 3 is used, if EMULATE_HALL is set, to trigger the change in hall output on overflow. Timer 4 is used to generate PWM outputs for the gates and trigger the commutation tick counter and check if the motor is spinning on overflow. The overflow event interrupt for Timer 4 is set outside this function at the end of the main initialization function.

See also
EMULATE_HALL, TIM3_FREQ, TimersSetModeBlockCommutation(), TimersSetModeBrake()

Definition at line 405 of file main.ino.

406{
407 // Set Timer1 accordingly.
408 TCCR1A = (1 << WGM11) | (0 << WGM10);
409 TCCR1B = (0 << WGM13) | (1 << WGM12);
410 TIMSK1 = (1 << TOIE1);
411
412 // Start Timer1.
413 TCCR1B |= TIM1_CLOCK_DIV_64;
414
415#if (EMULATE_HALL == TRUE)
416 // Set Timer3 accordingly.
417 TCCR3A = (1 << WGM31) | (1 << WGM30);
418 TCCR3B = (1 << WGM33) | (1 << WGM32);
419 TIMSK3 = (1 << TOIE3);
420
421 // Set top value of Timer/counter3.
422 OCR3AH = (uint8_t)(TIM3_TOP >> 8);
423 OCR3AL = (uint8_t)(0xff & TIM3_TOP);
424
425 // Start Timer3.
426 TCCR3B |= TIM1_CLOCK_DIV_8;
427#endif
428 // Set Timer4 in "PWM6 / Dual-slope" mode. Does not enable outputs yet.
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);
433
434 // Set top value of Timer/counter4.
435 TC4H = (uint8_t)(motorConfigs.tim4Top >> 8);
436 OCR4C = (uint8_t)(0xff & motorConfigs.tim4Top);
437
438 // Set the dead time.
440
441 // Start Timer4.
443}
#define DEAD_TIME_HALF(deadTime)
This value specifies half the dead time in number of clock cycles. Divide by frequency to get duratio...
Definition main.h:1080
#define DT_PRESCALER_DIV_PATTERN(dtPrescaler)
Deadtime generator pre-scaler selection bits based on pre-scaler value.
Definition main.h:1070
#define TIM3_TOP
Calculated top value for Timer 3.
Definition main.h:1088
#define TIM4_PRESCALER_DIV_PATTERN(tim4Prescaler)
Timer 4 clock select bits based on pre-scaler value.
Definition main.h:1052
#define CHOOSE_DT_PRESCALER(deadTime)
Macro to choose Timer4 dead time pre-scaler based on the dead time.
Definition main.h:695
#define CHOOSE_TIM4_PRESCALER(tim4Freq)
Macro to choose Timer4 pre-scaler.
Definition main.h:677
#define TIM1_CLOCK_DIV_64
Timer1 clock - i/o clk with division factor 64.
Definition main.h:805
#define TIM1_CLOCK_DIV_8
Timer1 clock - i/o clk with division factor 8.
Definition main.h:803
Here is the caller graph for this function:

◆ TimersSetModeBlockCommutation()

static void TimersSetModeBlockCommutation ( void )
static

Configures timers for block commutation.

This function is called every time the drive waveform is changed and block commutation is needed. PWM outputs are safely disabled while configuration registers are changed to avoid unintended driving or shoot-through.

The function sets the PWM pins to input (High-Z) while changing modes and configures the timers. The output duty cycle is set to zero initially. It waits for the next PWM cycle to ensure that all outputs are updated, and then the motor drive waveform is set to block commutation. Finally, the PWM pins are changed back to output mode to allow PWM control.

Definition at line 779 of file main.ino.

780{
781 // Set PWM pins to input (High-Z) while changing modes.
783
784 // Sets up timers.
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);
788
789 // Set output duty cycle to zero for now.
790 SetDuty(0);
791
792 // Wait for the next PWM cycle to ensure that all outputs are updated.
794
796
797 // Change PWM pins to output again to allow PWM control.
799}
static void TimersWaitForNextPWMCycle(void)
Wait for the start of the next PWM cycle.
Definition main.ino:852
Here is the call graph for this function:
Here is the caller graph for this function:

◆ TimersWaitForNextPWMCycle()

static void TimersWaitForNextPWMCycle ( void )
static

Wait for the start of the next PWM cycle.

This function waits for the beginning of the next PWM cycle to ensure smooth transitions between different PWM modes and avoid shoot-through conditions.

Definition at line 852 of file main.ino.

853{
854 // Clear Timer1 Capture event flag.
855 TIFR4 = (1 << TOV4);
856
857 // Wait for new Timer1 Capture event flag.
858 while (!(TIFR4 & (1 << TOV4)))
859 {
860 }
861}
Here is the caller graph for this function:

Variable Documentation

◆ commutationTicks

volatile uint16_t commutationTicks = 0

The number of 'ticks' between two hall sensor changes (counter).

This variable is used to count the number of 'ticks' between each hall sensor change. It is cleared when the hall sensor change occurs. One 'tick' is one PWM period.

Note
The speed of the motor is inversely proportional to this value, but this variable is also reset to 0 when a hall sensor change is detected, so cannot be used to infer speed of the motor.
See also
lastCommutationTicks

Definition at line 105 of file main.ino.

◆ current

volatile uint16_t current = 0

Current measurement (Register Value).

The most recent current measurement is stored in this variable.

The range is 0-1023.

This value is not scaled and represents the raw ADC register value. To obtain the scaled current value in amperes, you can use the formula:

\[ \text{Current (A)} = \frac{\text{REGISTER_VALUE} \times 0.004887586 \times 1000000}{\text{CURRENT_GAIN} \times \text{CURRENT_SENSE_RESISTOR}} \]

Where:

  • REGISTER_VALUE : The raw ADC register value stored in this variable.
  • 0.004887586 : The conversion factor for a 10-bit ADC with a Vref of 5V.
  • CURRENT_GAIN : The gain of the current sense operational amplifier.
  • CURRENT_SENSE_RESISTOR : The value of the shunt resistor in micro-ohms (μΩ).

The NEVB-3INV-001-01 comes with a current op-amp with a gain factor of 50 and a current sense resistor of value 2 mΩ. This corresponds to approximately 0.049 amperes (A) per register value.

See also
CURRENT_WARNING_THRESHOLD, CURRENT_ERROR_THRESHOLD

Definition at line 161 of file main.ino.

◆ faultFlags

volatile faultflags_t faultFlags

Fault flags placed in I/O space for fast access.

This variable contains all the flags used for faults. It is placed in GPIOR1 register, which allows usage of several fast bit manipulation/branch instructions.

Definition at line 84 of file main.ino.

◆ gateVref

volatile uint16_t gateVref = 0

Gate voltage measurement (Register Value)

The most recent gate voltage measurement is stored in this variable.

The range is 0-1023.

This value is not scaled and represents the raw ADC register value. To obtain the scaled gate voltage in volts, you can use the formula:

\[ \text{Voltage (V)} = \frac{\text{REGISTER_VALUE} \times 0.004887586 \times (\text{GATE_RTOP} + \text{GATE_RBOTTOM})}{\text{GATE_RBOTTOM}} \]

Where:

  • REGISTER_VALUE : The raw ADC register value stored in this variable.
  • 0.004887586 : The conversion factor for a 10-bit ADC with a Vref of 5V.
  • GATE_RTOP : The top resistor value in ohms (Ω) in the potential divider.
  • GATE_RBOTTOM : The bottom resistor value in ohms (Ω) in the potential divider.

NEVB-3INV-001-01 has a resistor divider with RTOP of 1 MΩ and RBOTTOM of 71.5 kΩ, so it corresponds to approximately 0.0732 volts (V) per register value.

Note
It is not used for any significant purpose in this implementation, but the measurement is updated.

Definition at line 190 of file main.ino.

◆ incoming_byte

char incoming_byte = 0

Buffer for incoming serial data.

This variable is used to store the latest byte received from the serial interface. It's intended to temporarily hold data as it's being read from the serial buffer.

Definition at line 199 of file main.ino.

◆ lastCommutationTicks

volatile uint16_t lastCommutationTicks = 0xffff

The number of 'ticks' between two hall sensor changes (store).

This variable is used to store the number of 'ticks' between each hall sensor change. It is set to the value in commutationTicks before it is cleared when the hall sensor change occurs.

One 'tick' is one PWM period. The speed of the motor is inversely proportional to this value.

See also
commutationTicks

Definition at line 118 of file main.ino.

◆ motorConfigs

volatile motorconfigs_t motorConfigs

Motor Configs.

This variable contains some of the motor configurations.

Definition at line 90 of file main.ino.

◆ motorFlags

volatile motorflags_t motorFlags

Motor control flags placed in I/O space for fast access.

This variable contains all the flags used for motor control. It is placed in GPIOR0 register, which allows usage of several fast bit manipulation/branch instructions.

Definition at line 76 of file main.ino.

◆ speedInput

volatile uint8_t speedInput = 0

The most recent "speed" input measurement.

This variable is set by the ADC from the speed input reference pin. The range is 0-255.

Definition at line 125 of file main.ino.

◆ speedOutput

volatile uint8_t speedOutput = 0

The most recent "speed" output from the speed controller.

This variable controls the duty cycle of the generated PWM signals. The range is 0-255.

Definition at line 132 of file main.ino.