1#ifndef J_MOTOR_DRIVER_AVR_L293_H
2#define J_MOTOR_DRIVER_AVR_L293_H
29 JMotorDriverAvrL293(
byte _en,
byte _i1,
byte _i2,
bool _breakOn =
true,
bool breakWhenDisabled =
false,
bool _reverse =
false)
45 digitalWrite(i2, LOW);
46 digitalWrite(i1, HIGH);
48 digitalWrite(i1, LOW);
49 digitalWrite(i2, HIGH);
51 digitalWrite(i1, HIGH);
52 digitalWrite(i2, HIGH);
60 return abs(val) < 1.0;
70 digitalWrite(i1, LOW);
71 digitalWrite(i2, LOW);
81 digitalWrite(i1, LOW);
82 digitalWrite(i2, LOW);
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