Motor Driver Evaluation Kit NEVB-MTR1-t01-1.0.0
Firmware for NEVB-MTR1-KIT1 for trapezoidal control of BLDC motors using Hall-effect sensors
Loading...
Searching...
No Matches
main.ino File Reference

Motor control implementation. More...

#include "config.h"
#include "tables.h"
#include "fault.h"
#include "filter.h"
#include "scpi.h"
Include dependency graph for main.ino:

Go to the source code of this file.

Functions

volatile motorflags_t motorFlags __attribute__ ((address(0x4A)))
 Motor control flags placed in I/O space for fast access.
 
volatile faultflags_t faultFlags __attribute__ ((address(0x3E)))
 Fault flags placed in I/O space for fast access.
 
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 DisableMotor (void)
 Disable motor.
 
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 ()
 Handle a fatal error and enter a fault state.
 
static __attribute__ ((always_inline)) void SetDuty(const uint16_t duty)
 Set duty cycle for TIM4.
 
 if (direction==0)
 
 ClearPWMPorts ()
 
TCCR4E & DisablePWMOutputs ()
 
 EnablePWMOutputs ()
 

Variables

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 ibus = 0
 Hi-side Current (IBUS) measurement (Register Value).
 
volatile int16_t iphaseU = 0
 In-line Phase U current current measurement (Register Value).
 
volatile int16_t iphaseV = 0
 In-line Phase V current current measurement (Register Value).
 
volatile int16_t iphaseW = 0
 In-line Phase W current current measurement (Register Value).
 
volatile uint16_t vbusVref = 0
 VBUS voltage measurement (Register Value)
 
static uint8_t hall
 
 else
 
 tableAddress = (hall * 4)
 
 PORTB = (uint8_t)pgm_read_byte_near(tableAddress++)
 
 PORTC = (uint8_t)pgm_read_byte_near(tableAddress++)
 
 PORTD = (uint8_t)pgm_read_byte_near(tableAddress++)
 
 TCCR4E = (uint8_t)pgm_read_byte_near(tableAddress)
 

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.

Function Documentation

◆ __attribute__() [1/3]

volatile faultflags_t faultFlags __attribute__ ( (address(0x3E)) )

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

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

Warning
This variable can only have a maximum size of 1 byte.

◆ __attribute__() [2/3]

volatile motorflags_t motorFlags __attribute__ ( (address(0x4A)) )

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 GPIOR1 and GPIOR2 registers, which allows usage of several fast bit manipulation/branch instructions.

Warning
This variable can only have a maximum size of 2 bytes.

◆ __attribute__() [3/3]

static __attribute__ ( (always_inline) ) const
inlinestatic

Set duty cycle for TIM4.

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

Updates global desired direction flag.

Read the hall sensor inputs and decode the hall state.

Perform block commutation based on direction and hall sensor input.

Wait for the start of the next PWM cycle.

Configures timers for block commutation.

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.

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.

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

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.

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.

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

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 823 of file main.ino.

824{
825 TC4H = duty >> 8;
826 OCR4A = 0xFF & duty;
827}

◆ 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.

Note
ADC_TRIGGER is set to ADC_TRIGGER_TIMER0_OVF. This triggers the ADC at a rate of ~977 samples per second. The ADC prescaler is set to ADC_PRESCALER_DIV_128 as this gives a 125kHz ADC clock. It is recommended to have the ADC clock between 50kHz and 200kHz to get maximum ADC resolution.
See also
ADC_TRIGGER

Definition at line 538 of file main.ino.

539{
540 // Select initial AD conversion channel [0V for self-test].
541 ADMUX = (ADC_REFERENCE_VOLTAGE | (1 << ADLAR) | ADC_MUX_L_0V);
542 ADCSRB = ADC_MUX_H_0V;
543 _delay_ms(1);
544
545 // Enable ADC
546 ADCSRA = (1 << ADEN);
547
548 // Start ADC single conversion and discard first measurement.
549 uint16_t adc_reading = ADCSingleConversion();
550
551 // Start ADC single conversion to measure 0V, this time it is correct.
552 adc_reading = ADCSingleConversion();
553
554 // Check if ADC can measure 0V within 10mV.
555 if (adc_reading > 2)
556 {
557 SetFaultFlag(FAULT_USER_FLAG1, TRUE);
558 SetFaultFlag(FAULT_USER_FLAG2, FALSE);
559 SetFaultFlag(FAULT_USER_FLAG3, FALSE);
560 FatalError();
561 }
562
563 // Select next AD conversion channel [1V1 for self-test].
564 ADMUX = (ADC_REFERENCE_VOLTAGE | (1 << ADLAR) | ADC_MUX_L_1V1);
565 ADCSRB = ADC_MUX_H_1V1;
566 _delay_ms(1);
567
568 // Start ADC single conversion to measure 1V1.
569 adc_reading = ADCSingleConversion();
570
571 // Check if ADC can measure 1.1V within 1% (1.09 to 1.1V).
572 if ((adc_reading < 223) || (adc_reading > 227))
573 {
574 SetFaultFlag(FAULT_USER_FLAG1, TRUE);
575 SetFaultFlag(FAULT_USER_FLAG2, FALSE);
576 SetFaultFlag(FAULT_USER_FLAG3, FALSE);
577 FatalError();
578 }
579
580 // Select next AD conversion channel [BREF].
581 ADMUX = (ADC_REFERENCE_VOLTAGE | (1 << ADLAR) | ADC_MUX_L_IBUS);
582 ADCSRB = ADC_MUX_H_IBUS;
583
584 // Enable pull up resistor
585 PORTF |= (1 << PF0);
586
587 _delay_ms(1);
589
590 // Start ADC single conversion to measure BREF.
591 adc_reading = ADCSingleConversion();
592
593 // Wait to check if any board is connected. Should be anything other than
594 // 0x3ff if any board is connected assuming BREF of the board is not equal to
595 // IOREF.
596 while (adc_reading == 0x3ff)
597 {
599
600 // Start ADC single conversion to measure BREF.
601 adc_reading = ADCSingleConversion();
602 }
603
604 // Disable pull up resistor
605 PORTF &= ~(1 << PF0);
606
607 // Re-initialize ADC mux channel select.
608 ADMUX &= ~ADC_MUX_L_BITS;
609 ADMUX |= ADC_MUX_L_SPEED;
610 // Set trigger source to ADC_TRIGGER.
611 ADCSRB = ADC_MUX_H_SPEED | ADC_TRIGGER;
612
613 // Re-initialize ADC to work with interrupts.
614 ADCSRA = (1 << ADEN) | (1 << ADSC) | (1 << ADATE) | (1 << ADIF) | (1 << ADIE) | ADC_PRESCALER;
615}
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 config.h:964
#define ADC_MUX_H_0V
High ADC channel selection bit (MUX5) - 0V (GND).
Definition config.h:968
#define ADC_MUX_L_1V1
Lower ADC channel selection bits (MUX4:0) - 1.1V (Vbandgap).
Definition config.h:962
#define ADC_MUX_L_0V
Lower ADC channel selection bits (MUX4:0) - 0V (GND).
Definition config.h:966
#define ADC_MUX_L_BITS
Lower ADC channel selection bits (MUX4:0) mask.
Definition config.h:906
#define ADC_MUX_L_IBUS
Lower analog channel selection bits (MUX4:0) for motor current measurement.
Definition config.h:660
#define ADC_MUX_L_SPEED
Definition config.h:655
#define ADC_TRIGGER
ADC trigger used in this application.
Definition config.h:686
#define ADC_MUX_H_IBUS
High analog channel selection bit (MUX5) for for motor current measurement.
Definition config.h:662
#define TRUE
TRUE constant value, defined to be compatible with comparisons.
Definition config.h:598
#define FALSE
FALSE constant value.
Definition config.h:596
#define ADC_PRESCALER
ADC clock pre-scaler used in this application.
Definition config.h:682
#define ADC_MUX_H_SPEED
Definition config.h:658
#define ADC_REFERENCE_VOLTAGE
ADC voltage reference used in this application.
Definition config.h:684
@ FAULT_USER_FLAG1
Is user flag 1 set?
Definition config.h:1103
@ FAULT_USER_FLAG2
Is user flag 2 set?
Definition config.h:1105
@ FAULT_USER_FLAG3
Is user flag 3 set?
Definition config.h:1107
static uint16_t ADCSingleConversion(void)
Perform a single ADC conversion.
Definition main.ino:624
static void FatalError()
Handle a fatal error and enter a fault state.
Definition main.ino:805
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 624 of file main.ino.

