JMotor
Loading...
Searching...
No Matches
JMotorDriverEsp32L293.h
Go to the documentation of this file.
1#ifndef J_MOTOR_DRIVER_ESP32_L293_H
2#define J_MOTOR_DRIVER_ESP32_L293_H
3#include "JMotorDriver.h"
5#include <Arduino.h>
6
13private:
14 bool enabled = false;
15 byte i1;
16 byte i2;
17
18public:
23 bool breakOn;
27 bool reverse;
28
41 JMotorDriverEsp32L293(byte _ch, byte _enablePin, byte _i1, byte _i2, bool _breakOn = true, bool _breakWhenDisabled = false, bool _reverse = false, int _freq = 2000, int _resolution = 12)
42 : pwmDriver { _ch, _enablePin, _freq, _resolution, _breakWhenDisabled }
43 {
44 enabled = false;
45 i1 = _i1;
46 i2 = _i2;
47 breakOn = _breakOn;
48 reverse = _reverse;
49 }
50 bool set(float val)
51 {
52 if (reverse) {
53 val = -val;
54 }
55 if (enabled) {
56 if (val > 0) {
57 digitalWrite(i2, LOW);
58 digitalWrite(i1, HIGH);
59 } else if (val < 0) {
60 digitalWrite(i1, LOW);
61 digitalWrite(i2, HIGH);
62 } else {
63 digitalWrite(i1, LOW);
64 digitalWrite(i2, LOW);
65 }
66 if (breakOn && val == 0) {
67 pwmDriver.set(1); // activate break
68 } else {
69 pwmDriver.set(abs(val));
70 }
71 }
72 return abs(val) < 1.0;
73 }
74 bool setEnable(bool _enable)
75 {
76 if (_enable) {
77 if (!enabled) {
78 // actually enable
79 enabled = true;
80 pinMode(i1, OUTPUT);
81 pinMode(i2, OUTPUT);
82 digitalWrite(i1, LOW);
83 digitalWrite(i2, LOW);
84 pwmDriver.setEnable(true);
85
86 return true;
87 }
88 } else { // disable
89 if (enabled) {
90 // actually disable
91 enabled = false;
92 pinMode(i1, OUTPUT);
93 pinMode(i2, OUTPUT);
94 digitalWrite(i1, LOW);
95 digitalWrite(i2, LOW);
96 pwmDriver.setEnable(false);
97 return true;
98 }
99 }
100 return false;
101 }
103 {
104 return enabled;
105 }
107 {
108 return 1.0;
109 }
111 {
112 return -1.0;
113 }
114};
115#endif
L293 motor driver chip: https://www.ti.com/lit/ds/symlink/l293.pdf also works with L298 drivers or an...
Definition JMotorDriverEsp32L293.h:12
JMotorDriverEsp32PWM pwmDriver
Definition JMotorDriverEsp32L293.h:19
bool set(float val)
set motor power
Definition JMotorDriverEsp32L293.h:50
bool getEnable()
get the enable state of the driver
Definition JMotorDriverEsp32L293.h:102
float getMinRange()
low end of the range
Definition JMotorDriverEsp32L293.h:110
JMotorDriverEsp32L293(byte _ch, byte _enablePin, byte _i1, byte _i2, bool _breakOn=true, bool _breakWhenDisabled=false, bool _reverse=false, int _freq=2000, int _resolution=12)
constructor, sets pins and other settings
Definition JMotorDriverEsp32L293.h:41
float getMaxRange()
high end of the range
Definition JMotorDriverEsp32L293.h:106
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverEsp32L293.h:74
bool reverse
reverse direction of driver
Definition JMotorDriverEsp32L293.h:27
bool breakOn
add extra resistance to motor when set to 0 power (by shorting motor terminals)
Definition JMotorDriverEsp32L293.h:23
uses ledc to output PWM approximation of an analog output ESP32s now have normal analogWrite() so the...
Definition JMotorDriverEsp32PWM.h:10
bool set(float _val)
set motor power
Definition JMotorDriverEsp32PWM.h:72
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverEsp32PWM.h:80
defines common interface for all types of JMotorDrivers
Definition JMotorDriver.h:10