Skip to content

Commit bf0019d

Browse files
author
Richard Unger
committed
add 1-PWM support to atmega drivers
1 parent 2c43b81 commit bf0019d

File tree

3 files changed

+74
-0
lines changed

3 files changed

+74
-0
lines changed

src/drivers/hardware_specific/atmega2560_mcu.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,21 @@ void _pinHighFrequency(const int pin){
2525
}
2626

2727

28+
// function setting the high pwm frequency to the supplied pins
29+
// - Stepper motor - 2PWM setting
30+
// - hardware speciffic
31+
void* _configure1PWM(long pwm_frequency,const int pinA) {
32+
// High PWM frequency
33+
// - always max 32kHz
34+
_pinHighFrequency(pinA);
35+
GenericDriverParams* params = new GenericDriverParams {
36+
.pins = { pinA },
37+
.pwm_frequency = pwm_frequency
38+
};
39+
return params;
40+
}
41+
42+
2843
// function setting the high pwm frequency to the supplied pins
2944
// - Stepper motor - 2PWM setting
3045
// - hardware speciffic
@@ -56,6 +71,14 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5671
return params;
5772
}
5873

74+
// function setting the pwm duty cycle to the hardware
75+
// - Stepper motor - 2PWM setting
76+
// - hardware speciffic
77+
void _writeDutyCycle1PWM(float dc_a, void* params){
78+
// transform duty cycle from [0,1] to [0,255]
79+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
80+
}
81+
5982
// function setting the pwm duty cycle to the hardware
6083
// - Stepper motor - 2PWM setting
6184
// - hardware speciffic

src/drivers/hardware_specific/atmega328_mcu.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,20 @@ void _pinHighFrequency(const int pin){
1717

1818
}
1919

20+
// function setting the high pwm frequency to the supplied pins
21+
// - Stepper motor - 2PWM setting
22+
// - hardware speciffic
23+
// supports Arudino/ATmega328
24+
void* _configure1PWM(long pwm_frequency,const int pinA) {
25+
// High PWM frequency
26+
// - always max 32kHz
27+
_pinHighFrequency(pinA);
28+
GenericDriverParams* params = new GenericDriverParams {
29+
.pins = { pinA },
30+
.pwm_frequency = pwm_frequency
31+
};
32+
return params;
33+
}
2034
// function setting the high pwm frequency to the supplied pins
2135
// - Stepper motor - 2PWM setting
2236
// - hardware speciffic
@@ -50,6 +64,18 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5064
return params;
5165
}
5266

67+
68+
69+
70+
// function setting the pwm duty cycle to the hardware
71+
// - Stepper motor - 2PWM setting
72+
// - hardware speciffic
73+
void _writeDutyCycle1PWM(float dc_a, void* params){
74+
// transform duty cycle from [0,1] to [0,255]
75+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
76+
}
77+
78+
5379
// function setting the pwm duty cycle to the hardware
5480
// - Stepper motor - 2PWM setting
5581
// - hardware speciffic

src/drivers/hardware_specific/atmega32u4_mcu.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,20 @@ void _pinHighFrequency(const int pin){
2828
}
2929

3030

31+
// function setting the high pwm frequency to the supplied pins
32+
// - Stepper motor - 2PWM setting
33+
// - hardware speciffic
34+
void* _configure1PWM(long pwm_frequency,const int pinA) {
35+
// High PWM frequency
36+
// - always max 32kHz
37+
_pinHighFrequency(pinA);
38+
GenericDriverParams* params = new GenericDriverParams {
39+
.pins = { pinA },
40+
.pwm_frequency = pwm_frequency
41+
};
42+
return params;
43+
}
44+
3145
// function setting the high pwm frequency to the supplied pins
3246
// - Stepper motor - 2PWM setting
3347
// - hardware speciffic
@@ -59,6 +73,17 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5973
return params;
6074
}
6175

76+
77+
78+
// function setting the pwm duty cycle to the hardware
79+
// - Stepper motor - 2PWM setting
80+
// - hardware speciffic
81+
void _writeDutyCycle1PWM(float dc_a, void* params){
82+
// transform duty cycle from [0,1] to [0,255]
83+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
84+
}
85+
86+
6287
// function setting the pwm duty cycle to the hardware
6388
// - Stepper motor - 2PWM setting
6489
// - hardware speciffic

0 commit comments

Comments
 (0)