JMotor
Loading...
Searching...
No Matches
JMotorDriverEsp32PWM.h
Go to the documentation of this file.
1#ifndef J_MOTOR_DRIVER_ESP32_PWM_H
2#define J_MOTOR_DRIVER_ESP32_PWM_H
3#include "JMotorDriver.h"
4#include <Arduino.h>
11private:
12 int PWM_RES = 12;
13 int PWM_FREQ = 2000; // <= int(80E6 / 2^PWM_RES), 2kHz recommended for motor PWM
14 int PWM_RANGE = 4095; // 2^PWM_RES -1
15 bool enabled = false;
16 byte ch;
17 byte pin;
18
19public:
20 bool disableState = LOW;
27 JMotorDriverEsp32PWM(byte _ch, byte _pin, bool _disableState = LOW)
28 {
29 enabled = false;
30 ch = _ch;
31 pin = _pin;
32 disableState = _disableState;
33 }
42 JMotorDriverEsp32PWM(byte _ch, byte _pin, int freq, int resolution, bool _disableState = LOW)
43 {
44 enabled = false;
45 ch = _ch;
46 pin = _pin;
47 disableState = _disableState;
48 PWM_RES = resolution;
49 PWM_FREQ = freq;
50 PWM_RANGE = (1 << PWM_RES) - 1;
51 }
58 void setFrequencyAndResolution(int freq = 2000, int resBits = 12)
59 {
60 if (freq == PWM_FREQ && resBits == PWM_RES) {
61 return; // already set
62 }
63 PWM_FREQ = freq;
64 PWM_RES = resBits;
65 PWM_RANGE = (1 << PWM_RES) - 1;
66 ledcDetachPin(pin);
67 ledcSetup(ch, PWM_FREQ, PWM_RES);
68 if (enabled)
69 ledcAttachPin(pin, ch);
70 return;
71 }
72 bool set(float _val)
73 {
74 if (enabled) {
75 int val = constrain(_val * PWM_RANGE, 0, PWM_RANGE);
76 ledcWrite(ch, val);
77 }
78 return (_val > 0) && (_val < 1.0);
79 }
80 bool setEnable(bool _enable)
81 {
82 if (_enable) {
83 if (!enabled) {
84 // actually enable
85 enabled = true;
86 ledcDetachPin(pin);
87 ledcSetup(ch, PWM_FREQ, PWM_RES);
88 ledcAttachPin(pin, ch);
89 ledcWrite(ch, !disableState ? 0 : PWM_RANGE); // set disable state to start with
90 return true;
91 }
92 } else { // disable
93 if (enabled) {
94 // actually disable
95 enabled = false;
96 ledcDetachPin(pin);
97 pinMode(pin, OUTPUT);
98 digitalWrite(pin, disableState);
99 return true;
100 }
101 }
102 return false;
103 }
105 {
106 return enabled;
107 }
109 {
110 return 1.0;
111 }
113 {
114 return 0;
115 }
116};
117#endif
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