1#ifndef J_MOTOR_DRIVER_ESP32_PWMDIR_H
2#define J_MOTOR_DRIVER_ESP32_PWMDIR_H
41 :
pwmDriver { _ch, _enPin, freq, resolution }
57 return abs(val) < 1.0;
for motor controllers with one direction input and one speed input pin
Definition JMotorDriverEsp32PWMDir.h:10
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverEsp32PWMDir.h:59
JMotorDriverEsp32PWM pwmDriver
Definition JMotorDriverEsp32PWMDir.h:16
float getMaxRange()
high end of the range
Definition JMotorDriverEsp32PWMDir.h:83
float getMinRange()
low end of the range
Definition JMotorDriverEsp32PWMDir.h:87
bool getEnable()
get the enable state of the driver
Definition JMotorDriverEsp32PWMDir.h:79
bool set(float val)
set motor power
Definition JMotorDriverEsp32PWMDir.h:46
JMotorDriverEsp32PWMDir(byte _ch, byte _enPin, byte _dirPin, int freq, int resolution, bool _rev=false)
constructor, sets pins, custom PWM settings
Definition JMotorDriverEsp32PWMDir.h:40
bool reverse
Definition JMotorDriverEsp32PWMDir.h:17
JMotorDriverEsp32PWMDir(byte _ch, byte _enablePin, byte _dirPin, bool _rev=false)
constructor, sets pins, default PWM
Definition JMotorDriverEsp32PWMDir.h:25
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