disabling end stops

pull/59/head
TimEversWw 2017-02-28 22:48:46 +01:00
parent 6dd8ef09a5
commit e0752c2df8
11 changed files with 194 additions and 66 deletions

View File

@ -59,6 +59,10 @@ const long MOVEMENT_TIMEOUT_X_DEFAULT = 120;
const long MOVEMENT_TIMEOUT_Y_DEFAULT = 120;
const long MOVEMENT_TIMEOUT_Z_DEFAULT = 120;
const long MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT = 0;

View File

@ -188,6 +188,10 @@ void ParameterList::loadDefaultValue(int id) {
case MOVEMENT_INVERT_ENDPOINTS_Y : paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT; break;
case MOVEMENT_INVERT_ENDPOINTS_Z : paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT; break;
case MOVEMENT_ENABLE_ENDPOINTS_X : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT; break;
case MOVEMENT_ENABLE_ENDPOINTS_Y : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT; break;
case MOVEMENT_ENABLE_ENDPOINTS_Z : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT; break;
case MOVEMENT_INVERT_MOTOR_X : paramValues[id] = MOVEMENT_INVERT_MOTOR_X_DEFAULT; break;
case MOVEMENT_INVERT_MOTOR_Y : paramValues[id] = MOVEMENT_INVERT_MOTOR_Y_DEFAULT; break;
case MOVEMENT_INVERT_MOTOR_Z : paramValues[id] = MOVEMENT_INVERT_MOTOR_Z_DEFAULT; break;
@ -257,6 +261,9 @@ bool ParameterList::validParam(int id) {
case MOVEMENT_TIMEOUT_X:
case MOVEMENT_TIMEOUT_Y:
case MOVEMENT_TIMEOUT_Z:
case MOVEMENT_ENABLE_ENDPOINTS_X:
case MOVEMENT_ENABLE_ENDPOINTS_Y:
case MOVEMENT_ENABLE_ENDPOINTS_Z:
case MOVEMENT_INVERT_ENDPOINTS_X:
case MOVEMENT_INVERT_ENDPOINTS_Y:
case MOVEMENT_INVERT_ENDPOINTS_Z:

View File

@ -25,6 +25,10 @@ enum ParamListEnum
MOVEMENT_INVERT_ENDPOINTS_Y = 22,
MOVEMENT_INVERT_ENDPOINTS_Z = 23,
MOVEMENT_ENABLE_ENDPOINTS_X = 25,
MOVEMENT_ENABLE_ENDPOINTS_Y = 26,
MOVEMENT_ENABLE_ENDPOINTS_Z = 27,
MOVEMENT_INVERT_MOTOR_X = 31,
MOVEMENT_INVERT_MOTOR_Y = 32,
MOVEMENT_INVERT_MOTOR_Z = 33,

View File

@ -101,9 +101,9 @@ StepperControl::StepperControl() {
encoderY = StepperControlEncoder();
encoderZ = StepperControlEncoder();
encoderX.loadPinNumbers(X_ENCDR_A, X_ENCDR_B, X_ENCDR_A_Q, X_ENCDR_B_Q);
encoderY.loadPinNumbers(Y_ENCDR_A, Y_ENCDR_B, Y_ENCDR_A_Q, Y_ENCDR_B_Q);
encoderZ.loadPinNumbers(Z_ENCDR_A, Z_ENCDR_B, Z_ENCDR_A_Q, Z_ENCDR_B_Q);
encoderX.loadPinNumbers(X_ENCDR_A, X_ENCDR_B);
encoderY.loadPinNumbers(Y_ENCDR_A, Y_ENCDR_B);
encoderZ.loadPinNumbers(Z_ENCDR_A, Z_ENCDR_B);
motorMotorsEnabled = false;
}
@ -113,7 +113,13 @@ void StepperControl::test() {
//encoderX.readEncoder();
//encoderY.readEncoder();
//encoderZ.readEncoder();
reportPosition();
//reportPosition();
//bool test = axisX.endStopMin();
//Serial.print("R99");
//Serial.print(" test = ");
//Serial.print(test);
//Serial.print("\r\n");
}
void StepperControl::test2() {
@ -922,6 +928,10 @@ void StepperControl::loadMotorSettings() {
endStInv[1] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_ENDPOINTS_Y);
endStInv[2] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_ENDPOINTS_Z);
endStEnbl[0] = intToBool(ParameterList::getInstance()->getValue(MOVEMENT_ENABLE_ENDPOINTS_X));
endStEnbl[1] = intToBool(ParameterList::getInstance()->getValue(MOVEMENT_ENABLE_ENDPOINTS_Y));
endStEnbl[2] = intToBool(ParameterList::getInstance()->getValue(MOVEMENT_ENABLE_ENDPOINTS_Z));
timeOut[0] = ParameterList::getInstance()->getValue(MOVEMENT_TIMEOUT_X);
timeOut[1] = ParameterList::getInstance()->getValue(MOVEMENT_TIMEOUT_X);
timeOut[2] = ParameterList::getInstance()->getValue(MOVEMENT_TIMEOUT_X);
@ -934,9 +944,9 @@ void StepperControl::loadMotorSettings() {
motor2Enbl[1] = false;
motor2Enbl[2] = false;
axisX.loadMotorSettings(speedMax[0], speedMin[0], stepsAcc[0], timeOut[0], homeIsUp[0], motorInv[0], endStInv[0], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[0], motor2Inv[0]);
axisY.loadMotorSettings(speedMax[1], speedMin[1], stepsAcc[1], timeOut[1], homeIsUp[1], motorInv[1], endStInv[1], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[1], motor2Inv[1]);
axisZ.loadMotorSettings(speedMax[2], speedMin[2], stepsAcc[2], timeOut[2], homeIsUp[2], motorInv[2], endStInv[2], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[2], motor2Inv[2]);
axisX.loadMotorSettings(speedMax[0], speedMin[0], stepsAcc[0], timeOut[0], homeIsUp[0], motorInv[0], endStInv[0], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[0], motor2Inv[0], endStEnbl[0]);
axisY.loadMotorSettings(speedMax[1], speedMin[1], stepsAcc[1], timeOut[1], homeIsUp[1], motorInv[1], endStInv[1], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[1], motor2Inv[1], endStEnbl[1]);
axisZ.loadMotorSettings(speedMax[2], speedMin[2], stepsAcc[2], timeOut[2], homeIsUp[2], motorInv[2], endStInv[2], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[2], motor2Inv[2], endStEnbl[2]);
}

View File

@ -80,6 +80,7 @@ private:
bool motor2Inv[3];
bool motor2Enbl[3];
bool endStInv[3];
bool endStEnbl[3];
long timeOut[3];
float motorConsMissedSteps[3];

View File

@ -276,6 +276,7 @@ bool StepperControlAxis::endStopAxisReached(bool movement_forward) {
if((!movement_forward && min_endstop) || (movement_forward && max_endstop)) {
return 1;
}
return 0;
}
@ -293,7 +294,9 @@ void StepperControlAxis::StepperControlAxis::loadPinNumbers(int step, int dir, i
}
void StepperControlAxis::loadMotorSettings(long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv, bool endStInv, long interruptSpeed, bool motor2Enbl,bool motor2Inv) {
void StepperControlAxis::loadMotorSettings(
long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv,
bool endStInv, long interruptSpeed, bool motor2Enbl,bool motor2Inv, bool endStEnbl) {
motorSpeedMax = speedMax;
motorSpeedMin = speedMin;
@ -302,6 +305,7 @@ void StepperControlAxis::loadMotorSettings(long speedMax, long speedMin, long st
motorHomeIsUp = homeIsUp;
motorMotorInv = motorInv;
motorEndStopInv = endStInv;
motorEndStopEnbl = endStEnbl;
motorInterruptSpeed = interruptSpeed;
motorMotor2Enl = motor2Enbl;
motorMotor2Inv = motor2Inv;
@ -409,17 +413,17 @@ unsigned long StepperControlAxis::getLength(long l1, long l2) {
}
bool StepperControlAxis::endStopsReached() {
return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv)) && motorEndStopEnbl;
}
bool StepperControlAxis::endStopMin() {
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMin);
return digitalRead(pinMin) && motorEndStopEnbl;
}
bool StepperControlAxis::endStopMax() {
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMax);
return digitalRead(pinMax) && motorEndStopEnbl;
}
bool StepperControlAxis::isAxisActive() {

View File

@ -24,7 +24,7 @@ public:
StepperControlAxis();
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);
void loadMotorSettings( long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv, bool endStInv, long interruptSpeed, bool motor2Enbl, bool motor2Inv);
void loadMotorSettings( long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv, bool endStInv, long interruptSpeed, bool motor2Enbl, bool motor2Inv, bool endStEnbl);
void loadCoordinates(long sourcePoint, long destinationPoint, bool home);
void setMaxSpeed(long speed);
@ -94,6 +94,10 @@ private:
int pinMin;
int pinMax;
// motor settings
bool motorEndStopInv; // invert input (true/false) of end stops
bool motorEndStopEnbl; // enable the use of the end stops
// motor settings
long motorSpeedMax; // maximum speed in steps per second
long motorSpeedMin; // minimum speed in steps per second
@ -103,7 +107,6 @@ private:
bool motorMotorInv; // invert motor direction
bool motorMotor2Enl; // enable secondary motor
bool motorMotor2Inv; // invert secondary motor direction
bool motorEndStopInv; // invert input (true/false) of end stops
long motorInterruptSpeed; // period of interrupt in micro seconds
// coordinates

View File

@ -24,7 +24,7 @@ void StepperControlEncoder::test() {
Serial.print("\r\n");
}
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelA2, int channelB2) {
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB) {
pinChannelA = channelA;
pinChannelB = channelB;
@ -85,32 +85,8 @@ void StepperControlEncoder::readEncoder() {
}
void StepperControlEncoder::readChannels() {
curAnlgValChannelA1 = analogRead(pinChannelA);
curAnlgValChannelA2 = analogRead(pinChannelA2);
curAnlgValChannelB1 = analogRead(pinChannelB);
curAnlgValChannelB2 = analogRead(pinChannelB2);
if (abs(curAnlgValChannelA1 - curAnlgValChannelA2) > 555) {
curValChannelA = true;
}
if (abs(curAnlgValChannelA1 - curAnlgValChannelA2) < 165) {
curValChannelA = false;
}
if (abs(curAnlgValChannelB1 - curAnlgValChannelB2) > 555) {
curValChannelB = true;
}
if (abs(curAnlgValChannelB1 - curAnlgValChannelB2) < 165) {
curValChannelB = false;
}
//curValChannelA = digitalRead(pinChannelA);
//curValChannelB = digitalRead(pinChannelB);
curValChannelA = digitalRead(pinChannelA);
curValChannelB = digitalRead(pinChannelB);
}
void StepperControlEncoder::shiftChannels() {

View File

@ -22,7 +22,7 @@ public:
StepperControlEncoder();
void loadPinNumbers(int channelA, int channelB, int channelA2, int channelB2);
void loadPinNumbers(int channelA, int channelB);
void setPosition(long newPosition);
long currentPosition();
@ -36,9 +36,7 @@ private:
// pin settings
int pinChannelA;
int pinChannelA2;
int pinChannelB;
int pinChannelB2;
// channels
bool prvValChannelA;
@ -46,13 +44,6 @@ private:
bool curValChannelA;
bool curValChannelB;
int curAnlgValChannelA1;
int curAnlgValChannelA2;
int curAnlgValChannelB1;
int curAnlgValChannelB2;
// encoder
long position;

View File

@ -0,0 +1,143 @@
#ifndef known_16bit_timers_header_
#define known_16bit_timers_header_
// Wiring-S
//
#if defined(__AVR_ATmega644P__) && defined(WIRING)
#define TIMER1_A_PIN 5
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 6
// Teensy 2.0
//
#elif defined(__AVR_ATmega32U4__) && defined(CORE_TEENSY)
#define TIMER1_A_PIN 14
#define TIMER1_B_PIN 15
#define TIMER1_C_PIN 4
#define TIMER1_ICP_PIN 22
#define TIMER1_CLK_PIN 11
#define TIMER3_A_PIN 9
#define TIMER3_ICP_PIN 10
// Teensy++ 2.0
#elif defined(__AVR_AT90USB1286__) && defined(CORE_TEENSY)
#define TIMER1_A_PIN 25
#define TIMER1_B_PIN 26
#define TIMER1_C_PIN 27
#define TIMER1_ICP_PIN 4
#define TIMER1_CLK_PIN 6
#define TIMER3_A_PIN 16
#define TIMER3_B_PIN 15
#define TIMER3_C_PIN 14
#define TIMER3_ICP_PIN 17
#define TIMER3_CLK_PIN 13
// Teensy 3.0
//
#elif defined(__MK20DX128__)
#define TIMER1_A_PIN 3
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 4
// Teensy 3.1
//
#elif defined(__MK20DX256__)
#define TIMER1_A_PIN 3
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 4
#define TIMER3_A_PIN 32
#define TIMER3_B_PIN 25
#define TIMER3_ICP_PIN 32
// Teensy-LC
//
#elif defined(__MKL26Z64__)
#define TIMER1_A_PIN 16
#define TIMER1_B_PIN 17
#define TIMER1_ICP_PIN 17
#define TIMER3_A_PIN 3
#define TIMER3_B_PIN 4
#define TIMER3_ICP_PIN 4
// Arduino Mega
//
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define TIMER1_A_PIN 11
#define TIMER1_B_PIN 12
#define TIMER1_C_PIN 13
#define TIMER3_A_PIN 5
#define TIMER3_B_PIN 2
#define TIMER3_C_PIN 3
#define TIMER4_A_PIN 6
#define TIMER4_B_PIN 7
#define TIMER4_C_PIN 8
#define TIMER4_ICP_PIN 49
#define TIMER5_A_PIN 46
#define TIMER5_B_PIN 45
#define TIMER5_C_PIN 44
#define TIMER3_ICP_PIN 48
#define TIMER3_CLK_PIN 47
// Arduino Leonardo, Yun, etc
//
#elif defined(__AVR_ATmega32U4__)
#define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10
#define TIMER1_C_PIN 11
#define TIMER1_ICP_PIN 4
#define TIMER1_CLK_PIN 12
#define TIMER3_A_PIN 5
#define TIMER3_ICP_PIN 13
// Uno, Duemilanove, LilyPad, etc
//
#elif defined (__AVR_ATmega168__) || defined (__AVR_ATmega328P__)
#define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10
#define TIMER1_ICP_PIN 8
#define TIMER1_CLK_PIN 5
// Sanguino
//
#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__)
#define TIMER1_A_PIN 13
#define TIMER1_B_PIN 12
#define TIMER1_ICP_PIN 14
#define TIMER1_CLK_PIN 1
// Wildfire - Wicked Devices
//
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION >= 3
#define TIMER1_A_PIN 5 // PD5
#define TIMER1_B_PIN 8 // PD4
#define TIMER1_ICP_PIN 6 // PD6
#define TIMER1_CLK_PIN 23 // PB1
#define TIMER3_A_PIN 12 // PB6
#define TIMER3_B_PIN 13 // PB7
#define TIMER3_ICP_PIN 9 // PB5
#define TIMER3_CLK_PIN 0 // PD0
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION < 3
#define TIMER1_A_PIN 5 // PD5
#define TIMER1_B_PIN 4 // PD4
#define TIMER1_ICP_PIN 6 // PD6
#define TIMER1_CLK_PIN 15 // PB1
#define TIMER3_A_PIN 12 // PB6
#define TIMER3_B_PIN 13 // PB7
#define TIMER3_ICP_PIN 11 // PB5
#define TIMER3_CLK_PIN 0 // PD0
// Mighty-1284 - Maniacbug
//
#elif defined(__AVR_ATmega1284P__)
#define TIMER1_A_PIN 12 // PD5
#define TIMER1_B_PIN 13 // PD4
#define TIMER1_ICP_PIN 14 // PD6
#define TIMER1_CLK_PIN 1 // PB1
#define TIMER3_A_PIN 6 // PB6
#define TIMER3_B_PIN 7 // PB7
#define TIMER3_ICP_PIN 5 // PB5
#define TIMER3_CLK_PIN 8 // PD0
#endif
#endif

View File

@ -82,22 +82,6 @@ void setup() {
pinMode(FAN_PIN , OUTPUT);
pinMode(LED_PIN , OUTPUT);
pinMode(X_ENCDR_A , INPUT_PULLUP );
pinMode(X_ENCDR_A_Q , INPUT_PULLUP );
pinMode(X_ENCDR_B , INPUT_PULLUP );
pinMode(X_ENCDR_B_Q , INPUT_PULLUP );
pinMode(Y_ENCDR_A , INPUT_PULLUP );
pinMode(Y_ENCDR_A_Q , INPUT_PULLUP );
pinMode(Y_ENCDR_B , INPUT_PULLUP );
pinMode(Y_ENCDR_B_Q , INPUT_PULLUP );
pinMode(Z_ENCDR_A , INPUT_PULLUP );
pinMode(Z_ENCDR_A_Q , INPUT_PULLUP );
pinMode(Z_ENCDR_B , INPUT_PULLUP );
pinMode(Z_ENCDR_B_Q , INPUT_PULLUP );
//pinMode(SERVO_0_PIN , OUTPUT);
//pinMode(SERVO_1_PIN , OUTPUT);
@ -211,6 +195,7 @@ void loop() {
CurrentState::getInstance()->printQAndNewLine();
CurrentState::getInstance()->printPosition();
CurrentState::getInstance()->storeEndStops();
CurrentState::getInstance()->printEndStops();
//ParameterList::getInstance()->readAllValues();