Genesis 1.5 board support and Express reporting encoder position

pull/132/head
Tim Evers 2020-02-11 21:32:04 +01:00
parent 3a9f629034
commit 37bc380681
12 changed files with 47 additions and 77 deletions

View File

@ -1,9 +1,15 @@
#ifndef FARMBOT_BOARD_ID #ifndef FARMBOT_BOARD_ID
// Farmbot using RAMPS board
//#define RAMPS_V14 //#define RAMPS_V14
//#define FARMDUINO_V10 //#define FARMDUINO_V10
//#define FARMDUINO_V14 //#define FARMDUINO_V14
// Farmbot Genesis 1.5
//#define FARMDUINO_V30 //#define FARMDUINO_V30
// Farmbot Express
#define FARMDUINO_EXP_V20 #define FARMDUINO_EXP_V20
#else #else

View File

@ -208,7 +208,7 @@ void Movement::loadSettings()
} }
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
void Movement::initTMC2130() void Movement::initTMC2130()
{ {
axisX.initTMC2130(); axisX.initTMC2130();
@ -289,7 +289,7 @@ void Movement::loadSettings()
void Movement::test() void Movement::test()
{ {
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
//axisX.enableMotor(); //axisX.enableMotor();
//axisX.setMotorStep(); //axisX.setMotorStep();
//delayMicroseconds(500); //delayMicroseconds(500);
@ -747,18 +747,16 @@ int Movement::moveToCoords(double xDestScaled, double yDestScaled, double zDestS
break; break;
case 2: case 2:
#if defined(FARMDUINO_EXP_V20) //#if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
//serialBuffer += "R89";
serialBuffer += "R89"; //serialBuffer += " X";
serialBuffer += " X"; //serialBuffer += axisX.getLoad();
serialBuffer += axisX.getLoad(); //serialBuffer += " Y";
serialBuffer += " Y"; //serialBuffer += axisY.getLoad();
serialBuffer += axisY.getLoad(); //serialBuffer += " Z";
serialBuffer += " Z"; //serialBuffer += axisZ.getLoad();
serialBuffer += axisZ.getLoad(); //serialBuffer += CurrentState::getInstance()->getQAndNewLine();
serialBuffer += CurrentState::getInstance()->getQAndNewLine(); //#endif
#endif
break; break;
default: default:
@ -767,14 +765,14 @@ int Movement::moveToCoords(double xDestScaled, double yDestScaled, double zDestS
serialMessageNr++; serialMessageNr++;
#if !defined(FARMDUINO_EXP_V20) #if !defined(FARMDUINO_EXP_V20) && !defined(FARMDUINO_V30)
if (serialMessageNr > 1) if (serialMessageNr > 1)
{ {
serialMessageNr = 0; serialMessageNr = 0;
} }
#endif #endif
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
if (serialMessageNr > 2) if (serialMessageNr > 2)
{ {
@ -1400,27 +1398,6 @@ void Movement::checkAxisVsEncoder(MovementAxis *axis, MovementEncoder *encoder,
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20)
void Movement::checkAxisVsEncoder(MovementAxis *axis, MovementEncoder *encoder, float *missedSteps, long *lastPosition, long *encoderLastPosition, int *encoderUseForPos, float *encoderStepDecay, bool *encoderEnabled) void Movement::checkAxisVsEncoder(MovementAxis *axis, MovementEncoder *encoder, float *missedSteps, long *lastPosition, long *encoderLastPosition, int *encoderUseForPos, float *encoderStepDecay, bool *encoderEnabled)
{ {
//
// /**/
// /*
// Serial.print("R99");
// Serial.print(" XXX ");
// Serial.print(" cur pos ");
// Serial.print(axis->currentPosition());
// Serial.print(" last pos ");
// Serial.print(*lastPosition);
// */
//
//if (axis->stallDetected()) {
// Serial.print("X");
//}
//else
//{
// Serial.print(".");
//}
/**/ /**/
bool stallGuard = false; bool stallGuard = false;
bool standStill = false; bool standStill = false;
@ -1428,28 +1405,15 @@ void Movement::checkAxisVsEncoder(MovementAxis *axis, MovementEncoder *encoder,
if (*encoderEnabled) { if (*encoderEnabled) {
//TMC2130X.read_STAT();
status = axis->getStatus(); status = axis->getStatus();
stallGuard = status & FB_TMC_SPISTATUS_STALLGUARD_MASK ? true : false; stallGuard = status & FB_TMC_SPISTATUS_STALLGUARD_MASK ? true : false;
standStill = status & FB_TMC_SPISTATUS_STANDSTILL_MASK ? true : false; standStill = status & FB_TMC_SPISTATUS_STANDSTILL_MASK ? true : false;
if (stallGuard || standStill) { if (stallGuard || standStill) {
//Serial.print(".");
// In case of stall detection, count this as a missed step // In case of stall detection, count this as a missed step
(*missedSteps)++; (*missedSteps)++;
axis->setCurrentPosition(*lastPosition); axis->setCurrentPosition(*lastPosition);
//if (int(*missedSteps) % 10 == 0) {
// Serial.println();
// Serial.print(*missedSteps);
// Serial.print("/");
// Serial.print(axis->currentPosition());
// Serial.println();
//}
} }
else { else {
// Decrease amount of missed steps if there are no missed step // Decrease amount of missed steps if there are no missed step
@ -1570,7 +1534,7 @@ void Movement::loadMotorSettings()
/**/ /**/
/* /*
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
loadSettingsTMC2130(); loadSettingsTMC2130();
#endif #endif
*/ */
@ -1722,7 +1686,7 @@ bool Movement::endStopsReached()
void Movement::storePosition() void Movement::storePosition()
{ {
#if !defined(FARMDUINO_EXP_V20) #if !defined(FARMDUINO_EXP_V20) && !defined(FARMDUINO_V30)
if (motorConsEncoderEnabled[0]) if (motorConsEncoderEnabled[0])
{ {
CurrentState::getInstance()->setX(encoderX.currentPosition()); CurrentState::getInstance()->setX(encoderX.currentPosition());
@ -1751,7 +1715,7 @@ void Movement::storePosition()
} }
#endif #endif
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
CurrentState::getInstance()->setX(axisX.currentPosition()); CurrentState::getInstance()->setX(axisX.currentPosition());
CurrentState::getInstance()->setY(axisY.currentPosition()); CurrentState::getInstance()->setY(axisY.currentPosition());
CurrentState::getInstance()->setZ(axisZ.currentPosition()); CurrentState::getInstance()->setZ(axisZ.currentPosition());

View File

@ -37,7 +37,7 @@ public:
void handleMovementInterrupt(); void handleMovementInterrupt();
void checkEncoders(); void checkEncoders();
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
void initTMC2130(); void initTMC2130();
void loadSettingsTMC2130(); void loadSettingsTMC2130();
#endif #endif

View File

@ -71,7 +71,7 @@ void MovementAxis::test()
} }
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
unsigned int MovementAxis::getLostSteps() unsigned int MovementAxis::getLostSteps()
{ {
@ -611,7 +611,7 @@ void MovementAxis::setDirectionUp()
//#endif //#endif
/* /*
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
// The TMC2130 uses a command to change direction, not a pin // The TMC2130 uses a command to change direction, not a pin
if (motorMotorInv) if (motorMotorInv)
@ -660,7 +660,7 @@ void MovementAxis::setDirectionDown()
//#endif //#endif
/* /*
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
// The TMC2130 uses a command to change direction, not a pin // The TMC2130 uses a command to change direction, not a pin
if (motorMotorInv) if (motorMotorInv)
@ -941,7 +941,7 @@ void MovementAxis::resetMotorStepWrite46()
PORTL &= B11110111; PORTL &= B11110111;
} }
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
//// TMC2130 Functions //// TMC2130 Functions
void MovementAxis::setMotorStepWriteTMC2130() void MovementAxis::setMotorStepWriteTMC2130()

View File

@ -29,7 +29,7 @@ class MovementAxis
public: public:
MovementAxis(); MovementAxis();
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
TMC2130_Basics *TMC2130A; TMC2130_Basics *TMC2130A;
TMC2130_Basics *TMC2130B; TMC2130_Basics *TMC2130B;
#endif #endif
@ -92,14 +92,14 @@ public:
char channelLabel; char channelLabel;
bool movementStarted; bool movementStarted;
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
void initTMC2130(); void initTMC2130();
void loadSettingsTMC2130(int motorCurrent, int stallSensitivity, int microSteps); void loadSettingsTMC2130(int motorCurrent, int stallSensitivity, int microSteps);
uint16_t getLoad(); uint16_t getLoad();
#endif #endif
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
void setMotorStepWriteTMC2130(); void setMotorStepWriteTMC2130();
void setMotorStepWriteTMC2130_2(); void setMotorStepWriteTMC2130_2();
void resetMotorStepWriteTMC2130(); void resetMotorStepWriteTMC2130();

View File

@ -76,7 +76,7 @@ void MovementEncoder::loadMdlEncoderId(MdlSpiEncoders encoder)
void MovementEncoder::setPosition(long newPosition) void MovementEncoder::setPosition(long newPosition)
{ {
#if defined(RAMPS_V14) || defined(FARMDUINO_V10) #if defined(RAMPS_V14) || defined(FARMDUINO_V10) || defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
position = newPosition; position = newPosition;
#endif #endif
@ -277,7 +277,7 @@ float MovementEncoder::getMissedSteps()
void MovementEncoder::checkMissedSteps() void MovementEncoder::checkMissedSteps()
{ {
#if !defined(FARMDUINO_EXP_V20) #if !defined(FARMDUINO_EXP_V20) && !defined(FARMDUINO_V30)
if (encoderEnabled) if (encoderEnabled)
{ {
bool stepMissed = false; bool stepMissed = false;
@ -307,7 +307,7 @@ void MovementEncoder::checkMissedSteps()
#endif #endif
/* /*
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
if (encoderEnabled) { if (encoderEnabled) {
if (axis->stallDetected()) { if (axis->stallDetected()) {

View File

@ -8,7 +8,7 @@
#include "TMC2130.h" #include "TMC2130.h"
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
//void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int current, int sensitivity) //void loadTMC2130ParametersMotor(Trinamic_TMC2130 *myStepper, int microsteps, int current, int sensitivity)
void loadTMC2130ParametersMotor(TMC2130_Basics *tb, int microsteps, int current, int sensitivity) void loadTMC2130ParametersMotor(TMC2130_Basics *tb, int microsteps, int current, int sensitivity)

View File

@ -14,7 +14,7 @@
#include "pins.h" #include "pins.h"
#include "Board.h" #include "Board.h"
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
#include "TMC2130_Basics.h" #include "TMC2130_Basics.h"
static TMC2130_Basics TMC2130X(X_CHIP_SELECT); static TMC2130_Basics TMC2130X(X_CHIP_SELECT);

View File

@ -2,7 +2,7 @@
#include "farmbot_arduino_controller.h" #include "farmbot_arduino_controller.h"
/**/ /**/
//#if !defined(FARMDUINO_EXP_V20) //#if !defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
#include "TimerOne.h" #include "TimerOne.h"
//#endif //#endif
@ -52,7 +52,7 @@ unsigned long interruptDurationMax = 0;
bool interruptBusy = false; bool interruptBusy = false;
int interruptSecondTimer = 0; int interruptSecondTimer = 0;
//#if !defined(FARMDUINO_EXP_V20) //#if !defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
void interrupt(void) void interrupt(void)
{ {
if (!debugInterrupt) if (!debugInterrupt)
@ -284,7 +284,7 @@ void checkParamsChanged()
} }
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
Movement::getInstance()->loadSettingsTMC2130(); Movement::getInstance()->loadSettingsTMC2130();
#endif #endif
@ -503,7 +503,7 @@ void setPinInputOutput()
} }
#endif #endif
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
void setPinInputOutput() void setPinInputOutput()
{ {
Serial.print(COMM_REPORT_COMMENT); Serial.print(COMM_REPORT_COMMENT);
@ -621,13 +621,13 @@ void startInterrupt()
// Interrupt management code library written by Paul Stoffregen // Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds // The default time 100 micro seconds
//#if !defined(FARMDUINO_EXP_V20) //#if !defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
Timer1.attachInterrupt(interrupt); Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED); Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start(); Timer1.start();
//#endif //#endif
//#if defined(FARMDUINO_EXP_V20) //#if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
// Serial.println("set timer"); // Serial.println("set timer");
// TIMSK2 = (TIMSK2 & B11111110) | 0x01; // Enable timer overflow // TIMSK2 = (TIMSK2 & B11111110) | 0x01; // Enable timer overflow
// TCCR2B = (TCCR2B & B11111000) | 0x01; // Set divider to 1 // TCCR2B = (TCCR2B & B11111000) | 0x01; // Set divider to 1
@ -735,7 +735,7 @@ void startServo()
ServoControl::getInstance()->attach(); ServoControl::getInstance()->attach();
} }
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
/**/ /**/
//static Trinamic_TMC2130 controllerTMC2130_X(X_CHIP_SELECT); //static Trinamic_TMC2130 controllerTMC2130_X(X_CHIP_SELECT);

View File

@ -16,7 +16,7 @@
#include "MemoryFree.h" #include "MemoryFree.h"
#include "Debug.h" #include "Debug.h"
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
#include "TMC2130.h" #include "TMC2130.h"
#endif #endif
@ -49,7 +49,7 @@ void setup();
void setPinInputOutput(); void setPinInputOutput();
void startSerial(); void startSerial();
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
void loadTMC2130drivers(); void loadTMC2130drivers();
void loadTMC2130parameters(); void loadTMC2130parameters();
void startupTmc(); void startupTmc();

View File

@ -257,7 +257,7 @@
#endif #endif
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
// X1-AXIS // X1-AXIS
#define X_STEP_PIN 26 // X1_STEP_PIN #define X_STEP_PIN 26 // X1_STEP_PIN

View File

@ -19,7 +19,7 @@ void setup()
readParameters(); readParameters();
#if defined(FARMDUINO_EXP_V20) #if defined(FARMDUINO_EXP_V20) || defined(FARMDUINO_V30)
loadTMC2130drivers(); loadTMC2130drivers();
startupTmc(); startupTmc();
loadTMC2130parameters(); loadTMC2130parameters();