Emergency reactor core shutdown / home on spawn / maximum size robotic universe [UNTESTED]

pull/75/head
Tim Evers 2017-04-26 22:45:05 +02:00
parent 3dcfa4bde6
commit 46f6c77899
18 changed files with 320 additions and 83 deletions

View File

@ -13,6 +13,7 @@ enum CommandCodeEnum
F01 = 101,
F02 = 102,
F03 = 103,
F09 = 109,
F11 = 111,
F12 = 112,
F13 = 113,

View File

@ -56,6 +56,10 @@ const long MOVEMENT_KEEP_ACTIVE_X_DEFAULT = 0;
const long MOVEMENT_KEEP_ACTIVE_Y_DEFAULT = 0;
const long MOVEMENT_KEEP_ACTIVE_Z_DEFAULT = 1;
const long MOVEMENT_HOME_AT_BOOT_X_DEFAULT = 0;
const long MOVEMENT_HOME_AT_BOOT_Y_DEFAULT = 0;
const long MOVEMENT_HOME_AT_BOOT_Z_DEFAULT = 1;
const long MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT = 0;
@ -75,7 +79,7 @@ const long MOVEMENT_HOME_UP_X_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Y_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Z_DEFAULT = 1;
// numver of steps used for acceleration or deceleration
// Number of steps used for acceleration or deceleration
const long MOVEMENT_STEPS_ACC_DEC_X_DEFAULT = 500;
const long MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT = 500;
const long MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT = 500;
@ -107,12 +111,13 @@ const long ENCODER_SCALING_X_DEFAULT = 100;
const long ENCODER_SCALING_Y_DEFAULT = 100;
const long ENCODER_SCALING_Z_DEFAULT = 100;
// Number of stes missed before motor is seen as not moving
// Number of steps missed before motor is seen as not moving
const long ENCODER_MISSED_STEPS_MAX_X_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_MAX_Y_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_MAX_Z_DEFAULT = 10;
// How much a good step is substracted from the missed step total (1-99)
// 10 means it ignores 10 steps in 100. This is normal because of jerkiness while moving
const long ENCODER_MISSED_STEPS_DECAY_X_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT = 10;
@ -127,7 +132,12 @@ const long ENCODER_INVERT_X_DEFAULT = 0;
const long ENCODER_INVERT_Y_DEFAULT = 0;
const long ENCODER_INVERT_Z_DEFAULT = 0;
// pin guard default settings
// Length of axis in steps. Zero means don't care
const long MOVEMENT_AXIS_NR_STEPS_X_DEFAULT = 0;
const long MOVEMENT_AXIS_NR_STEPS_Y_DEFAULT = 0;
const long MOVEMENT_AXIS_NR_STEPS_Z_DEFAULT = 0;
// Pin guard default settings
const long PIN_GUARD_1_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_1_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_1_ACTIVE_STATE_DEFAULT = 1;

View File

@ -150,3 +150,18 @@ void CurrentState::printQAndNewLine()
Serial.print(Q);
Serial.print("\r\n");
}
void CurrentState::setEmergencyStop()
{
emergencyStop = true;
}
void CurrentState::resetEmergencyStop()
{
emergencyStop = false;
}
bool CurrentState::isEmergencyStop()
{
return emergencyStop;
}

View File

@ -14,6 +14,7 @@ class CurrentState
{
public:
static CurrentState *getInstance();
long getX();
long getY();
long getZ();
@ -21,6 +22,7 @@ public:
void setX(long);
void setY(long);
void setZ(long);
void setEndStopState(unsigned int, unsigned int, bool);
void printPosition();
void storeEndStops();
@ -32,10 +34,16 @@ public:
void resetQ();
void printQAndNewLine();
void setEmergencyStop();
void resetEmergencyStop();
bool isEmergencyStop();
private:
CurrentState();
CurrentState(CurrentState const &);
void operator=(CurrentState const &);
bool emergencyStop = false;
};
#endif /* CURRENTSTATE_H_ */

37
src/F09Handler.cpp 100644
View File

@ -0,0 +1,37 @@
/*
* F09Handler.cpp
*
* Created on: 2017/04/26
* Author: Tim Evers
*/
#include "F09Handler.h"
static F09Handler *instance;
F09Handler *F09Handler::getInstance()
{
if (!instance)
{
instance = new F09Handler();
};
return instance;
};
F09Handler::F09Handler()
{
}
int F09Handler::execute(Command *command)
{
if (LOGGING)
{
Serial.print("R99 Reset emergency stop\r\n");
}
CurrentState::getInstance()->setEmergencyStop();
return 0;
}

