|
| 1 | + |
| 2 | +#include "../hardware_api.h" |
| 3 | + |
| 4 | +#if defined(__AVR_ATmega32U4__) |
| 5 | + |
| 6 | +// set pwm frequency to 32KHz |
| 7 | +void _pinHighFrequency(const int pin){ |
| 8 | + // High PWM frequency |
| 9 | + // reference: http://r6500.blogspot.com/2014/12/fast-pwm-on-arduino-leonardo.html |
| 10 | + if (pin == 3 || pin == 11 ) { |
| 11 | + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode |
| 12 | + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 |
| 13 | + } |
| 14 | + else if (pin == 9 || pin == 10 ) |
| 15 | + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1 |
| 16 | + else if (pin == 5 ) |
| 17 | + TCCR3B = ((TCCR3B & 0b11111000) | 0x01); // set prescaler to 1 |
| 18 | + else if ( pin == 6 || pin == 13 ) { // a bit more complicated 10 bit timer |
| 19 | + // PLL Configuration |
| 20 | + PLLFRQ= ((PLLFRQ & 0b11001111) | 0x20) // Use 96MHz / 1.5 = 64MHz |
| 21 | + TCCR4B = ((TCCR4B & 0b11110000) | 0xB); // configure prescaler to get 64M/2/1024 = 31.25 kHz |
| 22 | + TCCR4D = ((TCCR4D & 0b11111100) | 0x01); // configure the pwm phase-corrected mode |
| 23 | + |
| 24 | + if (pin == 6) TCCR4A = 0x82; // activate channel A - pin 13 |
| 25 | + else if (pin == 13) TCCR4C |= 0x09; // Activate channel D - pin 6 |
| 26 | + } |
| 27 | + |
| 28 | +} |
| 29 | + |
| 30 | + |
| 31 | +// function setting the high pwm frequency to the supplied pins |
| 32 | +// - Stepper motor - 2PWM setting |
| 33 | +// - hardware speciffic |
| 34 | +void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) { |
| 35 | + // High PWM frequency |
| 36 | + // - always max 32kHz |
| 37 | + _pinHighFrequency(pinA); |
| 38 | + _pinHighFrequency(pinB); |
| 39 | +} |
| 40 | + |
| 41 | +// function setting the high pwm frequency to the supplied pins |
| 42 | +// - BLDC motor - 3PWM setting |
| 43 | +// - hardware speciffic |
| 44 | +void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) { |
| 45 | + // High PWM frequency |
| 46 | + // - always max 32kHz |
| 47 | + _pinHighFrequency(pinA); |
| 48 | + _pinHighFrequency(pinB); |
| 49 | + _pinHighFrequency(pinC); |
| 50 | +} |
| 51 | + |
| 52 | +// function setting the pwm duty cycle to the hardware |
| 53 | +// - Stepper motor - 2PWM setting |
| 54 | +// - hardware speciffic |
| 55 | +void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){ |
| 56 | + // transform duty cycle from [0,1] to [0,255] |
| 57 | + analogWrite(pinA, 255.0*dc_a); |
| 58 | + analogWrite(pinB, 255.0*dc_b); |
| 59 | +} |
| 60 | + |
| 61 | +// function setting the pwm duty cycle to the hardware |
| 62 | +// - BLDC motor - 3PWM setting |
| 63 | +// - hardware speciffic |
| 64 | +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){ |
| 65 | + // transform duty cycle from [0,1] to [0,255] |
| 66 | + analogWrite(pinA, 255.0*dc_a); |
| 67 | + analogWrite(pinB, 255.0*dc_b); |
| 68 | + analogWrite(pinC, 255.0*dc_c); |
| 69 | +} |
| 70 | + |
| 71 | +// function setting the high pwm frequency to the supplied pins |
| 72 | +// - Stepper motor - 4PWM setting |
| 73 | +// - hardware speciffic |
| 74 | +void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) { |
| 75 | + // High PWM frequency |
| 76 | + // - always max 32kHz |
| 77 | + _pinHighFrequency(pin1A); |
| 78 | + _pinHighFrequency(pin1B); |
| 79 | + _pinHighFrequency(pin2A); |
| 80 | + _pinHighFrequency(pin2B); |
| 81 | +} |
| 82 | + |
| 83 | +// function setting the pwm duty cycle to the hardware |
| 84 | +// - Stepper motor - 4PWM setting |
| 85 | +// - hardware speciffic |
| 86 | +void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){ |
| 87 | + // transform duty cycle from [0,1] to [0,255] |
| 88 | + analogWrite(pin1A, 255.0*dc_1a); |
| 89 | + analogWrite(pin1B, 255.0*dc_1b); |
| 90 | + analogWrite(pin2A, 255.0*dc_2a); |
| 91 | + analogWrite(pin2B, 255.0*dc_2b); |
| 92 | +} |
| 93 | + |
| 94 | + |
| 95 | + |
| 96 | +// Configuring PWM frequency, resolution and alignment |
| 97 | +// - BLDC driver - 6PWM setting |
| 98 | +// - hardware specific |
| 99 | +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) { |
| 100 | + |
| 101 | + if( (pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){ |
| 102 | + // configure the pwm phase-corrected mode |
| 103 | + TCCR0A = ((TCCR0A & 0b11111100) | 0x01); |
| 104 | + // configure complementary pwm on low side |
| 105 | + if(pinH == 11 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ; |
| 106 | + else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ; |
| 107 | + // set prescaler to 1 - 32kHz freq |
| 108 | + TCCR0B = ((TCCR0B & 0b11110000) | 0x01); |
| 109 | + }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){ |
| 110 | + // set prescaler to 1 - 32kHz freq |
| 111 | + TCCR1B = ((TCCR1B & 0b11111000) | 0x01); |
| 112 | + // configure complementary pwm on low side |
| 113 | + if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ; |
| 114 | + else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ; |
| 115 | + }else if((pinH == 6 && pinL == 13 ) || (pinH == 13 && pinL == 6 ) ){ |
| 116 | + // PLL Configuration |
| 117 | + PLLFRQ= ((PLLFRQ & 0b11001111) | 0x20) // Use 96MHz / 1.5 = 64MHz |
| 118 | + TCCR4B = ((TCCR4B & 0b11110000) | 0xB); // configure prescaler to get 64M/2/1024 = 31.25 kHz |
| 119 | + TCCR4D = ((TCCR4D & 0b11111100) | 0x01); // configure the pwm phase-corrected mode |
| 120 | + |
| 121 | + // configure complementary pwm on low side |
| 122 | + if(pinH == 13 ){ |
| 123 | + TCCR4A = 0x82; // activate channel A - pin 13 |
| 124 | + TCCR4C |= 0x0d; // Activate complementary channel D - pin 6 |
| 125 | + }else { |
| 126 | + TCCR4C |= 0x09; // Activate channel D - pin 6 |
| 127 | + TCCR4A = 0xc2; // activate complementary channel A - pin 13 |
| 128 | + } |
| 129 | + }else{ |
| 130 | + return -1; |
| 131 | + } |
| 132 | + return 0; |
| 133 | +} |
| 134 | + |
| 135 | +// function setting the |
| 136 | +void _setPwmPair(int pinH, int pinL, float val, int dead_time) |
| 137 | +{ |
| 138 | + int pwm_h = _constrain(val-dead_time/2,0,255); |
| 139 | + int pwm_l = _constrain(val+dead_time/2,0,255); |
| 140 | + |
| 141 | + analogWrite(pinH, pwm_h); |
| 142 | + if(pwm_l == 255 || pwm_l == 0) |
| 143 | + digitalWrite(pinL, pwm_l ? LOW : HIGH); |
| 144 | + else |
| 145 | + analogWrite(pinL, pwm_l); |
| 146 | +} |
| 147 | + |
| 148 | +// Function setting the duty cycle to the pwm pin (ex. analogWrite()) |
| 149 | +// - BLDC driver - 6PWM setting |
| 150 | +// - hardware specific |
| 151 | +// supports Arudino/ATmega328 |
| 152 | +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){ |
| 153 | + _setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0); |
| 154 | + _setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0); |
| 155 | + _setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0); |
| 156 | +} |
| 157 | + |
| 158 | +#endif |
0 commit comments