1#ifndef J_MOTOR_DRIVER_ESP32_PWM_H
2#define J_MOTOR_DRIVER_ESP32_PWM_H
50 PWM_RANGE = (1 << PWM_RES) - 1;
60 if (freq == PWM_FREQ && resBits == PWM_RES) {
65 PWM_RANGE = (1 << PWM_RES) - 1;
67 ledcSetup(ch, PWM_FREQ, PWM_RES);
69 ledcAttachPin(pin, ch);
75 int val = constrain(_val * PWM_RANGE, 0, PWM_RANGE);
78 return (_val > 0) && (_val < 1.0);
87 ledcSetup(ch, PWM_FREQ, PWM_RES);
88 ledcAttachPin(pin, ch);
uses ledc to output PWM approximation of an analog output ESP32s now have normal analogWrite() so the...
Definition JMotorDriverEsp32PWM.h:10
void setFrequencyAndResolution(int freq=2000, int resBits=12)
set frequency of pwm
Definition JMotorDriverEsp32PWM.h:58
JMotorDriverEsp32PWM(byte _ch, byte _pin, int freq, int resolution, bool _disableState=LOW)
constructor, sets pins, custom PWM settings
Definition JMotorDriverEsp32PWM.h:42
float getMinRange()
low end of the range
Definition JMotorDriverEsp32PWM.h:112
bool disableState
Definition JMotorDriverEsp32PWM.h:20
JMotorDriverEsp32PWM(byte _ch, byte _pin, bool _disableState=LOW)
constructor, sets pins, default PWM
Definition JMotorDriverEsp32PWM.h:27
bool set(float _val)
set motor power
Definition JMotorDriverEsp32PWM.h:72
bool getEnable()
get the enable state of the driver
Definition JMotorDriverEsp32PWM.h:104
float getMaxRange()
high end of the range
Definition JMotorDriverEsp32PWM.h:108
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