JMotor
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
JMotorDriverEsp32PWM Class Reference

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>

Inheritance diagram for JMotorDriverEsp32PWM:
Inheritance graph
[legend]
Collaboration diagram for JMotorDriverEsp32PWM:
Collaboration graph
[legend]

Public Member Functions

 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
 
- Public Member Functions inherited from JMotorDriver
bool enable ()
 enable motor
 
bool disable ()
 disable motor
 

Public Attributes

bool disableState = LOW
 

Detailed Description

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

Constructor & Destructor Documentation

◆ JMotorDriverEsp32PWM() [1/2]

JMotorDriverEsp32PWM::JMotorDriverEsp32PWM ( byte  _ch,
byte  _pin,
bool  _disableState = LOW 
)
inline

constructor, sets pins, default PWM

Parameters
_chledc channel (must be unique for each driver)
_pinpin 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
_chledc channel (must be unique for each driver)
_pinpin to output signal on
freq<= int(80E6 / 2^resolution), 2kHz default and recommended for motor PWM
resolutionbits of resolution, tradeoff with frequency, default 12
_disableState= LOw: when disabled, set pin LOW(default) or HIGH

Member Function Documentation

◆ 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
(float)maxRange

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
(float)minRange

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
val(float) val
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
freqHz (default 2000) must be <= int(80E6 / 2^resBits)
resBits(default 12) tradeoff with max available frequency
Return values
none

Member Data Documentation

◆ disableState

bool JMotorDriverEsp32PWM::disableState = LOW

The documentation for this class was generated from the following file: