farmbot-arduino-firmware/src/farmbot_arduino_controller.cpp

299 lines
7.5 KiB
C++
Raw Normal View History

// Do not remove the include below
#include "farmbot_arduino_controller.h"
#include "pins.h"
#include "Config.h"
2015-06-14 15:08:57 -06:00
#include "StepperControl.h"
#include "ServoControl.h"
#include "PinGuard.h"
#include "TimerOne.h"
2017-03-27 13:58:25 -06:00
#include "MemoryFree.h"
2017-04-20 04:34:39 -06:00
#include "Debug.h"
#include "CurrentState.h"
2017-03-27 13:58:25 -06:00
static char commandEndChar = 0x0A;
2017-04-19 08:12:12 -06:00
static GCodeProcessor *gCodeProcessor = new GCodeProcessor();
2015-04-02 15:12:44 -06:00
unsigned long lastAction;
unsigned long currentTime;
2017-04-17 13:25:27 -06:00
unsigned long cycleCounter = 0;
bool previousEmergencyStop = false;
2015-04-02 15:12:44 -06:00
int lastParamChangeNr = 0;
String commandString = "";
char incomingChar = 0;
char incomingCommandArray[INCOMING_CMD_BUF_SIZE];
int incomingCommandPointer = 0;
// Blink led routine used for testing
2016-05-02 15:14:01 -06:00
bool blink = false;
2017-04-19 08:12:12 -06:00
void blinkLed()
{
blink = !blink;
digitalWrite(LED_PIN, blink);
2016-05-02 15:14:01 -06:00
}
// Interrupt handling for:
// - movement
// - encoders
// - pin guard
//
bool interruptBusy = false;
int interruptSecondTimer = 0;
2017-04-19 08:12:12 -06:00
void interrupt(void)
{
2017-04-20 04:34:39 -06:00
if (!debugInterrupt)
2017-04-19 08:12:12 -06:00
{
2017-04-20 04:34:39 -06:00
interruptSecondTimer++;
2017-04-19 08:12:12 -06:00
2017-04-20 04:34:39 -06:00
if (interruptBusy == false)
2017-04-19 08:12:12 -06:00
{
2017-04-20 04:34:39 -06:00
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
// Check the actions triggered once per second
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED)
{
interruptSecondTimer = 0;
PinGuard::getInstance()->checkPins();
//blinkLed();
}
interruptBusy = false;
}
2017-04-19 08:12:12 -06:00
}
}
//The setup function is called once at startup of the sketch
2017-04-19 08:12:12 -06:00
void setup()
{
// Setup pin input/output settings
pinMode(X_STEP_PIN, OUTPUT);
pinMode(X_DIR_PIN, OUTPUT);
pinMode(X_ENABLE_PIN, OUTPUT);
pinMode(E_STEP_PIN, OUTPUT);
pinMode(E_DIR_PIN, OUTPUT);
pinMode(E_ENABLE_PIN, OUTPUT);
pinMode(X_MIN_PIN, INPUT_PULLUP);
pinMode(X_MAX_PIN, INPUT_PULLUP);
pinMode(Y_STEP_PIN, OUTPUT);
pinMode(Y_DIR_PIN, OUTPUT);
pinMode(Y_ENABLE_PIN, OUTPUT);
pinMode(Y_MIN_PIN, INPUT_PULLUP);
pinMode(Y_MAX_PIN, INPUT_PULLUP);
pinMode(Z_STEP_PIN, OUTPUT);
pinMode(Z_DIR_PIN, OUTPUT);
pinMode(Z_ENABLE_PIN, OUTPUT);
pinMode(Z_MIN_PIN, INPUT_PULLUP);
pinMode(Z_MAX_PIN, INPUT_PULLUP);
pinMode(HEATER_0_PIN, OUTPUT);
pinMode(HEATER_1_PIN, OUTPUT);
pinMode(FAN_PIN, OUTPUT);
pinMode(LED_PIN, OUTPUT);
//pinMode(SERVO_0_PIN , OUTPUT);
//pinMode(SERVO_1_PIN , OUTPUT);
digitalWrite(X_ENABLE_PIN, HIGH);
digitalWrite(E_ENABLE_PIN, HIGH);
digitalWrite(Y_ENABLE_PIN, HIGH);
digitalWrite(Z_ENABLE_PIN, HIGH);
Serial.begin(115200);
delay(100);
// Start the motor handling
//ServoControl::getInstance()->attach();
// Load motor settings
StepperControl::getInstance()->loadSettings();
/**/
2017-04-19 08:12:12 -06:00
// Dump all values to the serial interface
ParameterList::getInstance()->readAllValues();
// Get the settings for the pin guard
PinGuard::getInstance()->loadConfig();
// Start the interrupt used for moving
// Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
// Initialize the inactivity check
lastAction = millis();
if (ParameterList::getInstance()->getValue(MOVEMENT_HOME_AT_BOOT_X) == 1)
{
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, true, false, false);
}
if (ParameterList::getInstance()->getValue(MOVEMENT_HOME_AT_BOOT_Y) == 1)
{
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, false, true, false);
}
if (ParameterList::getInstance()->getValue(MOVEMENT_HOME_AT_BOOT_Z) == 1)
{
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, false, false, true);
}
}
// The loop function is called in an endless loop
2017-04-19 08:12:12 -06:00
void loop()
{
2017-04-20 04:34:39 -06:00
if (debugInterrupt)
{
StepperControl::getInstance()->handleMovementInterrupt();
}
2017-04-19 08:12:12 -06:00
if (Serial.available())
{
// Save current time stamp for timeout actions
lastAction = millis();
// Get the input and start processing on receiving 'new line'
incomingChar = Serial.read();
// Filter out emergency stop.
if (!(incomingChar == 69 || incomingChar == 101))
{
incomingCommandArray[incomingCommandPointer] = incomingChar;
incomingCommandPointer++;
}
else
{
CurrentState::getInstance()->setEmergencyStop();
}
2017-04-19 08:12:12 -06:00
// If the string is getting to long, cap it off with a new line and let it process anyway
if (incomingCommandPointer >= INCOMING_CMD_BUF_SIZE - 1)
{
incomingChar = '\n';
incomingCommandArray[incomingCommandPointer] = incomingChar;
incomingCommandPointer++;
}
if (incomingChar == '\n' || incomingCommandPointer >= INCOMING_CMD_BUF_SIZE)
{
char commandChar[incomingCommandPointer + 1];
for (int i = 0; i < incomingCommandPointer - 1; i++)
{
if (incomingChar)
2017-04-19 08:12:12 -06:00
commandChar[i] = incomingCommandArray[i];
}
commandChar[incomingCommandPointer] = 0;
if (incomingCommandPointer > 1)
{
// Copy the command to another string object.
// because there are issues with passing the
// string to the command object
// Create a command and let it execute
//Command* command = new Command(commandString);
Command *command = new Command(commandChar);
if (LOGGING || debugMessages)
2017-04-19 08:12:12 -06:00
{
command->print();
}
2017-04-19 08:12:12 -06:00
gCodeProcessor->execute(command);
2017-04-19 08:12:12 -06:00
free(command);
2017-04-19 08:12:12 -06:00
}
2017-04-19 08:12:12 -06:00
incomingCommandPointer = 0;
}
}
// In case of emergency stop, disable movement and
// shut down the pins used
if (previousEmergencyStop == false && CurrentState::getInstance()->isEmergencyStop())
{
StepperControl::getInstance()->disableMotors();
PinControl::getInstance()->resetPinsUsed();
}
previousEmergencyStop == CurrentState::getInstance()->isEmergencyStop();
2017-04-19 08:12:12 -06:00
// Check if parameters are changes, and if so load the new settings
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber())
{
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();
2017-04-19 08:12:12 -06:00
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" loading parameters ");
CurrentState::getInstance()->printQAndNewLine();
2017-04-19 08:12:12 -06:00
StepperControl::getInstance()->loadSettings();
PinGuard::getInstance()->loadConfig();
}
2017-04-19 08:12:12 -06:00
// Do periodic checks and feedback
2017-04-19 08:12:12 -06:00
currentTime = millis();
if (currentTime < lastAction)
{
2017-04-19 08:12:12 -06:00
// If the device timer overruns, reset the idle counter
lastAction = millis();
}
else
{
2017-03-27 13:58:25 -06:00
2017-04-19 08:12:12 -06:00
if ((currentTime - lastAction) > 5000)
{
// After an idle time, send the idle message
2016-10-02 15:43:39 -06:00
2017-04-19 08:12:12 -06:00
Serial.print(COMM_REPORT_CMD_IDLE);
CurrentState::getInstance()->printQAndNewLine();
2017-04-19 08:12:12 -06:00
StepperControl::getInstance()->storePosition();
CurrentState::getInstance()->printPosition();
2017-04-19 08:12:12 -06:00
CurrentState::getInstance()->storeEndStops();
CurrentState::getInstance()->printEndStops();
2017-03-27 13:58:25 -06:00
2017-04-20 04:34:39 -06:00
if (debugMessages)
{
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" MEM ");
Serial.print(freeMemory());
CurrentState::getInstance()->printQAndNewLine();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" Cycle ");
Serial.print(cycleCounter);
CurrentState::getInstance()->printQAndNewLine();
StepperControl::getInstance()->test();
}
// Tim 2017-04-20 Temporary disabling the warning of no valid configuration
// until fully supported on RPI
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1)
// {
// Serial.print(COMM_REPORT_NO_CONFIG);
// }
2017-04-19 08:12:12 -06:00
cycleCounter++;
lastAction = millis();
}
}
}