farmbot-arduino-firmware/src/farmbot_arduino_controller.cpp

131 lines
3.0 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"
2014-11-04 15:14:35 -07:00
#include "ServoControl.h"
#include "PinGuard.h"
#include "TimerOne.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;
// 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();
//blinkLed();
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED) {
PinGuard::getInstance()->checkPins();
}
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);
2014-07-13 11:26:29 -06:00
pinMode(X_MIN_PIN , INPUT );
pinMode(X_MAX_PIN , INPUT );
2014-07-13 11:26:29 -06:00
pinMode(Y_STEP_PIN , OUTPUT);
pinMode(Y_DIR_PIN , OUTPUT);
pinMode(Y_ENABLE_PIN, OUTPUT);
2014-07-13 11:26:29 -06:00
pinMode(Y_MIN_PIN , INPUT );
pinMode(Y_MAX_PIN , INPUT );
2014-07-13 11:26:29 -06:00
pinMode(Z_STEP_PIN , OUTPUT);
pinMode(Z_DIR_PIN , OUTPUT);
pinMode(Z_ENABLE_PIN, OUTPUT);
2014-07-13 11:26:29 -06:00
pinMode(Z_MIN_PIN , INPUT );
pinMode(Z_MAX_PIN , INPUT );
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);
digitalWrite(Y_ENABLE_PIN, HIGH);
digitalWrite(Z_ENABLE_PIN, HIGH);
Serial.begin(115200);
2014-11-04 15:14:35 -07:00
ServoControl::getInstance()->attach();
//StepperControl::getInstance()->initInterrupt();
2014-11-04 15:14:35 -07:00
// Start the interrupt used for moviing
// Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds
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()) {
2014-05-05 16:15:58 -06:00
String commandString = Serial.readStringUntil(commandEndChar);
if (commandString && commandString.length() > 0) {
2015-04-02 15:12:44 -06:00
lastAction = millis();
2014-05-05 16:15:58 -06:00
Command* command = new Command(commandString);
if(LOGGING) {
command->print();
}
gCodeProcessor->execute(command);
2014-07-29 16:12:19 -06:00
free(command);
2014-05-05 16:15:58 -06:00
}
}
2015-04-02 15:12:44 -06:00
delay(10);
2014-11-04 15:14:35 -07:00
// Test
2015-11-06 15:22:17 -07:00
/**///StepperControl::getInstance()->test();
2015-04-02 15:12:44 -06:00
currentTime = millis();
if (currentTime < lastAction) {
// 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
2015-04-08 16:09:08 -06:00
Serial.print("R00\r\n");
2016-04-08 16:19:45 -06:00
CurrentState::getInstance()->printPosition();
CurrentState::getInstance()->printEndStops();
2015-04-02 15:12:44 -06:00
lastAction = millis();
}
}
}