Rough API and initial code without testing.
This commit is contained in:
parent
984f12b9fc
commit
1bd8a68f01
|
@ -0,0 +1,76 @@
|
|||
#include "TB6600MotorDriver.h"
|
||||
|
||||
TB6600MotorDriver::TB6600MotorDriver() {
|
||||
//
|
||||
}
|
||||
|
||||
TB6600MotorDriver::TB6600MotorDriver(uint8_t enablePin, uint8_t directionPin, uint8_t pulsePin, uint32_t usPulse, uint8_t microsteps) {
|
||||
_enablePin = enablePin;
|
||||
_directionPin = directionPin;
|
||||
_pulsePin = pulsePin;
|
||||
|
||||
_usPulse = usPulse;
|
||||
_microsteps = microsteps;
|
||||
_revsteps = 200 * microsteps;
|
||||
}
|
||||
|
||||
|
||||
void TB6600MotorDriver::setup() {
|
||||
if (_enablePin != 0) {
|
||||
pinMode(_enablePin, OUTPUT);
|
||||
}
|
||||
pinMode(_directionPin, OUTPUT);
|
||||
pinMode(_pulsePin, OUTPUT);
|
||||
|
||||
digitalWrite(_directionPin, LOW);
|
||||
digitalWrite(_enablePin, HIGH);
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::setDirection(uint8_t direction) {
|
||||
if (direction != _direction) {
|
||||
_direction = direction;
|
||||
_setDirection();
|
||||
}
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::_setDirection{
|
||||
digitalWrite(_directionPin, _direction ? LOW : HIGH);
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::setSpeed(uint16_t rpm) {
|
||||
_usPulse = 60000000 / ((uint32_t) revsteps * (uint32_t) rpm);
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::steps(uint64_t stepCount) {
|
||||
for (uint64_t i = 0; i < stepCount; i++) {
|
||||
_step();
|
||||
}
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::_step() {
|
||||
digitalWrite(_pulsePin, HIGH);
|
||||
delayMicroseconds(_usPulse);
|
||||
digitalWrite(_pulsePin, LOW);
|
||||
delayMicroseconds(_usPulse);
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::step() {
|
||||
_step();
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::release() {
|
||||
_enabled = false;
|
||||
_setEnable();
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::enable() {
|
||||
_enabled = true;
|
||||
_setEnable();
|
||||
}
|
||||
|
||||
void TB6600MotorDriver::_setEnable() {
|
||||
if (_enablePin != 0) {
|
||||
digitalWrite(_enablePin, _enabled ? HIGH : LOW);
|
||||
}
|
||||
}
|
||||
|
|
@ -4,67 +4,48 @@
|
|||
#include <Arduino.h>
|
||||
|
||||
/**
|
||||
* D2 X Step
|
||||
* D3 X Direction
|
||||
* D4 X MS1 setting
|
||||
* D5 X MS2 setting
|
||||
* D6 Y Step
|
||||
* D7 Y Direction
|
||||
* D8 Y MS1 setting
|
||||
* D9 Y MS2 setting
|
||||
*
|
||||
* MS1(X/Y) MS2(X/Y) Description
|
||||
* L L Full step
|
||||
* H L Half step
|
||||
* L H Quarter step
|
||||
* H H Eighth STEP
|
||||
* Default pins
|
||||
* D6 Enable +
|
||||
* D7 Direction +
|
||||
* D8 Pulse +
|
||||
**/
|
||||
|
||||
class TB6600MotorDriver {
|
||||
private:
|
||||
|
||||
volatile uint8_t _enablePin = 0; //0 is disabled
|
||||
volatile uint8_t _directionPin = 7;
|
||||
volatile uint8_t _pulsePin = 8;
|
||||
|
||||
volatile uint32_t _usPulse = 300;
|
||||
|
||||
const uint8_t _directionA = 3;
|
||||
const uint8_t _directionB = 7;
|
||||
const uint8_t _stepA = 2;
|
||||
const uint8_t _stepB = 6;
|
||||
//physically set, can't change
|
||||
volatile uint8_t _microsteps = 1; //1, 2, 4, 8, 16, 32
|
||||
|
||||
const uint8_t _settingsA1 = 4;
|
||||
const uint8_t _settingsA2 = 5;
|
||||
const uint8_t _settingsB1 = 8;
|
||||
const uint8_t _settingsB2 = 9;
|
||||
volatile uint16_t _revsteps = 200; // # steps per revolution
|
||||
volatile bool _direction = true;
|
||||
volatile bool _enabled = true;
|
||||
|
||||
volatile uint32_t _usStepA = 300;
|
||||
volatile uint32_t _usStepB = 300;
|
||||
|
||||
//const uint8_t _microsteps = 8; //8 or 16
|
||||
volatile uint8_t _modeA = 1; //1, 2, 4, or 8
|
||||
volatile uint8_t _modeB = 1;
|
||||
|
||||
void _single(uint8_t motor);
|
||||
void _micro(uint8_t motor);
|
||||
void _both();
|
||||
void _step();
|
||||
void _setDirection();
|
||||
void _setEnable();
|
||||
|
||||
public:
|
||||
|
||||
IteadDualStepperShield();
|
||||
TB6600MotorDriver();
|
||||
TB6600MotorDriver(uint8_t enablePin, uint8_t directionPin, uint8_t pulsePin, uint32_t usPulse, uint8_t microsteps);
|
||||
|
||||
uint16_t revsteps = 200; // # steps per revolution
|
||||
|
||||
volatile uint8_t directionA = 1;
|
||||
volatile uint8_t directionB = 1;
|
||||
void setup();
|
||||
|
||||
void setDir(uint8_t motor, uint8_t dir);
|
||||
void setSpeed(uint8_t motor, uint16_t speed);
|
||||
void setDirection(uint8_t direction);
|
||||
void setSpeed(uint16_t rpm);
|
||||
|
||||
//full
|
||||
void step(uint8_t motor, uint64_t steps, uint8_t dir);
|
||||
void stepBoth(uint64_t steps);
|
||||
void onestep(uint8_t motor, uint8_t dir);
|
||||
void setStepperMode (uint8_t motor, uint8_t mode);
|
||||
void steps(uint64_t stepCount);
|
||||
void step();
|
||||
|
||||
void enable();
|
||||
void release();
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue