uses ledc to output PWM approximation of an analog output ESP32s now have normal analogWrite() so the "Avr" driver will work, but this driver gives a bit more control over resolution and frequency.
More...
#include <JMotorDriverEsp32PWM.h>
|
| | JMotorDriverEsp32PWM (byte _ch, byte _pin, bool _disableState=LOW) |
| | constructor, sets pins, default PWM
|
| |
| | JMotorDriverEsp32PWM (byte _ch, byte _pin, int freq, int resolution, bool _disableState=LOW) |
| | constructor, sets pins, custom PWM settings
|
| |
| void | setFrequencyAndResolution (int freq=2000, int resBits=12) |
| | set frequency of pwm
|
| |
| bool | set (float _val) |
| | set motor power
|
| |
| bool | setEnable (bool _enable) |
| | use to enable or disable a motor, and sets up pin states
|
| |
| 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
|
| |
uses ledc to output PWM approximation of an analog output ESP32s now have normal analogWrite() so the "Avr" driver will work, but this driver gives a bit more control over resolution and frequency.
- Note
- platform: ESP32
◆ JMotorDriverEsp32PWM() [1/2]
| JMotorDriverEsp32PWM::JMotorDriverEsp32PWM |
( |
byte |
_ch, |
|
|
byte |
_pin, |
|
|
bool |
_disableState = LOW |
|
) |
| |
|
inline |
constructor, sets pins, default PWM
- Parameters
-
| _ch | ledc channel (must be unique for each driver) |
| _pin | pin to output signal on |
| _disableState | = LOW: when disabled, set pin LOW(default) or HIGH |
◆ JMotorDriverEsp32PWM() [2/2]
| JMotorDriverEsp32PWM::JMotorDriverEsp32PWM |
( |
byte |
_ch, |
|
|
byte |
_pin, |
|
|
int |
freq, |
|
|
int |
resolution, |
|
|
bool |
_disableState = LOW |
|
) |
| |
|
inline |
constructor, sets pins, custom PWM settings
- Parameters
-
| _ch | ledc channel (must be unique for each driver) |
| _pin | pin to output signal on |
| freq | <= int(80E6 / 2^resolution), 2kHz default and recommended for motor PWM |
| resolution | bits of resolution, tradeoff with frequency, default 12 |
| _disableState | = LOw: when disabled, set pin LOW(default) or HIGH |
◆ getEnable()
| bool JMotorDriverEsp32PWM::getEnable |
( |
| ) |
|
|
inlinevirtual |
get the enable state of the driver
- Return values
-
| (bool) | true if enabled, false if disabled |
Reimplemented from JMotorDriver.
◆ getMaxRange()
| float JMotorDriverEsp32PWM::getMaxRange |
( |
| ) |
|
|
inlinevirtual |
high end of the range
- Note
- usually 1.0
- Return values
-
Reimplemented from JMotorDriver.
◆ getMinRange()
| float JMotorDriverEsp32PWM::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 JMotorDriverEsp32PWM::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 JMotorDriverEsp32PWM::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 JMotorDriverEsp32PWM::setFrequencyAndResolution |
( |
int |
freq = 2000, |
|
|
int |
resBits = 12 |
|
) |
| |
|
inline |
set frequency of pwm
- Parameters
-
| freq | Hz (default 2000) must be <= int(80E6 / 2^resBits) |
| resBits | (default 12) tradeoff with max available frequency |
- Return values
-
◆ disableState
| bool JMotorDriverEsp32PWM::disableState = LOW |
The documentation for this class was generated from the following file: