Skip to content

Commit

Permalink
FEAT added weak definitions of generic hardware implementations + ard…
Browse files Browse the repository at this point in the history
…uino due same frequency PWM and TC calculation
  • Loading branch information
askuric committed May 15, 2021
1 parent dd3dbeb commit 0b7839f
Show file tree
Hide file tree
Showing 5 changed files with 95 additions and 84 deletions.
1 change: 1 addition & 0 deletions src/common/foc_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
#define _sqrt(a) (_sqrtApprox(a))
#define _isset(a) ( (a) != (NOT_SET) )
#define _UNUSED(v) (void) (v)

// utility defines
#define _2_SQRT3 1.15470053838
Expand Down
7 changes: 5 additions & 2 deletions src/drivers/hardware_specific/atmega328_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
void _pinHighFrequency(const int pin){
// High PWM frequency
// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328
if (pin == 5 || pin == 6 ) {
if (pin == 5 || pin == 6 ) {
TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1
}
Expand All @@ -17,12 +17,12 @@ void _pinHighFrequency(const int pin){

}


// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
// supports Arudino/ATmega328
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
_UNUSED(pwm_frequency);
// High PWM frequency
// - always max 32kHz
_pinHighFrequency(pinA);
Expand All @@ -34,6 +34,7 @@ void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
// - hardware speciffic
// supports Arudino/ATmega328
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
_UNUSED(pwm_frequency);
// High PWM frequency
// - always max 32kHz
_pinHighFrequency(pinA);
Expand Down Expand Up @@ -118,6 +119,8 @@ int _configureComplementaryPair(int pinH, int pinL) {
// - hardware specific
// supports Arudino/ATmega328
int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
_UNUSED(pwm_frequency);
_UNUSED(dead_zone);
// High PWM frequency
// - always max 32kHz
int ret_flag = 0;
Expand Down
87 changes: 51 additions & 36 deletions src/drivers/hardware_specific/due_mcu.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
#include "../hardware_api.h"

#if defined(__arm__) && defined(__SAM3X8E__)
#if defined(__arm__) && defined(__SAM3X8E__)

#define _PWM_FREQUENCY 25000 // 25khz
#define _PWM_FREQUENCY_MAX 50000 // 50khz

#define _PWM_RES_MIN 255 // 50khz

// pwm frequency and max duty cycle
static unsigned long _pwm_frequency;
Expand Down Expand Up @@ -101,7 +106,29 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
if (!PWMEnabled) {
// PWM Startup code
pmc_enable_periph_clk(PWM_INTERFACE_ID);
PWMC_ConfigureClocks(pwm_freq * _max_pwm_value, 0, VARIANT_MCK);
// this function does not work too well - I'll rewrite it
// PWMC_ConfigureClocks(PWM_FREQUENCY * _max_pwm_value, 0, VARIANT_MCK);

// finding the divisors an prescalers form FindClockConfiguration function
uint32_t divisors[11] = {1, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024};
uint8_t divisor = 0;
uint32_t prescaler;

/* Find prescaler and divisor values */
prescaler = (VARIANT_MCK / divisors[divisor]) / (pwm_freq*_max_pwm_value);
while ((prescaler > 255) && (divisor < 11)) {
divisor++;
prescaler = (VARIANT_MCK / divisors[divisor]) / (pwm_freq*_max_pwm_value);
}
// update the divisor*prescaler value
prescaler = prescaler | (divisor << 8);

// now calculate the real resolution timer period necessary (pwm resolution)
// pwm_res = bus_freq / (pwm_freq * (prescaler))
_max_pwm_value = (double)VARIANT_MCK / (double)pwm_freq / (double)(prescaler);
// set the prescaler value
PWM->PWM_CLK = prescaler;

PWMEnabled = 1;
}

Expand All @@ -112,6 +139,8 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
g_APinDescription[ulPin].ulPinType,
g_APinDescription[ulPin].ulPin,
g_APinDescription[ulPin].ulPinConfiguration);
// PWM_CMR_CALG - center align
// PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, PWM_CMR_CALG, 0);
PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, 0, 0);
PWMC_SetPeriod(PWM_INTERFACE, chan, _max_pwm_value);
PWMC_SetDutyCycle(PWM_INTERFACE, chan, 0);
Expand All @@ -123,25 +152,26 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){

if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) { // if timer pin
// We use MCLK/2 as clock.
const uint32_t TC = VARIANT_MCK / 2 / pwm_freq;
const uint32_t TC = VARIANT_MCK / 2 / pwm_freq ;
// Setup Timer for this pin
ETCChannel channel = g_APinDescription[ulPin].ulTCChannel;
uint32_t chNo = channelToChNo[channel];
uint32_t chA = channelToAB[channel];
Tc *chTC = channelToTC[channel];
uint32_t interfaceID = channelToId[channel];

if (!TCChanEnabled[interfaceID]) {
pmc_enable_periph_clk(TC_INTERFACE_ID + interfaceID);
TC_Configure(chTC, chNo,
TC_CMR_TCCLKS_TIMER_CLOCK1 |
TC_CMR_WAVE | // Waveform mode
TC_CMR_WAVSEL_UP_RC | // Counter running up and reset when equals to RC
TC_CMR_EEVT_XC0 | // Set external events from XC0 (this setup TIOB as output)
TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR |
TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR);
TC_SetRC(chTC, chNo, TC);
}
if (!TCChanEnabled[interfaceID]) {
pmc_enable_periph_clk(TC_INTERFACE_ID + interfaceID);
TC_Configure(chTC, chNo,
TC_CMR_TCCLKS_TIMER_CLOCK1 |
TC_CMR_WAVE | // Waveform mode
TC_CMR_WAVSEL_UP_RC | // Counter running up and reset when equals to RC
TC_CMR_EEVT_XC0 | // Set external events from XC0 (this setup TIOB as output)
TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR |
TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR);
TC_SetRC(chTC, chNo, TC);
}

// disable the counter on start
if (chA){
TC_SetCMR_ChannelA(chTC, chNo, TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_SET);
Expand Down Expand Up @@ -197,7 +227,7 @@ void setPwm(uint32_t ulPin, uint32_t ulValue) {
const uint32_t TC = VARIANT_MCK / 2 / _pwm_frequency;
// Map value to Timer ranges 0..max_duty_cycle => 0..TC
// Setup Timer for this pin
ulValue = ulValue * TC;
ulValue = ulValue * TC ;
pwm_counter_vals[channel] = ulValue / _max_pwm_value;
// enable counter
if (channelToAB[channel])
Expand Down Expand Up @@ -297,8 +327,8 @@ void TC8_Handler()
// - BLDC motor - 3PWM setting
// - hardware specific
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 35000; // default frequency 50khz
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
// save the pwm frequency
_pwm_frequency = pwm_frequency;
// cinfigure pwm pins
Expand All @@ -314,8 +344,8 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
//- Stepper driver - 2PWM setting
// - hardware specific
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = 35000; // default frequency 50khz
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
// save the pwm frequency
_pwm_frequency = pwm_frequency;
// cinfigure pwm pins
Expand All @@ -329,8 +359,8 @@ void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
// - Stepper motor - 4PWM setting
// - hardware speciffic
void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = 35000; // default frequency 50khz
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
// save the pwm frequency
_pwm_frequency = pwm_frequency;
// cinfigure pwm pins
Expand Down Expand Up @@ -373,19 +403,4 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
}


// Configuring PWM frequency, resolution and alignment
// - BLDC driver - 6PWM setting
// - hardware specific
int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
return -1;
}

// Function setting the duty cycle to the pwm pin (ex. analogWrite())
// - BLDC driver - 6PWM setting
// - hardware specific
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
return;
}


