SimpleFOClibrary  2.1
StepperDriver4PWM.cpp
Go to the documentation of this file.
1 #include "StepperDriver4PWM.h"
2 
3 StepperDriver4PWM::StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B,int en1, int en2){
4  // Pin initialization
5  pwm1A = ph1A;
6  pwm1B = ph1B;
7  pwm2A = ph2A;
8  pwm2B = ph2B;
9 
10  // enable_pin pin
11  enable_pin1 = en1;
12  enable_pin2 = en2;
13 
14  // default power-supply value
17 
18 }
19 
20 // enable motor driver
22  // enable_pin the driver - if enable_pin pin available
23  if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, HIGH);
24  if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, HIGH);
25  // set zero to PWM
26  setPwm(0,0);
27 }
28 
29 // disable motor driver
31 {
32  // set zero to PWM
33  setPwm(0, 0);
34  // disable the driver - if enable_pin pin available
35  if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, LOW);
36  if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, LOW);
37 
38 }
39 
40 // init hardware pins
42  // a bit of separation
43  _delay(1000);
44 
45  // PWM pins
46  pinMode(pwm1A, OUTPUT);
47  pinMode(pwm1B, OUTPUT);
48  pinMode(pwm2A, OUTPUT);
49  pinMode(pwm2B, OUTPUT);
50  if( _isset(enable_pin1) ) pinMode(enable_pin1, OUTPUT);
51  if( _isset(enable_pin2) ) pinMode(enable_pin2, OUTPUT);
52 
53  // sanity check for the voltage limit configuration
55 
56  // Set the pwm frequency to the pins
57  // hardware specific function - depending on driver and mcu
59  return 0;
60 }
61 
62 
63 // Set voltage to the pwm pin
64 void StepperDriver4PWM::setPwm(float Ualpha, float Ubeta) {
65  float duty_cycle1A(0.0),duty_cycle1B(0.0),duty_cycle2A(0.0),duty_cycle2B(0.0);
66  // limit the voltage in driver
67  Ualpha = _constrain(Ualpha, -voltage_limit, voltage_limit);
68  Ubeta = _constrain(Ubeta, -voltage_limit, voltage_limit);
69  // hardware specific writing
70  if( Ualpha > 0 )
71  duty_cycle1B = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0);
72  else
73  duty_cycle1A = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0);
74 
75  if( Ubeta > 0 )
76  duty_cycle2B = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0);
77  else
78  duty_cycle2A = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0);
79  // write to hardware
80  _writeDutyCycle4PWM(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B);
81 }
_configure4PWM
void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B)
Definition: drivers/hardware_specific/generic_mcu.cpp:40
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
_constrain
#define _constrain(amt, low, high)
Definition: foc_utils.h:9
StepperDriver4PWM::enable_pin2
int enable_pin2
enable pin number phase 2
Definition: StepperDriver4PWM.h:40
_isset
#define _isset(a)
Definition: foc_utils.h:11
_delay
void _delay(unsigned long ms)
Definition: time_utils.cpp:5
StepperDriver4PWM::pwm2B
int pwm2B
phase 2B pwm pin number
Definition: StepperDriver4PWM.h:38
StepperDriver4PWM.h
StepperDriver4PWM::init
int init() override
Definition: StepperDriver4PWM.cpp:41
StepperDriver::pwm_frequency
long pwm_frequency
pwm frequency value in hertz
Definition: StepperDriver.h:14
StepperDriver4PWM::disable
void disable() override
Definition: StepperDriver4PWM.cpp:30
_writeDutyCycle4PWM
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B)
Definition: drivers/hardware_specific/generic_mcu.cpp:74
DEF_POWER_SUPPLY
#define DEF_POWER_SUPPLY
default power supply voltage
Definition: defaults.h:4
StepperDriver4PWM::enable
void enable() override
Definition: StepperDriver4PWM.cpp:21
StepperDriver4PWM::pwm2A
int pwm2A
phase 2A pwm pin number
Definition: StepperDriver4PWM.h:37
StepperDriver4PWM::StepperDriver4PWM
StepperDriver4PWM(int ph1A, int ph1B, int ph2A, int ph2B, int en1=NOT_SET, int en2=NOT_SET)
Definition: StepperDriver4PWM.cpp:3
StepperDriver4PWM::pwm1B
int pwm1B
phase 1B pwm pin number
Definition: StepperDriver4PWM.h:36
StepperDriver::voltage_power_supply
float voltage_power_supply
power supply voltage
Definition: StepperDriver.h:15
StepperDriver4PWM::setPwm
void setPwm(float Ua, float Ub) override
Definition: StepperDriver4PWM.cpp:64
StepperDriver4PWM::pwm1A
int pwm1A
phase 1A pwm pin number
Definition: StepperDriver4PWM.h:35
StepperDriver4PWM::enable_pin1
int enable_pin1
enable pin number phase 1
Definition: StepperDriver4PWM.h:39