JMotor
Loading...
Searching...
No Matches
JMotorDriverEsp32PWMDir.h
Go to the documentation of this file.
1#ifndef J_MOTOR_DRIVER_ESP32_PWMDIR_H
2#define J_MOTOR_DRIVER_ESP32_PWMDIR_H
3#include "JMotorDriver.h"
5#include <Arduino.h>
11private:
12 bool enabled = false;
13 byte dir;
14
15public:
17 bool reverse = false;
25 JMotorDriverEsp32PWMDir(byte _ch, byte _enablePin, byte _dirPin, bool _rev = false)
26 : pwmDriver { _ch, _enablePin }
27 {
28 enabled = false;
29 dir = _dirPin;
30 }
40 JMotorDriverEsp32PWMDir(byte _ch, byte _enPin, byte _dirPin, int freq, int resolution, bool _rev = false)
41 : pwmDriver { _ch, _enPin, freq, resolution }
42 {
43 enabled = false;
44 dir = _dirPin;
45 }
46 bool set(float val)
47 {
48 if (enabled) {
49 if (val > 0) {
50 digitalWrite(dir, !reverse);
51 } else if (val < 0) {
52 digitalWrite(dir, reverse);
53 } else {
54 }
55 pwmDriver.set(abs(val));
56 }
57 return abs(val) < 1.0;
58 }
59 bool setEnable(bool _enable)
60 {
61 if (_enable) {
62 if (!enabled) {
63 // actually enable
64 enabled = true;
65 pinMode(dir, OUTPUT);
66 pwmDriver.setEnable(true);
67 return true;
68 }
69 } else { // disable
70 if (enabled) {
71 // actually disable
72 enabled = false;
73 pwmDriver.setEnable(false);
74 return true;
75 }
76 }
77 return false;
78 }
79 bool getEnable()
80 {
81 return enabled;
82 }
84 {
85 return 1.0;
86 }
88 {
89 return -1.0;
90 }
91};
92#endif
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