26
src/F09Handler.h 100644
View File

@ -0,0 +1,26 @@
/*
* F09Handler.h
*
* Created on: 2017/04/26
* Author: Tim Evers
*/
#ifndef F09HANDLER_H_
#define F09HANDLER_H_
#include "GCodeHandler.h"
#include "Config.h"
#include "CurrentState.h"
class F09Handler : public GCodeHandler
{
public:
static F09Handler *getInstance();
int execute(Command *);
private:
F09Handler();
F09Handler(F09Handler const &);
void operator=(F09Handler const &);
};
#endif /* F09HANDLER_H_ */

View File

@ -130,6 +130,11 @@ GCodeHandler *GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum)
handler = G28Handler::getInstance();
}
if (codeEnum == F09)
{
handler = F09Handler::getInstance();
}
if (codeEnum == F11)
{
handler = F11Handler::getInstance();

View File

@ -15,6 +15,8 @@
#include "G00Handler.h"
#include "G28Handler.h"
#include "F09Handler.h"
#include "F11Handler.h"
#include "F12Handler.h"
#include "F13Handler.h"

View File

@ -262,6 +262,16 @@ void ParameterList::loadDefaultValue(int id)
paramValues[id] = MOVEMENT_KEEP_ACTIVE_Z_DEFAULT;
break;
case MOVEMENT_HOME_AT_BOOT_X:
paramValues[id] = MOVEMENT_HOME_AT_BOOT_X_DEFAULT;
break;
case MOVEMENT_HOME_AT_BOOT_Y:
paramValues[id] = MOVEMENT_HOME_AT_BOOT_Y_DEFAULT;
break;
case MOVEMENT_HOME_AT_BOOT_Z:
paramValues[id] = MOVEMENT_HOME_AT_BOOT_Z_DEFAULT;
break;
case MOVEMENT_INVERT_ENDPOINTS_X:
paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT;
break;
@ -480,6 +490,9 @@ bool ParameterList::validParam(int id)
case MOVEMENT_KEEP_ACTIVE_X:
case MOVEMENT_KEEP_ACTIVE_Y:
case MOVEMENT_KEEP_ACTIVE_Z:
case MOVEMENT_HOME_AT_BOOT_X:
case MOVEMENT_HOME_AT_BOOT_Y:
case MOVEMENT_HOME_AT_BOOT_Z:
case MOVEMENT_ENABLE_ENDPOINTS_X:
case MOVEMENT_ENABLE_ENDPOINTS_Y:
case MOVEMENT_ENABLE_ENDPOINTS_Z:
@ -524,6 +537,9 @@ bool ParameterList::validParam(int id)
case ENCODER_INVERT_X:
case ENCODER_INVERT_Y:
case ENCODER_INVERT_Z:
case MOVEMENT_AXIS_NR_STEPS_X:
case MOVEMENT_AXIS_NR_STEPS_Y:
case MOVEMENT_AXIS_NR_STEPS_Z:
case PIN_GUARD_1_PIN_NR:
case PIN_GUARD_1_TIME_OUT:
case PIN_GUARD_1_ACTIVE_STATE:

View File

@ -26,6 +26,10 @@ enum ParamListEnum
MOVEMENT_KEEP_ACTIVE_Y = 16,
MOVEMENT_KEEP_ACTIVE_Z = 17,
MOVEMENT_HOME_AT_BOOT_X = 18,
MOVEMENT_HOME_AT_BOOT_Y = 19,
MOVEMENT_HOME_AT_BOOT_Z = 20,
MOVEMENT_INVERT_ENDPOINTS_X = 21,
MOVEMENT_INVERT_ENDPOINTS_Y = 22,
MOVEMENT_INVERT_ENDPOINTS_Z = 23,
@ -86,7 +90,7 @@ enum ParamListEnum
ENCODER_INVERT_Y = 132,
ENCODER_INVERT_Z = 133,
// not used in software at this time
// sizes of axis
MOVEMENT_AXIS_NR_STEPS_X = 141,
MOVEMENT_AXIS_NR_STEPS_Y = 142,
MOVEMENT_AXIS_NR_STEPS_Z = 143,

View File

@ -24,19 +24,40 @@ int PinControl::setMode(int pinNr, int mode)
int PinControl::writeValue(int pinNr, int value, int mode)
{
if (mode == 0)
if (pinNr > 0 && pinNr <= 52 && (mode == 0 || mode == 1))
{
digitalWrite(pinNr, value);
return 0;
}
if (mode == 1)
{
analogWrite(pinNr, value);
return 0;
pinWritten[mode][pinNr] = true;
if (mode == 0)
{
digitalWrite(pinNr, value);
return 0;
}
if (mode == 1)
{
analogWrite(pinNr, value);
return 0;
}
}
return 1;
}
// Set all pins that were once used for writing to zero
void PinControl::resetPinsUsed()
{
for (int pinNr = 1; pinNr <= 52; pinNr++)
{
if (pinWritten[0][pinNr])
{
digitalWrite(pinNr, false);
}
if (pinWritten[1][pinNr])
{
analogWrite(pinNr, 0);
}
}
}
int PinControl::readValue(int pinNr, int mode)
{

View File

@ -25,11 +25,15 @@ public:
int writeValue(int pinNr, int value, int mode);
int readValue(int pinNr, int mode);
int writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode);
void resetPinsUsed();
private:
PinControl();
PinControl(PinControl const &);
void operator=(PinControl const &);
bool pinWritten[1][56];
};
#endif /* PINCONTROL_H_ */

