farmbot-arduino-firmware/src/farmbot_arduino_controller.cpp

242 lines
6.1 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"
2014-11-04 15:14:35 -07:00
static char commandEndChar = 0x0A;
static GCodeProcessor* gCodeProcessor = new GCodeProcessor();
2015-04-02 15:12:44 -06:00
unsigned long lastAction;
unsigned long currentTime;
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;
void blinkLed() {
blink = !blink;
digitalWrite(LED_PIN,blink);
}
// Interrupt handling for:
// - movement
// - encoders
// - pin guard
//
bool interruptBusy = false;
int interruptSecondTimer = 0;
void interrupt(void) {
interruptSecondTimer++;
if (interruptBusy == false) {
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
2016-05-06 15:15:38 -06:00
// Check the actions triggered once per second
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED) {
2016-05-06 15:15:38 -06:00
interruptSecondTimer = 0;
PinGuard::getInstance()->checkPins();
2016-05-06 15:15:38 -06:00
//blinkLed();
}
interruptBusy = false;
}
}
//The setup function is called once at startup of the sketch
void setup() {
// Setup pin input/output settings
2014-07-13 11:26:29 -06:00
pinMode(X_STEP_PIN , OUTPUT);
pinMode(X_DIR_PIN , OUTPUT);
pinMode(X_ENABLE_PIN, OUTPUT);
2017-02-06 13:51:09 -07:00
pinMode(E_STEP_PIN , OUTPUT);
pinMode(E_DIR_PIN , OUTPUT);
pinMode(E_ENABLE_PIN, OUTPUT);
2017-01-02 11:19:46 -07:00
pinMode(X_MIN_PIN , INPUT_PULLUP );
pinMode(X_MAX_PIN , INPUT_PULLUP );
2014-07-13 11:26:29 -06:00
pinMode(Y_STEP_PIN , OUTPUT);
pinMode(Y_DIR_PIN , OUTPUT);
pinMode(Y_ENABLE_PIN, OUTPUT);
2017-01-02 11:19:46 -07:00
pinMode(Y_MIN_PIN , INPUT_PULLUP );
pinMode(Y_MAX_PIN , INPUT_PULLUP );
2014-07-13 11:26:29 -06:00
pinMode(Z_STEP_PIN , OUTPUT);
pinMode(Z_DIR_PIN , OUTPUT);
pinMode(Z_ENABLE_PIN, OUTPUT);
2017-01-02 11:19:46 -07:00
pinMode(Z_MIN_PIN , INPUT_PULLUP );
pinMode(Z_MAX_PIN , INPUT_PULLUP );
2014-09-10 09:21:17 -06:00
pinMode(HEATER_0_PIN, OUTPUT);
pinMode(HEATER_1_PIN, OUTPUT);
pinMode(FAN_PIN , OUTPUT);
pinMode(LED_PIN , OUTPUT);
2014-07-15 14:23:01 -06:00
2014-11-04 15:14:35 -07:00
//pinMode(SERVO_0_PIN , OUTPUT);
//pinMode(SERVO_1_PIN , OUTPUT);
2014-07-15 14:23:01 -06:00
digitalWrite(X_ENABLE_PIN, HIGH);
2017-02-06 13:51:09 -07:00
digitalWrite(E_ENABLE_PIN, HIGH);
2014-07-15 14:23:01 -06:00
digitalWrite(Y_ENABLE_PIN, HIGH);
digitalWrite(Z_ENABLE_PIN, HIGH);
Serial.begin(115200);
2014-11-04 15:14:35 -07:00
delay(100);
2016-05-06 15:15:38 -06:00
// Start the motor handling
//ServoControl::getInstance()->attach();
2016-05-06 15:15:38 -06:00
// Dump all values to the serial interface
ParameterList::getInstance()->readAllValues();
2014-11-04 15:14:35 -07:00
2016-05-02 15:14:01 -06:00
// 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
2017-03-20 16:08:23 -06:00
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
2015-04-02 15:12:44 -06:00
// Initialize the inactivity check
lastAction = millis();
}
// The loop function is called in an endless loop
void loop() {
2014-05-05 16:15:58 -06:00
if (Serial.available()) {
// Save current time stamp for timeout actions
lastAction = millis();
2015-04-02 15:12:44 -06:00
// Get the input and start processing on receiving 'new line'
incomingChar = Serial.read();
incomingCommandArray[incomingCommandPointer] = incomingChar;
incomingCommandPointer++;
// 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++;
}
2015-04-02 15:12:44 -06:00
if (incomingChar == '\n' || incomingCommandPointer >= INCOMING_CMD_BUF_SIZE) {
//commandString += incomingChar;
//String commandString = Serial.readStringUntil(commandEndChar);
//char commandChar[currentCommand.length()];
//currentCommand.toCharArray(commandChar, currentCommand.length());
char commandChar[incomingCommandPointer + 1];
for (int i = 0; i < incomingCommandPointer -1; i++) {
commandChar[i] = incomingCommandArray[i];
}
commandChar[incomingCommandPointer] = 0;
commandString.toCharArray(commandChar, commandString.length());
String currentCommand = String(commandString);
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) {
command->print();
}
gCodeProcessor->execute(command);
free(command);
}
incomingCommandPointer = 0;
2014-05-05 16:15:58 -06:00
}
}
//StepperControl::getInstance()->test();
// Check if parameters are changes, and if so load the new settings
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber()) {
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" loading parameters ");
CurrentState::getInstance()->printQAndNewLine();
StepperControl::getInstance()->loadSettings();
PinGuard::getInstance()->loadConfig();
}
// Do periodic checks and feedback
2015-04-02 15:12:44 -06:00
currentTime = millis();
if (currentTime < lastAction) {
2015-04-02 15:12:44 -06:00
// If the device timer overruns, reset the idle counter
lastAction = millis();
}
else {
2015-11-06 15:22:17 -07:00
if ((currentTime - lastAction) > 5000) {
2015-04-02 15:12:44 -06:00
// After an idle time, send the idle message
2017-03-27 13:58:25 -06:00
Serial.print(COMM_REPORT_CMD_IDLE);
2016-10-02 15:43:39 -06:00
CurrentState::getInstance()->printQAndNewLine();
StepperControl::getInstance()->storePosition();
2016-04-08 16:19:45 -06:00
CurrentState::getInstance()->printPosition();
2017-02-28 14:48:46 -07:00
CurrentState::getInstance()->storeEndStops();
2016-04-08 16:19:45 -06:00
CurrentState::getInstance()->printEndStops();
2017-03-27 13:58:25 -06:00
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" MEM ");
Serial.print(freeMemory());
CurrentState::getInstance()->printQAndNewLine();
StepperControl::getInstance()->test();
//ParameterList::getInstance()->readAllValues();
2017-03-27 13:58:25 -06:00
//StepperControl::getInstance()->test();
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
// Serial.print(COMM_REPORT_NO_CONFIG);
// }
2015-04-02 15:12:44 -06:00
lastAction = millis();
}
}
}