625{
626 // Initialize ADC for one-time conversion.
627 ADCSRA |= (1 << ADSC);
628
629 // Wait for the conversion to complete.
630 while (ADCSRA & (1 << ADSC))
631 {
632 // Wait until the conversion is finished.
633 }
634
635 // Read the ADC result and combine ADCH and ADCL into a 16-bit value.
636 uint16_t value = (ADCL >> 6);
637 value |= 0x3ff & (ADCH << 2);
638
639 return value;
640}
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 368 of file main.ino.

369{
370 motorConfigs.tim4Freq = (uint32_t)TIM4_FREQ;
371 motorConfigs.tim4Top = (uint16_t)TIM4_TOP(motorConfigs.tim4Freq);
372 motorConfigs.tim4DeadTime = (uint16_t)DEAD_TIME;
373 motorConfigs.speedInputSource = (uint8_t)SPEED_INPUT_SOURCE_LOCAL;
374}
#define TIM4_TOP(tim4Freq)
Definition config.h:1151
#define SPEED_INPUT_SOURCE_LOCAL
Speed input source - Local or speed input pin.
Definition config.h:698
#define TIM4_FREQ
Desired Switching Frequency for MOSFET Gate Signals.
Definition config.h:124
#define DEAD_TIME
Dead Time Specification.
Definition config.h:153
volatile motorconfigs_t motorConfigs
Motor Configs.
Definition main.ino:66
Here is the caller graph for this function:

◆ DisableMotor()

static void DisableMotor ( void )
static

Disable motor.

This function disables the motor by clearing the enable flag and performing 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

Definition at line 683 of file main.ino.

684{
685 motorFlags.enable = FALSE;
686 SetFaultFlag(FAULT_MOTOR_STOPPED, FALSE);
687
688#if (TURN_OFF_MODE == TURN_OFF_MODE_COAST)
689 // Disable driver signals to let the motor coast.
690 motorFlags.driveWaveform = WAVEFORM_UNDEFINED;
691 DisablePWMOutputs();
692 ClearPWMPorts();
693#endif
694}
#define WAVEFORM_UNDEFINED
Waveform status flag used for coasting.
Definition config.h:714
@ FAULT_MOTOR_STOPPED
Is motor stopped?
Definition config.h:1097
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

Definition at line 657 of file main.ino.

658{
659 if ((PIND & (1 << ENABLE_PIN)) != 0)
660 {
661 motorFlags.enable = TRUE;
662 }
663 else
664 {
665 DisableMotor();
666 }
667}
#define ENABLE_PIN
Enable input pin.
Definition config.h:692
static void DisableMotor(void)
Disable motor.
Definition main.ino:683
Here is the call graph for this function:
Here is the caller graph for this function:

◆ FatalError()

static void FatalError ( )
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:

  • Sets the motor to stop rotation.
  • Once the motor is stopped, it will loop indefinitely inside CommutationTicksUpdate().

Definition at line 805 of file main.ino.

806{
807 // Stop the motor.
808 DisableMotor();
809
810 // Once this is set no more faults will be registered creating a snapshot
811 // of the failure point.
812 motorFlags.fatalFault = TRUE;
813}
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 341 of file main.ino.

342{
343 // Initialize motorFlags with default values.
344 motorFlags.speedControllerRun = FALSE;
345 motorFlags.remote = FALSE;
346 motorFlags.enable = FALSE;
347 motorFlags.actualDirection = DIRECTION_UNKNOWN;
348 motorFlags.desiredDirection = DIRECTION_FORWARD;
349 motorFlags.driveWaveform = WAVEFORM_UNDEFINED;
350 motorFlags.fatalFault = FALSE;
351
352 // Initialize faultFlags with default values. Set motorStopped to FALSE at
353 // startup. This will make sure that the motor is not started if it is not
354 // really stopped. If it is stopped, this variable will quickly be updated.
355 faultFlags.motorStopped = FALSE;
356 faultFlags.reverseDirection = FALSE;
357 faultFlags.overCurrent = FALSE;
358 faultFlags.noHallConnections = FALSE;
359 faultFlags.userFlag1 = FALSE;
360 faultFlags.userFlag2 = FALSE;
361 faultFlags.userFlag3 = FALSE;
362}
#define DIRECTION_FORWARD
Forward direction flag value.
Definition config.h:636
#define DIRECTION_UNKNOWN
Unknown direction flag value.
Definition config.h:640
Here is the caller graph for this function:

