JMotor
Loading...
Searching...
No Matches
JMotorDriverAvrPWMDir.h
Go to the documentation of this file.
1#ifndef J_MOTOR_DRIVER_AVR_PWMDIR_H
2#define J_MOTOR_DRIVER_AVR_PWMDIR_H
3#include "JMotorDriver.h"
5#include <Arduino.h>
6
12private:
13 bool enabled = false;
14 byte dir;
15
16public:
17 bool reverse = false;
26 JMotorDriverAvrPWMDir(byte _speedPin, byte _dirPin, bool _rev = false)
27 : pwmDriver { _speedPin }
28 {
29 enabled = false;
30 dir = _dirPin;
31 reverse = _rev;
32 }
33 bool set(float val)
34 {
35 if (enabled) {
36 if (val > 0) {
37 digitalWrite(dir, !reverse);
38 } else if (val < 0) {
39 digitalWrite(dir, reverse);
40 }
41 pwmDriver.set(abs(val));
42 }
43 return abs(val) < 1.0;
44 }
45 bool setEnable(bool _enable)
46 {
47 if (_enable) {
48 if (!enabled) {
49 // actually enable
50 enabled = true;
51 pinMode(dir, OUTPUT);
52 pwmDriver.setEnable(true);
53 return true;
54 }
55 } else { // disable
56 if (enabled) {
57 // actually disable
58 enabled = false;
59 pwmDriver.setEnable(false);
60 return true;
61 }
62 }
63 return false;
64 }
65 bool getEnable()
66 {
67 return enabled;
68 }
70 {
71 return 1.0;
72 }
74 {
75 return -1.0;
76 }
77};
78
79#endif
for motor controllers with one direction input and one speed input pin
Definition JMotorDriverAvrPWMDir.h:11
float getMaxRange()
high end of the range
Definition JMotorDriverAvrPWMDir.h:69
float getMinRange()
low end of the range
Definition JMotorDriverAvrPWMDir.h:73
JMotorDriverAvrPWM pwmDriver
Definition JMotorDriverAvrPWMDir.h:18
bool reverse
Definition JMotorDriverAvrPWMDir.h:17
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverAvrPWMDir.h:45
bool getEnable()
get the enable state of the driver
Definition JMotorDriverAvrPWMDir.h:65
bool set(float val)
set motor power
Definition JMotorDriverAvrPWMDir.h:33
JMotorDriverAvrPWMDir(byte _speedPin, byte _dirPin, bool _rev=false)
constructor, sets pins
Definition JMotorDriverAvrPWMDir.h:26
wrapper for analogWrite()
Definition JMotorDriverAvrPWM.h:10
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverAvrPWM.h:41
bool set(float _val)
set motor power
Definition JMotorDriverAvrPWM.h:33
defines common interface for all types of JMotorDrivers
Definition JMotorDriver.h:10