SimpleFOClibrary  2.1
StepperDriver2PWM.cpp
Go to the documentation of this file.
1 #include "StepperDriver2PWM.h"
2 
3 StepperDriver2PWM::StepperDriver2PWM(int _pwm1, int _in1a, int _in1b, int _pwm2, int _in2a, int _in2b, int en1, int en2){
4  // Pin initialization
5  pwm1 = _pwm1; // phase 1 pwm pin number
6  dir1a = _in1a; // phase 1 INA pin number
7  dir1b = _in1b; // phase 1 INB pin number
8  pwm2 = _pwm2; // phase 2 pwm pin number
9  dir2a = _in2a; // phase 2 INA pin number
10  dir2b = _in2b; // phase 2 INB pin number
11 
12  // enable_pin pin
13  enable_pin1 = en1;
14  enable_pin2 = en2;
15 
16  // default power-supply value
19 
20 }
21 
22 StepperDriver2PWM::StepperDriver2PWM(int _pwm1, int _dir1, int _pwm2, int _dir2, int en1, int en2){
23  // Pin initialization
24  pwm1 = _pwm1; // phase 1 pwm pin number
25  dir1a = _dir1; // phase 1 direction pin
26  pwm2 = _pwm2; // phase 2 pwm pin number
27  dir2a = _dir2; // phase 2 direction pin
28  // these pins are not used
29  dir1b = NOT_SET;
30  dir2b = NOT_SET;
31 
32  // enable_pin pin
33  enable_pin1 = en1;
34  enable_pin2 = en2;
35 
36  // default power-supply value
39 
40 }
41 
42 // enable motor driver
44  // enable_pin the driver - if enable_pin pin available
45  if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, HIGH);
46  if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, HIGH);
47  // set zero to PWM
48  setPwm(0,0);
49 }
50 
51 // disable motor driver
53 {
54  // set zero to PWM
55  setPwm(0, 0);
56  // disable the driver - if enable_pin pin available
57  if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, LOW);
58  if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, LOW);
59 
60 }
61 
62 // init hardware pins
64  // a bit of separation
65  _delay(1000);
66 
67  // PWM pins
68  pinMode(pwm1, OUTPUT);
69  pinMode(pwm2, OUTPUT);
70  pinMode(dir1a, OUTPUT);
71  pinMode(dir2a, OUTPUT);
72  if( _isset(dir1b) ) pinMode(dir1b, OUTPUT);
73  if( _isset(dir2b) ) pinMode(dir2b, OUTPUT);
74 
75  if( _isset(enable_pin1) ) pinMode(enable_pin1, OUTPUT);
76  if( _isset(enable_pin2) ) pinMode(enable_pin2, OUTPUT);
77 
78  // sanity check for the voltage limit configuration
80 
81  // Set the pwm frequency to the pins
82  // hardware specific function - depending on driver and mcu
84  return 0;
85 }
86 
87 
88 // Set voltage to the pwm pin
89 void StepperDriver2PWM::setPwm(float Ua, float Ub) {
90  float duty_cycle1(0.0),duty_cycle2(0.0);
91  // limit the voltage in driver
94  // hardware specific writing
95  duty_cycle1 = _constrain(abs(Ua)/voltage_power_supply,0.0,1.0);
96  duty_cycle2 = _constrain(abs(Ub)/voltage_power_supply,0.0,1.0);
97 
98  // phase 1 direction
99  digitalWrite(dir1a, Ua >= 0 ? LOW : HIGH);
100  if( _isset(dir1b) ) digitalWrite(dir1b, Ua <= 0 ? LOW : HIGH);
101  // phase 2 direction
102  digitalWrite(dir2a, Ub >= 0 ? LOW : HIGH);
103  if( _isset(dir2b) ) digitalWrite(dir2b, Ub <= 0 ? LOW : HIGH);
104 
105  // write to hardware
106  _writeDutyCycle2PWM(duty_cycle1, duty_cycle2, pwm1, pwm2);
107 }
NOT_SET
#define NOT_SET
Definition: foc_utils.h:27
StepperDriver::voltage_limit
float voltage_limit
limiting voltage set to the motor
Definition: StepperDriver.h:16
StepperDriver2PWM::setPwm
void setPwm(float Ua, float Ub) override
Definition: StepperDriver2PWM.cpp:89
StepperDriver2PWM::enable
void enable() override
Definition: StepperDriver2PWM.cpp:43
StepperDriver2PWM::dir1b
int dir1b
phase 1 INB pin number
Definition: StepperDriver2PWM.h:50
_constrain
#define _constrain(amt, low, high)
Definition: foc_utils.h:9
_isset
#define _isset(a)
Definition: foc_utils.h:11
_delay
void _delay(unsigned long ms)
Definition: time_utils.cpp:5
StepperDriver2PWM::dir2b
int dir2b
phase 2 INB pin number
Definition: StepperDriver2PWM.h:53
StepperDriver::pwm_frequency
long pwm_frequency
pwm frequency value in hertz
Definition: StepperDriver.h:14
StepperDriver2PWM::pwm1
int pwm1
phase 1 pwm pin number
Definition: StepperDriver2PWM.h:48
StepperDriver2PWM::disable
void disable() override
Definition: StepperDriver2PWM.cpp:52
StepperDriver2PWM::dir1a
int dir1a
phase 1 INA pin number
Definition: StepperDriver2PWM.h:49
StepperDriver2PWM::enable_pin2
int enable_pin2
enable pin number phase 2
Definition: StepperDriver2PWM.h:55
_writeDutyCycle2PWM
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB)
Definition: drivers/hardware_specific/generic_mcu.cpp:55
StepperDriver2PWM::init
int init() override
Definition: StepperDriver2PWM.cpp:63
DEF_POWER_SUPPLY
#define DEF_POWER_SUPPLY
default power supply voltage
Definition: defaults.h:4
StepperDriver2PWM.h
StepperDriver2PWM::enable_pin1
int enable_pin1
enable pin number phase 1
Definition: StepperDriver2PWM.h:54
StepperDriver2PWM::StepperDriver2PWM
StepperDriver2PWM(int pwm1, int in1a, int in1b, int pwm2, int in2a, int in2b, int en1=NOT_SET, int en2=NOT_SET)
Definition: StepperDriver2PWM.cpp:3
StepperDriver::voltage_power_supply
float voltage_power_supply
power supply voltage
Definition: StepperDriver.h:15
StepperDriver2PWM::pwm2
int pwm2
phase 2 pwm pin number
Definition: StepperDriver2PWM.h:51
StepperDriver2PWM::dir2a
int dir2a
phase 2 INA pin number
Definition: StepperDriver2PWM.h:52
_configure2PWM
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
Definition: drivers/hardware_specific/generic_mcu.cpp:23