◆ if()

if ( direction = = 0)

Definition at line 893 of file main.ino.

894 {
895 tableAddress = blockCommutationTableForward;
896 }
const uint8_t blockCommutationTableForward[32]
Block Commutation Port Direction Masks for Forward Driving.
Definition tables.h:80

◆ 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 323 of file main.ino.

324{
325 if (motorFlags.remote == TRUE)
326 {
327 ScpiInput(Serial);
328 }
329 if (motorFlags.speedControllerRun)
330 {
332 motorFlags.speedControllerRun = FALSE;
333 }
334}
static void SpeedController(void)
Speed regulator loop.
Definition main.ino:740
void ScpiInput(Stream &interface)
Processes incoming data from a serial interface for SCPI commands.
Definition scpi.cpp:124
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 502 of file main.ino.

503{
504 // Initialize external interrupt on shutdown pin (INT0) and direction input
505 // (INT2) pin.
506 EICRA = (0 << ISC21) | (1 << ISC20) | (0 << ISC01) | (1 << ISC00);
507 EIMSK = (1 << INT2) | (1 << INT0);
508
509 // Initialize pin change interrupt on hall sensor inputs (PCINT1..3).
510 PCMSK0 = (1 << PCINT3) | (1 << PCINT2) | (1 << PCINT1);
511
512 // Enable pin change interrupt on ports with pin change signals
513 PCICR = (1 << PCIE0);
514}
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 383 of file main.ino.

384{
385 // Configure PLL Frequency Control Register to output 48MHz for USB Module and
386 // 64MHz for the High-Speed Clock Timer with a base speed of 96MHz for PLL
387 // Output Frequency.
388
389 PLLFRQ = (0 << PINMUX) | (1 << PLLUSB) | PLL_POSTSCALER_DIV_1_5 | (1 << PDIV3) | (0 << PDIV2) | (1 << PDIV1) | (0 << PDIV0);
390
391 // Enable PLL.
392 PLLCSR = (1 << PINDIV) | (1 << PLLE);
393
394 // Wait until PLOCK bit is set, indicating PLL is locked and stable.
395 while ((PLLCSR & (1 << PLOCK)) == 0)
396 {
397 // Wait for PLL lock
398 ;
399 }
400}
#define PLL_POSTSCALER_DIV_1_5
PLL Post-scaler - division factor 1.5.
Definition config.h:836
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 409 of file main.ino.

410{
411#if (EMULATE_HALL == TRUE)
412 // Configure and set hall sensor pins for motor emulation
413 PORTB &= ~((1 << H1_PIN) | (1 << H2_PIN) | (1 << H3_PIN));
414 PORTB |= (0x07 & pgm_read_byte_near(&expectedHallSequenceForward[1]));
415 // Set hall sensor pins as outputs.
416 DDRB |= (1 << H1_PIN) | (1 << H2_PIN) | (1 << H3_PIN);
417#endif
418
419#if ((HALL_PULLUP_ENABLE == TRUE) && (EMULATE_HALL != TRUE))
420 // Configure and set hall sensor pins as input with pull-ups enabled
421 PORTB |= (1 << H1_PIN) | (1 << H2_PIN) | (1 << H3_PIN);
422#endif
423
424 // Configure and set pins FAULT_PIN_3, FAULT_PIN_2, and FAULT_PIN_1 as outputs
425 PORTB &= ~((1 << FAULT_PIN_3) | (1 << FAULT_PIN_2));
426 DDRB |= (1 << FAULT_PIN_3) | (1 << FAULT_PIN_2);
427 PORTD &= ~(1 << FAULT_PIN_1);
428 DDRD |= (1 << FAULT_PIN_1);
429
430 // If remote mode, set enable and direction pin as output to allow software
431 // triggered interrupts
432 if (motorFlags.remote == TRUE)
433 {
434 PORTD &= ~((1 << ENABLE_PIN) | (1 << DIRECTION_COMMAND_PIN));
435 DDRD |= (1 << ENABLE_PIN) | (1 << DIRECTION_COMMAND_PIN);
436 }
437}
#define H2_PIN
Pin where H2 is connected.
Definition config.h:648
#define FAULT_PIN_2
Fault Pin 2.
Definition config.h:706
#define DIRECTION_COMMAND_PIN
Pin where direction command input is located.
Definition config.h:690
#define FAULT_PIN_3
Fault Pin 3.
Definition config.h:708
#define H3_PIN
Pin where H3 is connected.
Definition config.h:650
#define H1_PIN
Pin where H1 is connected.
Definition config.h:646
#define FAULT_PIN_1
Fault Pin 1.
Definition config.h:704
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:

◆ 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 703 of file main.ino.

704{
705 if ((PIND & (1 << REMOTE_PIN)) != 0)
706 {
707 motorFlags.remote = TRUE;
708 }
709 else
710 {
711 motorFlags.remote = FALSE;
712 }
713}
#define REMOTE_PIN
Remote input pin.
Definition config.h:694
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 267 of file main.ino.

268{
269 // Load motor configs
270 ConfigsInit();
271
272 // Initialize flags.
273 FlagsInit();
274
275 // Check if remote mode requested.
276 RemoteUpdate();
277
278 // Initialize peripherals.
279 PortsInit(); // depends on motorFlags.remote
280 ADCInit(); // include self-test + loop until board detected must be before TimersInit
281 PLLInit();
282 TimersInit();
283
284#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
285 PIDInit(PID_K_P, PID_K_I, PID_K_D, &pidParameters);
286#endif
287
288 if (motorFlags.remote == TRUE)
289 {
290 // Start serial interface with 115200 bauds.
291 Serial.begin(115200);
292 // while (!Serial); // wait for serial to finish initializing
293 while (!Serial)
294 ; // wait for serial to finish initializing
295
296 // Initialise SCPI subsystem if remote mode.
297 ScpiInit();
298 }
299 else
300 {
301 // Update direction before enable flag.
302 DesiredDirectionUpdate();
303 // Do not update enable flag until everything is ready.
304 EnableUpdate();
305 }
306
307 // Set up pin change interrupts.
309
310 // Enable Timer4 overflow event interrupt.
311 TIMSK4 |= (1 << TOIE4);
312
313 // Enable interrupts globally and let motor driver take over.
314 sei();
315}
#define PID_K_P
PID Controller Proportional Gain Constant (Only for Closed Loop)
Definition config.h:476
#define PID_K_D
PID Controller Derivative Gain Constant (Only for Closed Loop)
Definition config.h:533
#define PID_K_I
PID Controller Integral Gain Constant (Only for Closed Loop)
Definition config.h:495
static void PortsInit(void)
Initialize I/O port directions and pull-up resistors.
Definition main.ino:409
static void ADCInit(void)
Initializes the ADC.
Definition main.ino:538
static void FlagsInit(void)
Initializes motorFlags and faultFlags.
Definition main.ino:341
static void PinChangeIntInit(void)
Initialize pin change interrupts.
Definition main.ino:502
static void PLLInit(void)
Initialize PLL (Phase-Locked Loop)
Definition main.ino:383
void TimersInit(void)
Initializes and synchronizes Timers.
Definition main.ino:457
static void EnableUpdate(void)
Check whether the enable pin is set and update flags accordingly.
Definition main.ino:657
static void ConfigsInit(void)
Initializes motorConfigs.
Definition main.ino:368
static void RemoteUpdate(void)
Check whether the remote pin is set and update flags accordingly.
Definition main.ino:703
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
void ScpiInit(void)
Initializes the SCPI command parser and registers all supported commands.
Definition scpi.cpp:71
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 740 of file main.ino.

741{
742 if (motorFlags.enable == TRUE)
743 {
744#if (SPEED_CONTROL_METHOD == SPEED_CONTROL_CLOSED_LOOP)
745 // Calculate an increment set point from the analog speed input.
746 int16_t incrementSetpoint = ((int32_t)speedInput * SPEED_CONTROLLER_MAX_SPEED) / SPEED_CONTROLLER_MAX_INPUT;
747
748 // PID regulator with feed forward from speed input.
749 uint16_t outputValue;
750
751 outputValue = PIDController(incrementSetpoint, (motorConfigs.tim4Freq / (lastCommutationTicks * 3)) >> 1, &pidParameters);
752
753 if (outputValue > 255)
754 {
755 outputValue = 255;
756 }
757
758 speedOutput = outputValue;
759
760 // Without the delay PID does not reset when needed
761 _delay_us(1);
762#else
763 // Calculate the delta in speedInput
764 int16_t delta = speedInput - speedOutput;
765 // If delta exceeds the maximum allowed change, limit it and update
766 // speedOutput
767 if (delta > SPEED_CONTROLLER_MAX_DELTA)
768 {
770 }
771 else if (delta < -SPEED_CONTROLLER_MAX_DELTA)
772 {
774 }
775 else
776 {
778 }
779#endif
780 }
781 else
782 {
783 if (speedOutput > 0)
784 {
786 {
788 }
789 else
790 {
791 speedOutput = 0;
792 }
793 }
794 }
795}
#define SPEED_CONTROLLER_MAX_INPUT
Maximum Speed Reference Input.
Definition config.h:740
#define SPEED_CONTROLLER_MAX_DELTA
Speed Controller Maximum Delta (Applicable for Open Loop Control)
Definition config.h:436
#define SPEED_CONTROLLER_MAX_SPEED
Speed Controller Maximum Speed.
Definition config.h:457
volatile uint8_t speedInput
The most recent "speed" input measurement.
Definition main.ino:101
volatile uint8_t speedOutput
The most recent "speed" output from the speed controller.
Definition main.ino:108
volatile uint16_t lastCommutationTicks
The number of 'ticks' between two hall sensor changes (store).
Definition main.ino:94
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.

Timer 0 is used by the Ardiono core to generate interrupts. For reference, it is set up in mode 3 (Fast PWM, TOP=0xFF) with a prescaler of 64. This means ovwerflow occurs ~977 times per second. The overflow interrupt is used to trigger the ADC conversion unless changed by the user.

See also
EMULATE_HALL, TIM3_FREQ, TimersSetModeBlockCommutation()

Definition at line 457 of file main.ino.

458{
459 // Set Timer1 accordingly.
460 TCCR1A = (1 << WGM11) | (0 << WGM10);
461 TCCR1B = (0 << WGM13) | (1 << WGM12);
462 TIMSK1 = (1 << TOIE1);
463
464 // Start Timer1.
465 TCCR1B |= TIM1_CLOCK_DIV_64;
466
467#if (EMULATE_HALL == TRUE)
468 // Set Timer3 accordingly.
469 TCCR3A = (1 << WGM31) | (1 << WGM30);
470 TCCR3B = (1 << WGM33) | (1 << WGM32);
471 TIMSK3 = (1 << TOIE3);
472
473 // Set top value of Timer/counter3.
474 OCR3AH = (uint8_t)(TIM3_TOP >> 8);
475 OCR3AL = (uint8_t)(0xff & TIM3_TOP);
476
477 // Start Timer3.
478 TCCR3B |= TIM1_CLOCK_DIV_8;
479#endif
480 // Set Timer4 in "PWM6 / Dual-slope" mode. Does not enable outputs yet.
481 TCCR4A = (0 << COM4A1) | (1 << COM4A0) | (0 << COM4B1) | (1 << COM4B0) | (1 << PWM4A) | (1 << PWM4B);
483 TCCR4C |= (0 << COM4D1) | (1 << COM4D0) | (1 << PWM4D);
484 TCCR4E = (1 << ENHC4);
485
486 // Set top value of Timer/counter4.
487 TC4H = (uint8_t)(motorConfigs.tim4Top >> 8);
488 OCR4C = (uint8_t)(0xff & motorConfigs.tim4Top);
489
490 // Set the dead time.
491 DT4 = (DEAD_TIME_HALF(motorConfigs.tim4DeadTime) << 4) | DEAD_TIME_HALF(motorConfigs.tim4DeadTime);
492
493 // Start Timer4.
495}
#define DEAD_TIME_HALF(deadTime)
This value specifies half the dead time in number of clock cycles. Divide by frequency to get duratio...
Definition config.h:1172
#define DT_PRESCALER_DIV_PATTERN(dtPrescaler)
Deadtime generator pre-scaler selection bits based on pre-scaler value.
Definition config.h:1162
#define TIM3_TOP
Calculated top value for Timer 3.
Definition config.h:1180
#define TIM4_PRESCALER_DIV_PATTERN(tim4Prescaler)
Timer 4 clock select bits based on pre-scaler value.
Definition config.h:1144
#define CHOOSE_DT_PRESCALER(deadTime)
Macro to choose Timer4 dead time pre-scaler based on the dead time.
Definition config.h:761
#define CHOOSE_TIM4_PRESCALER(tim4Freq)
Macro to choose Timer4 pre-scaler.
Definition config.h:743
#define TIM1_CLOCK_DIV_64
Timer1 clock - i/o clk with division factor 64.
Definition config.h:871
#define TIM1_CLOCK_DIV_8
Timer1 clock - i/o clk with division factor 8.
Definition config.h:869
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 81 of file main.ino.

◆ else

else
Initial value:
{
const uint8_t blockCommutationTableReverse[32]
Block Commutation Port Direction Masks for Reverse Driving.
Definition tables.h:128

Definition at line 897 of file main.ino.

◆ hall

uint8_t hall
Initial value:
{
const uint8_t *tableAddress

Definition at line 889 of file main.ino.

◆ ibus

volatile uint16_t ibus = 0

Hi-side Current (IBUS) 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.004888 \times 1000000}{\text{IBUS_GAIN} \times \text{IBUS_SENSE_RESISTOR}} \]

Where:

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

The NEVB-MTR1-I56-1 comes with a current op-amp with a gain factor of 50 and a current sense resistor of value 4 mΩ. This corresponds to approximately 0.0244 amperes (A) per register value.

See also
IBUS_WARNING_THRESHOLD, IBUS_ERROR_THRESHOLD

Definition at line 137 of file main.ino.

◆ iphaseU

volatile int16_t iphaseU = 0

In-line Phase U current 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.004888 \times 1000000}{\text{IBUS_GAIN} \times \text{IBUS_SENSE_RESISTOR}} \]

Where:

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

The NEVB-MTR1-I56-1 comes with a current op-amp with a gain factor of 20 and a current sense resistor of value 2.5 mΩ. This corresponds to approximately TODO: amperes (A) per register value.

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

Definition at line 167 of file main.ino.

◆ iphaseV

volatile int16_t iphaseV = 0

In-line Phase V current 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.004888 \times 1000000}{\text{IBUS_GAIN} \times \text{IBUS_SENSE_RESISTOR}} \]

Where:

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

The NEVB-MTR1-I56-1 comes with a current op-amp with a gain factor of 20 and a current sense resistor of value 2.5 mΩ. This corresponds to approximately TODO: amperes (A) per register value.

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

Definition at line 196 of file main.ino.

◆ iphaseW

volatile int16_t iphaseW = 0

In-line Phase W current 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.004888 \times 1000000}{\text{IBUS_GAIN} \times \text{IBUS_SENSE_RESISTOR}} \]

Where:

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

The NEVB-MTR1-I56-1 comes with a current op-amp with a gain factor of 20 and a current sense resistor of value 2.5 mΩ. This corresponds to approximately TODO: amperes (A) per register value.

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

Definition at line 226 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 94 of file main.ino.

◆ motorConfigs

volatile motorconfigs_t motorConfigs

Motor Configs.

This variable contains some of the motor configurations.

Definition at line 66 of file main.ino.

◆ PORTB

PORTB = (uint8_t)pgm_read_byte_near(tableAddress++)

Definition at line 908 of file main.ino.

◆ PORTC

PORTC = (uint8_t)pgm_read_byte_near(tableAddress++)

Definition at line 909 of file main.ino.

◆ PORTD

PORTD = (uint8_t)pgm_read_byte_near(tableAddress++)

Definition at line 910 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 101 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 108 of file main.ino.

◆ tableAddress

tableAddress = (hall * 4)

Definition at line 901 of file main.ino.

◆ TCCR4E

TCCR4E = (uint8_t)pgm_read_byte_near(tableAddress)

Definition at line 911 of file main.ino.

◆ vbusVref

volatile uint16_t vbusVref = 0

VBUS voltage measurement (Register Value)

The most recent VBUS 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 VBUS voltage in volts, you can use the formula:

\[ \text{Voltage (V)} = \frac{\text{REGISTER_VALUE} \times 0.004888 \times (\text{VBUS_RTOP} + \text{VBUS_RBOTTOM})}{\text{VBUS_RBOTTOM}} \]

Where:

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

The NEVB-MTR1-C-1 has a resistor divider with RTOP of 100 kΩ and RBOTTOM of 6.2 kΩ, so it corresponds to approximately 0.0837 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 255 of file main.ino.