#endif
70 changes: 38 additions & 32 deletions src/drivers/hardware_specific/generic_mcu.cpp
Original file line number Diff line number Diff line change
@@ -1,40 +1,25 @@
#include "../hardware_api.h"

#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) // if mcu is not atmega328

#elif defined(__AVR_ATmega2560__) // if mcu is not atmega2560

#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy

#elif defined(__arm__) && defined(__SAM3X8E__) // or due

#elif defined(ESP_H) // or esp32

#elif defined(_STM32_DEF_) // or stm32

#elif defined(_SAMD21_) // samd21

#elif defined(_SAMD51_) // samd51

#elif defined(__SAME51J19A__) || defined(__ATSAME51J19A__) // samd51

#elif defined(TARGET_RP2040)

#else

// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
// in generic case dont do anything
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
__attribute__((weak)) void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
_UNUSED(pwm_frequency);
_UNUSED(pinA);
_UNUSED(pinB);
return;
}

// function setting the high pwm frequency to the supplied pins
// - BLDC motor - 3PWM setting
// - hardware speciffic
// in generic case dont do anything
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
__attribute__((weak)) void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
_UNUSED(pwm_frequency);
_UNUSED(pinA);
_UNUSED(pinB);
_UNUSED(pinC);
return;
}

Expand All @@ -43,22 +28,35 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
// - Stepper motor - 4PWM setting
// - hardware speciffic
// in generic case dont do anything
void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
__attribute__((weak)) void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
_UNUSED(pwm_frequency);
_UNUSED(pin1A);
_UNUSED(pin1B);
_UNUSED(pin2A);
_UNUSED(pin2B);
return;
}

// Configuring PWM frequency, resolution and alignment
// - BLDC driver - 6PWM setting
// - hardware specific
int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
__attribute__((weak)) int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
_UNUSED(pwm_frequency);
_UNUSED(dead_zone);
_UNUSED(pinA_h);
_UNUSED(pinB_h);
_UNUSED(pinC_h);
_UNUSED(pinA_l);
_UNUSED(pinB_l);
_UNUSED(pinC_l);
return -1;
}


// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
__attribute__((weak)) void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
// transform duty cycle from [0,1] to [0,255]
analogWrite(pinA, 255.0*dc_a);
analogWrite(pinB, 255.0*dc_b);
Expand All @@ -67,7 +65,7 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
// function setting the pwm duty cycle to the hardware
// - BLDC motor - 3PWM setting
// - hardware speciffic
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
__attribute__((weak)) void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
// transform duty cycle from [0,1] to [0,255]
analogWrite(pinA, 255.0*dc_a);
analogWrite(pinB, 255.0*dc_b);
Expand All @@ -77,7 +75,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB
// function setting the pwm duty cycle to the hardware
// - Stepper motor - 4PWM setting
// - hardware speciffic
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
__attribute__((weak)) void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
// transform duty cycle from [0,1] to [0,255]
analogWrite(pin1A, 255.0*dc_1a);
analogWrite(pin1B, 255.0*dc_1b);
Expand All @@ -89,9 +87,17 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
// - BLDC driver - 6PWM setting
// - hardware specific
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
__attribute__((weak)) void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
_UNUSED(dc_a);
_UNUSED(dc_b);
_UNUSED(dc_c);
_UNUSED(dead_zone);
_UNUSED(pinA_h);
_UNUSED(pinB_h);
_UNUSED(pinC_h);
_UNUSED(pinA_l);
_UNUSED(pinB_l);
_UNUSED(pinC_l);
return;
}


#endif
14 changes: 0 additions & 14 deletions src/drivers/hardware_specific/teensy_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,18 +74,4 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
analogWrite(pin2B, 255.0*dc_2b);
}


// Configuring PWM frequency, resolution and alignment
// - BLDC driver - 6PWM setting
// - hardware specific
int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
return -1;
}

// Function setting the duty cycle to the pwm pin (ex. analogWrite())
// - BLDC driver - 6PWM setting
// - hardware specific
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
return;
}
#endif

0 comments on commit 0b7839f

Please sign in to comment.