View File

@ -206,8 +206,8 @@ int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
// load motor and encoder settings
loadMotorSettings();
loadEncoderSettings();
//loadMotorSettings();
//loadEncoderSettings();
// load current encoder coordinates
//axisX.setCurrentPosition(encoderX.currentPosition());
@ -249,6 +249,42 @@ int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
destinationPoint[1] = yDest;
destinationPoint[2] = zDest;
if (abs(destinationPoint[0]) > abs(motorMaxSize[0]) && motorMaxSize[0] != 0)
{
if (destinationPoint[0] < 0)
{
destinationPoint[0] = abs(motorMaxSize[0]);
}
else
{
destinationPoint[0] = -abs(motorMaxSize[0]);
}
}
if (abs(destinationPoint[1]) > abs(motorMaxSize[1]) && motorMaxSize[1] != 0)
{
if (destinationPoint[1] < 0)
{
destinationPoint[1] = abs(motorMaxSize[1]);
}
else
{
destinationPoint[1] = -abs(motorMaxSize[1]);
}
}
if (abs(destinationPoint[2]) > abs(motorMaxSize[2]) && motorMaxSize[2] != 0)
{
if (destinationPoint[2] < 0)
{
destinationPoint[2] = abs(motorMaxSize[2]);
}
else
{
destinationPoint[2] = -abs(motorMaxSize[2]);
}
}
motorConsMissedSteps[0] = 0;
motorConsMissedSteps[1] = 0;
motorConsMissedSteps[2] = 0;
@ -298,6 +334,8 @@ int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
axisY.checkMovement();
axisZ.checkMovement();
emergencyStop = CurrentState::getInstance()->isEmergencyStop();
// Let the interrupt handle all the movements
while ((axisActive[0] || axisActive[1] || axisActive[2]) && !emergencyStop)
{
@ -324,14 +362,14 @@ int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
Serial.print(" deactivate motor X due to missed steps");
Serial.print("\r\n");
if (axisX.movingToHome())
{
encoderX.setPosition(0);
axisX.setCurrentPosition(0);
Serial.print("R99");
Serial.print(" home position X axis detected with encoder");
Serial.print("\r\n");
}
//if (axisX.movingToHome())
//{
// encoderX.setPosition(0);
// axisX.setCurrentPosition(0);
// Serial.print("R99");
// Serial.print(" home position X axis detected with encoder");
// Serial.print("\r\n");
//}
}
if (motorConsMissedSteps[1] > motorConsMissedStepsMax[1])
@ -341,14 +379,14 @@ int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
Serial.print(" deactivate motor Y due to missed steps");
Serial.print("\r\n");
if (axisY.movingToHome())
{
encoderY.setPosition(0);
axisY.setCurrentPosition(0);
Serial.print("R99");
Serial.print(" home position Y axis detected with encoder");
Serial.print("\r\n");
}
//if (axisY.movingToHome())
//{
// encoderY.setPosition(0);
// axisY.setCurrentPosition(0);
// Serial.print("R99");
// Serial.print(" home position Y axis detected with encoder");
// Serial.print("\r\n");
//}
}
if (motorConsMissedSteps[2] > motorConsMissedStepsMax[2])
@ -358,14 +396,14 @@ int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
Serial.print(" deactivate motor Z due to missed steps");
Serial.print("\r\n");
if (axisZ.movingToHome())
{
encoderZ.setPosition(0);
axisZ.setCurrentPosition(0);
Serial.print("R99");
Serial.print(" home position Z axis detected with encoder");
Serial.print("\r\n");
}
//if (axisZ.movingToHome())
//{
// encoderZ.setPosition(0);
// axisZ.setCurrentPosition(0);
// Serial.print("R99");
// Serial.print(" home position Z axis detected with encoder");
// Serial.print("\r\n");
//}
}
if (axisX.endStopAxisReached(false))
@ -518,8 +556,12 @@ int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
disableMotors();
// Return error
if (emergencyStop)
{
CurrentState::getInstance()->setEmergencyStop();
}
// Return error
return error;
}
@ -1011,6 +1053,10 @@ void StepperControl::loadMotorSettings()
motorKeepActive[1] = ParameterList::getInstance()->getValue(MOVEMENT_KEEP_ACTIVE_Y);
motorKeepActive[2] = ParameterList::getInstance()->getValue(MOVEMENT_KEEP_ACTIVE_Z);
motorMaxSize[0] = ParameterList::getInstance()->getValue(MOVEMENT_AXIS_NR_STEPS_X);
motorMaxSize[1] = ParameterList::getInstance()->getValue(MOVEMENT_AXIS_NR_STEPS_Y);
motorMaxSize[2] = ParameterList::getInstance()->getValue(MOVEMENT_AXIS_NR_STEPS_Z);
motor2Inv[0] = intToBool(ParameterList::getInstance()->getValue(MOVEMENT_SECONDARY_MOTOR_INVERT_X));
motor2Inv[1] = false;
motor2Inv[2] = false;

