1#ifndef JMOTOR_DRIVER_AVR_HBRIDGE_H
2#define JMOTOR_DRIVER_AVR_HBRIDGE_H
39 return abs(val) < 1.0;
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