1#ifndef J_MOTOR_DRIVER_ESP32_L293_H
2#define J_MOTOR_DRIVER_ESP32_L293_H
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 }
57 digitalWrite(i2, LOW);
58 digitalWrite(i1, HIGH);
60 digitalWrite(i1, LOW);
61 digitalWrite(i2, HIGH);
63 digitalWrite(i1, LOW);
64 digitalWrite(i2, LOW);
72 return abs(val) < 1.0;
82 digitalWrite(i1, LOW);
83 digitalWrite(i2, LOW);
94 digitalWrite(i1, LOW);
95 digitalWrite(i2, LOW);
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