JMotor
Loading...
Searching...
No Matches
JMotorDriverAvrHBridge.h
Go to the documentation of this file.
1#ifndef JMOTOR_DRIVER_AVR_HBRIDGE_H
2#define JMOTOR_DRIVER_AVR_HBRIDGE_H
3#include "JMotorDriver.h"
5#include <Arduino.h>
7private:
8 bool enabled = false;
9
10public:
13 bool reverse;
14 // TODO: COMMENT
15 JMotorDriverAvrHBridge(byte _pinPos, byte _pinNeg, bool _reverse = false)
16 : pwmDriverPos { _pinPos, LOW }
17 , pwmDriverNeg { _pinNeg, LOW }
18 {
19 enabled = false;
20 reverse = _reverse;
21 }
22 bool set(float val)
23 {
24 if (reverse) {
25 val = -val;
26 }
27 if (enabled) {
28 if (val > 0) {
30 pwmDriverPos.set(val);
31 } else if (val < 0) {
33 pwmDriverNeg.set(-val);
34 } else {
37 }
38 }
39 return abs(val) < 1.0;
40 }
41 bool setEnable(bool _enable)
42 {
43 if (_enable) {
44 if (!enabled) {
45 // actually enable
46 enabled = true;
49 return true;
50 }
51 } else { // disable
52 if (enabled) {
53 // actually disable
54 enabled = false;
57 return true;
58 }
59 }
60 return false;
61 }
62 bool getEnable()
63 {
64 return enabled;
65 }
67 {
68 return 1.0;
69 }
71 {
72 return -1.0;
73 }
74};
75#endif // JMOTOR_DRIVER_AVR_HBRIDGE_H
Definition JMotorDriverAvrHBridge.h:6
float getMaxRange()
high end of the range
Definition JMotorDriverAvrHBridge.h:66
JMotorDriverAvrHBridge(byte _pinPos, byte _pinNeg, bool _reverse=false)
Definition JMotorDriverAvrHBridge.h:15
bool set(float val)
set motor power
Definition JMotorDriverAvrHBridge.h:22
JMotorDriverAvrPWM pwmDriverNeg
Definition JMotorDriverAvrHBridge.h:12
bool reverse
Definition JMotorDriverAvrHBridge.h:13
JMotorDriverAvrPWM pwmDriverPos
Definition JMotorDriverAvrHBridge.h:11
float getMinRange()
low end of the range
Definition JMotorDriverAvrHBridge.h:70
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverAvrHBridge.h:41
bool getEnable()
get the enable state of the driver
Definition JMotorDriverAvrHBridge.h:62
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