View File

@ -19,6 +19,7 @@
#include <stdlib.h>
#include "Command.h"
class StepperControl
{
public:
@ -64,8 +65,8 @@ private:
void checkAxisVsEncoder(StepperControlAxis *axis, StepperControlEncoder *encoder, float *missedSteps, long *lastPosition, long *encoderLastPosition, int *encoderUseForPos, float *encoderStepDecay, bool *encoderEnabled);
void checkAxisSubStatus(StepperControlAxis *axis, int *axisSubStatus);
bool axisActive[3];
int axisSubStep[3];
bool axisActive[3] = { false, false, false };
int axisSubStep[3] = { 0, 0, 0 };
void loadMotorSettings();
void loadEncoderSettings();
@ -80,31 +81,32 @@ private:
unsigned long getMaxLength(unsigned long lengths[3]);
bool endStopsReached();
bool homeIsUp[3];
long speedMax[3];
long speedMin[3];
long stepsAcc[3];
bool motorInv[3];
bool motorKeepActive[3];
bool motor2Inv[3];
bool motor2Enbl[3];
bool endStInv[3];
bool endStEnbl[3];
long timeOut[3];
bool homeIsUp[3] = {false, false, false};
long speedMax[3] = {0, 0, 0 };
long speedMin[3] = { 0, 0, 0 };
long stepsAcc[3] = { 0, 0, 0 };
bool motorInv[3] = { false, false, false };
bool motorMaxSize[3] = { false, false, false };
bool motorKeepActive[3] = { false, false, false };
bool motor2Inv[3] = { false, false, false };
bool motor2Enbl[3] = { false, false, false };
bool endStInv[3] = { false, false, false };
bool endStEnbl[3] = { false, false, false };
long timeOut[3] = { 0, 0, 0 };
float motorConsMissedSteps[3];
long motorLastPosition[3];
long motorConsEncoderLastPosition[3];
float motorConsMissedSteps[3] = { 0, 0, 0 };
long motorLastPosition[3] = { 0, 0, 0 };
long motorConsEncoderLastPosition[3] = { 0, 0, 0 };
int motorConsMissedStepsMax[3];
float motorConsMissedStepsDecay[3];
bool motorConsEncoderEnabled[3];
int motorConsEncoderType[3];
int motorConsEncoderScaling[3];
int motorConsEncoderUseForPos[3];
int motorConsEncoderInvert[3];
int motorConsMissedStepsMax[3] = { 0, 0, 0 };
float motorConsMissedStepsDecay[3] = { 0, 0, 0 };
bool motorConsEncoderEnabled[3] = { false, false, false };
int motorConsEncoderType[3] = { 0, 0, 0 };
int motorConsEncoderScaling[3] = { 0, 0, 0 };
int motorConsEncoderUseForPos[3] = { 0, 0, 0 };
int motorConsEncoderInvert[3] = { 0, 0, 0 };
bool motorMotorsEnabled;
bool motorMotorsEnabled = false;
};
#endif /* STEPPERCONTROL_H_ */

View File

@ -65,19 +65,19 @@ unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long curren
{
staPos = abs(sourcePosition);
endPos = abs(destinationPosition);
;
}
else
{
staPos = abs(destinationPosition);
;
endPos = abs(sourcePosition);
}
/**/
unsigned long halfway = ((endPos - staPos) / 2) + staPos;
//unsigned long halfway = ((destinationPosition - sourcePosition) / 2) + sourcePosition;
// Set the minimum speed if the position would be out of bounds
if (curPos < staPos || curPos > endPos)
if (curPos < staPos || curPos > endPos || (!motorHomeIsUp && currentPosition <= 0) || (motorHomeIsUp && currentPosition >= 0))
{
newSpeed = minSpeed;
movementCrawling = true;
@ -367,15 +367,16 @@ void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint
coordHomeAxis = home;
// Limit normal movmement to the home position
if (!motorHomeIsUp && coordDestinationPoint < 0)
{
coordDestinationPoint = 0;
}
/**/
//if (!motorHomeIsUp && coordDestinationPoint < 0)
//{
// coordDestinationPoint = 0;
//}
if (motorHomeIsUp && coordDestinationPoint > 0)
{
coordDestinationPoint = 0;
}
//if (motorHomeIsUp && coordDestinationPoint > 0)
//{
// coordDestinationPoint = 0;
//}
// Initialize movement variables
moveTicks = 0;

View File

@ -8,6 +8,7 @@
#include "TimerOne.h"
#include "MemoryFree.h"
#include "Debug.h"
#include "CurrentState.h"
static char commandEndChar = 0x0A;
static GCodeProcessor *gCodeProcessor = new GCodeProcessor();
@ -15,6 +16,7 @@ static GCodeProcessor *gCodeProcessor = new GCodeProcessor();
unsigned long lastAction;
unsigned long currentTime;
unsigned long cycleCounter = 0;
bool previousEmergencyStop = false;
int lastParamChangeNr = 0;
@ -109,6 +111,10 @@ void setup()
// Start the motor handling
//ServoControl::getInstance()->attach();
// Load motor settings
StepperControl::getInstance()->loadSettings();
/**/
// Dump all values to the serial interface
ParameterList::getInstance()->readAllValues();
@ -125,6 +131,21 @@ void setup()
// 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
@ -144,12 +165,17 @@ void loop()
// Get the input and start processing on receiving 'new line'
incomingChar = Serial.read();
// Filter out emergency stop. Emergency stop is captured in moving routines
// Filter out emergency stop.
if (!(incomingChar == 69 || incomingChar == 101))
{
incomingCommandArray[incomingCommandPointer] = incomingChar;
incomingCommandPointer++;
}
else
{
CurrentState::getInstance()->setEmergencyStop();
}
// 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)
@ -162,14 +188,10 @@ void loop()
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++)
{
if (incomingChar)
commandChar[i] = incomingCommandArray[i];
}
commandChar[incomingCommandPointer] = 0;
@ -189,18 +211,27 @@ void loop()
{
command->print();
}
Serial.print("R99 V1 \r\n");
gCodeProcessor->execute(command);
Serial.print("R99 V2 \r\n");
free(command);
}
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();
// Check if parameters are changes, and if so load the new settings
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber())
{
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();

View File

@ -84,6 +84,7 @@
<ItemGroup>
<ClCompile Include="Command.cpp" />
<ClCompile Include="CurrentState.cpp" />
<ClCompile Include="F09Handler.cpp" />
<ClCompile Include="F11Handler.cpp" />
<ClCompile Include="F12Handler.cpp" />
<ClCompile Include="F13Handler.cpp" />
@ -126,6 +127,7 @@
<ClInclude Include="Config.h" />
<ClInclude Include="CurrentState.h" />
<ClInclude Include="Debug.h" />
<ClInclude Include="F09Handler.h" />
<ClInclude Include="F11Handler.h" />
<ClInclude Include="F12Handler.h" />
<ClInclude Include="F13Handler.h" />

View File

@ -132,6 +132,9 @@
<ClCompile Include="StepperControl.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="F09Handler.cpp">
<Filter>Source Files</Filter>
</ClCompile>
</ItemGroup>
<ItemGroup>
<ClInclude Include="GCodeProcessor.h">
@ -263,5 +266,8 @@
<ClInclude Include="Debug.h">
<Filter>Source Files</Filter>
</ClInclude>
<ClInclude Include="F09Handler.h">
<Filter>Header Files</Filter>
</ClInclude>
</ItemGroup>
</Project>