1+ #include " StepperDriver2PWM.h"
2+
3+ StepperDriver2PWM::StepperDriver2PWM (int ph1PWM, int ph1INA, int ph1INB, int ph2PWM, int ph2INA, int ph2INB, int en1, int en2){
4+ // Pin initialization
5+ pwm1 = ph1PWM; // !< phase 1 pwm pin number
6+ ina1 = ph1INA; // !< phase 1 INA pin number
7+ inb1 = ph1INB; // !< phase 1 INB pin number
8+ pwm2 = ph2PWM; // !< phase 2 pwm pin number
9+ ina2 = ph2INA; // !< phase 2 INA pin number
10+ inb2 = ph2INB; // !< phase 2 INB pin number
11+
12+ // enable_pin pin
13+ enable_pin1 = en1;
14+ enable_pin2 = en2;
15+
16+ // default power-supply value
17+ voltage_power_supply = DEF_POWER_SUPPLY;
18+ voltage_limit = NOT_SET;
19+
20+ }
21+
22+ // enable motor driver
23+ void StepperDriver2PWM::enable (){
24+ // enable_pin the driver - if enable_pin pin available
25+ if ( enable_pin1 != NOT_SET ) digitalWrite (enable_pin1, HIGH);
26+ if ( enable_pin2 != NOT_SET ) digitalWrite (enable_pin2, HIGH);
27+ // set zero to PWM
28+ setPwm (0 ,0 );
29+ }
30+
31+ // disable motor driver
32+ void StepperDriver2PWM::disable ()
33+ {
34+ // set zero to PWM
35+ setPwm (0 , 0 );
36+ // disable the driver - if enable_pin pin available
37+ if ( enable_pin1 != NOT_SET ) digitalWrite (enable_pin1, LOW);
38+ if ( enable_pin2 != NOT_SET ) digitalWrite (enable_pin2, LOW);
39+
40+ }
41+
42+ // init hardware pins
43+ int StepperDriver2PWM::init () {
44+
45+ // PWM pins
46+ pinMode (pwm1, OUTPUT);
47+ pinMode (pwm2, OUTPUT);
48+ pinMode (ina1, OUTPUT);
49+ pinMode (ina2, OUTPUT);
50+ pinMode (inb1, OUTPUT);
51+ pinMode (inb2, OUTPUT);
52+
53+ if (enable_pin1 != NOT_SET) pinMode (enable_pin1, OUTPUT);
54+ if (enable_pin2 != NOT_SET) pinMode (enable_pin2, OUTPUT);
55+
56+ // sanity check for the voltage limit configuration
57+ if (voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
58+
59+ // Set the pwm frequency to the pins
60+ // hardware specific function - depending on driver and mcu
61+ _configure2PWM (pwm_frequency, pwm1, pwm2);
62+ return 0 ;
63+ }
64+
65+
66+ // Set voltage to the pwm pin
67+ void StepperDriver2PWM::setPwm (float Ualpha, float Ubeta) {
68+ float duty_cycle1 (0.0 ),duty_cycle2 (0.0 );
69+ // limit the voltage in driver
70+ Ualpha = _constrain (Ualpha, -voltage_limit, voltage_limit);
71+ Ubeta = _constrain (Ubeta, -voltage_limit, voltage_limit);
72+ // hardware specific writing
73+ duty_cycle1 = _constrain (abs (Ualpha)/voltage_power_supply,0.0 ,1.0 );
74+ duty_cycle2 = _constrain (abs (Ubeta)/voltage_power_supply,0.0 ,1.0 );
75+ // set direction
76+ if ( Ualpha > 0 ){
77+ digitalWrite (inb1, LOW);
78+ digitalWrite (ina1, HIGH);
79+ }
80+ else {
81+ digitalWrite (ina1, LOW);
82+ digitalWrite (inb1, HIGH);
83+ }
84+
85+ if ( Ubeta > 0 ){
86+ digitalWrite (ina2, LOW);
87+ digitalWrite (inb2, HIGH);
88+ }
89+ else {
90+ digitalWrite (inb2, LOW);
91+ digitalWrite (ina2, HIGH);
92+ }
93+
94+ // write to hardware
95+ _writeDutyCycle2PWM (duty_cycle1, duty_cycle2, pwm1, pwm2);
96+ }
0 commit comments