JMotor
Loading...
Searching...
No Matches
JMotorDriverEsp32HBridge.h
Go to the documentation of this file.
1#ifndef J_MOTOR_DRIVER_ESP32_HBRIDGE_H
2#define J_MOTOR_DRIVER_ESP32_HBRIDGE_H
3#include "JMotorDriver.h"
4#include <Arduino.h>
12protected:
13 bool enabled = false;
14 bool reverse;
16
20
21 byte pinPos;
22 byte pinNeg;
23 byte ch;
24
25public:
39 JMotorDriverEsp32HBridge(byte _ledCChannel, byte _pinPos, byte _pinNeg, bool _reverse = false, int _freq = 2000, int _resolution = 12, bool _invertSignals = false)
40 {
41 pinPos = _pinPos;
42 pinNeg = _pinNeg;
43 PWM_FREQ = _freq;
44 PWM_RES = _resolution;
45 ch = _ledCChannel;
46 enabled = false;
47 reverse = _reverse;
48 invertSignals = _invertSignals;
49 PWM_RANGE = (1 << PWM_RES) - 1;
50 }
51 bool set(float val)
52 {
53 if (reverse) {
54 val = -val;
55 }
56 if (enabled) {
57 val = val * PWM_RANGE;
58 val = constrain(val, -PWM_RANGE, PWM_RANGE);
59 if (val == 0) {
60 ledcDetachPin(pinPos);
61 ledcDetachPin(pinNeg);
62 write(pinPos, LOW);
63 write(pinNeg, LOW);
64 } else if (val > 0) {
65 ledcDetachPin(pinNeg);
66 ledcAttachPin(pinPos, ch);
67 writePWM(ch, val);
68 write(pinNeg, LOW);
69 } else {
70 ledcDetachPin(pinPos);
71 ledcAttachPin(pinNeg, ch);
72 writePWM(ch, -val);
73 write(pinPos, LOW);
74 }
75 }
76 return abs(val) < 1.0;
77 }
78 bool setEnable(bool _enable)
79 {
80 if (_enable) {
81 if (!enabled) {
82 // actually enable
83 ledcDetachPin(pinPos);
84 ledcDetachPin(pinNeg);
85 ledcSetup(ch, PWM_FREQ, PWM_RES);
86 write(pinPos, LOW);
87 write(pinNeg, LOW);
88 enabled = true;
89 return true;
90 }
91 } else { // disable
92 if (enabled) {
93 // actually disable
94 enabled = false;
95 ledcDetachPin(pinPos);
96 ledcDetachPin(pinNeg);
97 write(pinPos, LOW);
98 write(pinNeg, LOW);
99 return true;
100 }
101 }
102 return false;
103 }
111 void setFrequencyAndResolution(int freq = 2000, int resBits = 12)
112 {
113 if (freq == PWM_FREQ && resBits == PWM_RES) {
114 return; // already set
115 }
116 PWM_FREQ = freq;
117 PWM_RES = resBits;
118 PWM_RANGE = (1 << PWM_RES) - 1;
119
120 ledcDetachPin(pinPos);
121 ledcDetachPin(pinNeg);
122 ledcSetup(ch, PWM_FREQ, PWM_RES);
123 digitalWrite(pinPos, LOW);
124 digitalWrite(pinNeg, LOW);
125 return;
126 }
127
129 {
130 return enabled;
131 }
133 {
134 return 1.0;
135 }
137 {
138 return -1.0;
139 }
140
141protected:
145 void write(byte pin, bool state)
146 {
147 if (invertSignals) {
148 state = !state;
149 }
150 digitalWrite(pin, state);
151 }
155 void writePWM(byte ch, int val)
156 {
157 if (invertSignals) {
158 val = PWM_RANGE - val;
159 }
160 ledcWrite(ch, val);
161 }
162};
163#endif // J_MOTOR_DRIVER_ESP32_HBRIDGE_H
Controls an H-bridge motor driver with two pins When wiring to an L293D or similar motor driver,...
Definition JMotorDriverEsp32HBridge.h:11
int PWM_RES
Definition JMotorDriverEsp32HBridge.h:18
byte ch
Definition JMotorDriverEsp32HBridge.h:23
float getMaxRange()
high end of the range
Definition JMotorDriverEsp32HBridge.h:132
int PWM_RANGE
Definition JMotorDriverEsp32HBridge.h:19
JMotorDriverEsp32HBridge(byte _ledCChannel, byte _pinPos, byte _pinNeg, bool _reverse=false, int _freq=2000, int _resolution=12, bool _invertSignals=false)
Controls an H-bridge motor driver with two pins When wiring to an L293D or similar motor driver,...
Definition JMotorDriverEsp32HBridge.h:39
bool set(float val)
set motor power
Definition JMotorDriverEsp32HBridge.h:51
bool invertSignals
Definition JMotorDriverEsp32HBridge.h:15
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverEsp32HBridge.h:78
float getMinRange()
low end of the range
Definition JMotorDriverEsp32HBridge.h:136
bool reverse
Definition JMotorDriverEsp32HBridge.h:14
void writePWM(byte ch, int val)
just ledcWrite, but with invertSignals
Definition JMotorDriverEsp32HBridge.h:155
byte pinNeg
Definition JMotorDriverEsp32HBridge.h:22
bool getEnable()
get the enable state of the driver
Definition JMotorDriverEsp32HBridge.h:128
int PWM_FREQ
Definition JMotorDriverEsp32HBridge.h:17
bool enabled
Definition JMotorDriverEsp32HBridge.h:13
void setFrequencyAndResolution(int freq=2000, int resBits=12)
set frequency of pwm
Definition JMotorDriverEsp32HBridge.h:111
byte pinPos
Definition JMotorDriverEsp32HBridge.h:21
void write(byte pin, bool state)
just digitalWrite, but with invertSignals
Definition JMotorDriverEsp32HBridge.h:145
defines common interface for all types of JMotorDrivers
Definition JMotorDriver.h:10