JMotor
Loading...
Searching...
No Matches
JMotorDriverAvrL293.h
Go to the documentation of this file.
1#ifndef J_MOTOR_DRIVER_AVR_L293_H
2#define J_MOTOR_DRIVER_AVR_L293_H
3#include "JMotorDriver.h"
5#include <Arduino.h>
11private:
12 bool enabled = false;
13 byte i1;
14 byte i2;
15
16public:
18 bool breakOn; // can be changed while running
19 bool reverse;
29 JMotorDriverAvrL293(byte _en, byte _i1, byte _i2, bool _breakOn = true, bool breakWhenDisabled = false, bool _reverse = false)
30 : pwmDriver { _en, breakWhenDisabled }
31 {
32 enabled = false;
33 i1 = _i1;
34 i2 = _i2;
35 breakOn = _breakOn;
36 reverse = _reverse;
37 }
38 bool set(float val)
39 {
40 if (reverse) {
41 val = -val;
42 }
43 if (enabled) {
44 if (val > 0) {
45 digitalWrite(i2, LOW);
46 digitalWrite(i1, HIGH);
47 } else if (val < 0) {
48 digitalWrite(i1, LOW);
49 digitalWrite(i2, HIGH);
50 } else {
51 digitalWrite(i1, HIGH);
52 digitalWrite(i2, HIGH);
53 }
54 if (breakOn && val == 0) {
55 pwmDriver.set(1); // activate break
56 } else {
57 pwmDriver.set(abs(val));
58 }
59 }
60 return abs(val) < 1.0;
61 }
62 bool setEnable(bool _enable)
63 {
64 if (_enable) {
65 if (!enabled) {
66 // actually enable
67 enabled = true;
68 pinMode(i1, OUTPUT);
69 pinMode(i2, OUTPUT);
70 digitalWrite(i1, LOW);
71 digitalWrite(i2, LOW);
72 pwmDriver.setEnable(true);
73 return true;
74 }
75 } else { // disable
76 if (enabled) {
77 // actually disable
78 enabled = false;
79 pinMode(i1, OUTPUT);
80 pinMode(i2, OUTPUT);
81 digitalWrite(i1, LOW);
82 digitalWrite(i2, LOW);
83 pwmDriver.setEnable(false);
84 return true;
85 }
86 }
87 return false;
88 }
89 bool getEnable()
90 {
91 return enabled;
92 }
94 {
95 return 1.0;
96 }
98 {
99 return -1.0;
100 }
101};
102
103#endif
L293 motor driver chip: https://www.ti.com/lit/ds/symlink/l293.pdf.
Definition JMotorDriverAvrL293.h:10
bool breakOn
Definition JMotorDriverAvrL293.h:18
float getMaxRange()
high end of the range
Definition JMotorDriverAvrL293.h:93
bool getEnable()
get the enable state of the driver
Definition JMotorDriverAvrL293.h:89
bool reverse
Definition JMotorDriverAvrL293.h:19
bool set(float val)
set motor power
Definition JMotorDriverAvrL293.h:38
JMotorDriverAvrL293(byte _en, byte _i1, byte _i2, bool _breakOn=true, bool breakWhenDisabled=false, bool _reverse=false)
constructor, sets pins
Definition JMotorDriverAvrL293.h:29
JMotorDriverAvrPWM pwmDriver
Definition JMotorDriverAvrL293.h:17
bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
Definition JMotorDriverAvrL293.h:62
float getMinRange()
low end of the range
Definition JMotorDriverAvrL293.h:97
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