Controls an H-bridge motor driver with two pins When wiring to an L293D or similar motor driver, connect the enable pin to 5 volts, and the two other input pins to the ESP32. Unlike JMotorDriverEsp32L293, this driver uses two pins to control the motor. Unlike JMotorDriverEsp32HBridgeTwoLedcChannels, this driver uses a single LEDc channel, so this is better than JMotorDriverEsp32HBridgeTwoLedcChannels.
More...
#include <JMotorDriverEsp32HBridge.h>
|
| JMotorDriverEsp32HBridge (byte _ledCChannel, byte _pinPos, byte _pinNeg, bool _reverse=false, int _freq=2000, int _resolution=12, bool _invertSignals=false) |
| Controls an H-bridge motor driver with two pins When wiring to an L293D or similar motor driver, connect the enable pin to 5 volts, and the two other input pins to the ESP32. Unlike JMotorDriverEsp32L293, this driver uses two pins to control the motor. Unlike JMotorDriverEsp32HBridgeTwoChannels, this driver uses a single LEDc channel, so this is better than JMotorDriverEsp32HBridge.
|
|
bool | set (float val) |
| set motor power
|
|
bool | setEnable (bool _enable) |
| use to enable or disable a motor, and sets up pin states
|
|
void | setFrequencyAndResolution (int freq=2000, int resBits=12) |
| set frequency of pwm
|
|
bool | getEnable () |
| get the enable state of the driver
|
|
float | getMaxRange () |
| high end of the range
|
|
float | getMinRange () |
| low end of the range
|
|
bool | enable () |
| enable motor
|
|
bool | disable () |
| disable motor
|
|
|
void | write (byte pin, bool state) |
| just digitalWrite, but with invertSignals
|
|
void | writePWM (byte ch, int val) |
| just ledcWrite, but with invertSignals
|
|
Controls an H-bridge motor driver with two pins When wiring to an L293D or similar motor driver, connect the enable pin to 5 volts, and the two other input pins to the ESP32. Unlike JMotorDriverEsp32L293, this driver uses two pins to control the motor. Unlike JMotorDriverEsp32HBridgeTwoLedcChannels, this driver uses a single LEDc channel, so this is better than JMotorDriverEsp32HBridgeTwoLedcChannels.
◆ JMotorDriverEsp32HBridge()
JMotorDriverEsp32HBridge::JMotorDriverEsp32HBridge |
( |
byte |
_ledCChannel, |
|
|
byte |
_pinPos, |
|
|
byte |
_pinNeg, |
|
|
bool |
_reverse = false , |
|
|
int |
_freq = 2000 , |
|
|
int |
_resolution = 12 , |
|
|
bool |
_invertSignals = false |
|
) |
| |
|
inline |
Controls an H-bridge motor driver with two pins When wiring to an L293D or similar motor driver, connect the enable pin to 5 volts, and the two other input pins to the ESP32. Unlike JMotorDriverEsp32L293, this driver uses two pins to control the motor. Unlike JMotorDriverEsp32HBridgeTwoChannels, this driver uses a single LEDc channel, so this is better than JMotorDriverEsp32HBridge.
- Parameters
-
_ledCChannel | ledc channel (must be unique for each driver) |
_pinPos | positive direction pin of motor driver |
_pinNeg | negative direction pin of motor driver |
_reverse | invert values (default false) |
_freq | Hz (default 2000) must be <= int(80E6 / 2^resBits) |
_resolution | bits of resolution, tradeoff with frequency, default 12 |
_invertSignals | invert signals on both pinPos and pinNeg (default false) |
◆ getEnable()
bool JMotorDriverEsp32HBridge::getEnable |
( |
| ) |
|
|
inlinevirtual |
get the enable state of the driver
- Return values
-
(bool) | true if enabled, false if disabled |
Reimplemented from JMotorDriver.
◆ getMaxRange()
float JMotorDriverEsp32HBridge::getMaxRange |
( |
| ) |
|
|
inlinevirtual |
high end of the range
- Note
- usually 1.0
- Return values
-
Reimplemented from JMotorDriver.
◆ getMinRange()
float JMotorDriverEsp32HBridge::getMinRange |
( |
| ) |
|
|
inlinevirtual |
low end of the range
- Note
- usually -1.0, if 0, that indicates a motor controller with no reverse function
- Return values
-
Reimplemented from JMotorDriver.
◆ set()
bool JMotorDriverEsp32HBridge::set |
( |
float |
val | ) |
|
|
inlinevirtual |
set motor power
- Note
- val should be between getMinRange and getMaxRange, but constrained internally
- Parameters
-
- Return values
-
(bool) | false if at end of power range, true otherwise |
Reimplemented from JMotorDriver.
◆ setEnable()
bool JMotorDriverEsp32HBridge::setEnable |
( |
bool |
_enable | ) |
|
|
inlinevirtual |
use to enable or disable a motor, and sets up pin states
- Note
- setEnable(true) must be called before a motor driver will activate
- Parameters
-
_enable | (bool) true=enable, false=disable |
- Return values
-
(bool) | true if state changed, false if state already set |
Reimplemented from JMotorDriver.
◆ setFrequencyAndResolution()
void JMotorDriverEsp32HBridge::setFrequencyAndResolution |
( |
int |
freq = 2000 , |
|
|
int |
resBits = 12 |
|
) |
| |
|
inline |
set frequency of pwm
- Note
- side effect: this function turns the motor off, so call set again right after this if you want the motor to turn on again.
- Parameters
-
freq | Hz (default 2000) must be <= int(80E6 / 2^resBits) |
resBits | (default 12) tradeoff with max available frequency |
- Return values
-
◆ write()
void JMotorDriverEsp32HBridge::write |
( |
byte |
pin, |
|
|
bool |
state |
|
) |
| |
|
inlineprotected |
just digitalWrite, but with invertSignals
◆ writePWM()
void JMotorDriverEsp32HBridge::writePWM |
( |
byte |
ch, |
|
|
int |
val |
|
) |
| |
|
inlineprotected |
just ledcWrite, but with invertSignals
◆ ch
byte JMotorDriverEsp32HBridge::ch |
|
protected |
◆ enabled
bool JMotorDriverEsp32HBridge::enabled = false |
|
protected |
◆ invertSignals
bool JMotorDriverEsp32HBridge::invertSignals |
|
protected |
◆ pinNeg
byte JMotorDriverEsp32HBridge::pinNeg |
|
protected |
◆ pinPos
byte JMotorDriverEsp32HBridge::pinPos |
|
protected |
◆ PWM_FREQ
int JMotorDriverEsp32HBridge::PWM_FREQ |
|
protected |
◆ PWM_RANGE
int JMotorDriverEsp32HBridge::PWM_RANGE |
|
protected |
◆ PWM_RES
int JMotorDriverEsp32HBridge::PWM_RES |
|
protected |
◆ reverse
bool JMotorDriverEsp32HBridge::reverse |
|
protected |
The documentation for this class was generated from the following file: