commit
413f5c868f
|
@ -0,0 +1,63 @@
|
|||
###############################################################################
|
||||
# Set default behavior to automatically normalize line endings.
|
||||
###############################################################################
|
||||
* text=auto
|
||||
|
||||
###############################################################################
|
||||
# Set default behavior for command prompt diff.
|
||||
#
|
||||
# This is need for earlier builds of msysgit that does not have it on by
|
||||
# default for csharp files.
|
||||
# Note: This is only used by command line
|
||||
###############################################################################
|
||||
#*.cs diff=csharp
|
||||
|
||||
###############################################################################
|
||||
# Set the merge driver for project and solution files
|
||||
#
|
||||
# Merging from the command prompt will add diff markers to the files if there
|
||||
# are conflicts (Merging from VS is not affected by the settings below, in VS
|
||||
# the diff markers are never inserted). Diff markers may cause the following
|
||||
# file extensions to fail to load in VS. An alternative would be to treat
|
||||
# these files as binary and thus will always conflict and require user
|
||||
# intervention with every merge. To do so, just uncomment the entries below
|
||||
###############################################################################
|
||||
#*.sln merge=binary
|
||||
#*.csproj merge=binary
|
||||
#*.vbproj merge=binary
|
||||
#*.vcxproj merge=binary
|
||||
#*.vcproj merge=binary
|
||||
#*.dbproj merge=binary
|
||||
#*.fsproj merge=binary
|
||||
#*.lsproj merge=binary
|
||||
#*.wixproj merge=binary
|
||||
#*.modelproj merge=binary
|
||||
#*.sqlproj merge=binary
|
||||
#*.wwaproj merge=binary
|
||||
|
||||
###############################################################################
|
||||
# behavior for image files
|
||||
#
|
||||
# image files are treated as binary by default.
|
||||
###############################################################################
|
||||
#*.jpg binary
|
||||
#*.png binary
|
||||
#*.gif binary
|
||||
|
||||
###############################################################################
|
||||
# diff behavior for common document formats
|
||||
#
|
||||
# Convert binary document formats to text before diffing them. This feature
|
||||
# is only available from the command line. Turn it on by uncommenting the
|
||||
# entries below.
|
||||
###############################################################################
|
||||
#*.doc diff=astextplain
|
||||
#*.DOC diff=astextplain
|
||||
#*.docx diff=astextplain
|
||||
#*.DOCX diff=astextplain
|
||||
#*.dot diff=astextplain
|
||||
#*.DOT diff=astextplain
|
||||
#*.pdf diff=astextplain
|
||||
#*.PDF diff=astextplain
|
||||
#*.rtf diff=astextplain
|
||||
#*.RTF diff=astextplain
|
|
@ -23,3 +23,6 @@
|
|||
/spec.d
|
||||
/arduino
|
||||
/.build
|
||||
/.vs
|
||||
/src/Debug
|
||||
/src/__vm
|
|
@ -0,0 +1,22 @@
|
|||
|
||||
Microsoft Visual Studio Solution File, Format Version 12.00
|
||||
# Visual Studio 15
|
||||
VisualStudioVersion = 15.0.26403.3
|
||||
MinimumVisualStudioVersion = 10.0.40219.1
|
||||
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "src", "src\src.vcxproj", "{C5F80730-F44F-4478-BDAE-6634EFC2CA88}"
|
||||
EndProject
|
||||
Global
|
||||
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
||||
Debug|x86 = Debug|x86
|
||||
Release|x86 = Release|x86
|
||||
EndGlobalSection
|
||||
GlobalSection(ProjectConfigurationPlatforms) = postSolution
|
||||
{C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.ActiveCfg = Debug|Win32
|
||||
{C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.Build.0 = Debug|Win32
|
||||
{C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.ActiveCfg = Release|Win32
|
||||
{C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.Build.0 = Release|Win32
|
||||
EndGlobalSection
|
||||
GlobalSection(SolutionProperties) = preSolution
|
||||
HideSolutionNode = FALSE
|
||||
EndGlobalSection
|
||||
EndGlobal
|
|
@ -11,17 +11,6 @@ const char timeCode = 'T';
|
|||
const char modeCode = 'M';
|
||||
const char msgQueueCode = 'Q';
|
||||
|
||||
double axisValue[3] = { 0.0, 0.0, 0.0 };
|
||||
long axisSpeedValue[3] = { 0, 0, 0 };
|
||||
double speedValue = 0.0;
|
||||
long parameterId = 0;
|
||||
long parameterValue = 0;
|
||||
long parameterValue2 = 0;
|
||||
long element = 0;
|
||||
long time = 0;
|
||||
long mode = 0;
|
||||
long msgQueue = 0;
|
||||
|
||||
CommandCodeEnum commandCodeEnum = CODE_UNDEFINED;
|
||||
|
||||
Command::Command(char * commandChar) {
|
||||
|
@ -30,7 +19,7 @@ Command::Command(char * commandChar) {
|
|||
char* charPointer;
|
||||
bool invalidCommand = false;
|
||||
|
||||
charPointer = strtok(charBuf, " ");
|
||||
charPointer = strtok(charBuf, " \n\r");
|
||||
|
||||
if (charPointer[0] == 'G' || charPointer[0] == 'F') {
|
||||
commandCodeEnum = getGCodeEnum(charPointer);
|
||||
|
@ -122,6 +111,9 @@ CommandCodeEnum Command::getGCodeEnum(char* code) {
|
|||
if (strcmp(code, "F83") == 0) {
|
||||
return F83;
|
||||
}
|
||||
if (strcmp(code, "F84") == 0) {
|
||||
return F84;
|
||||
}
|
||||
|
||||
return CODE_UNDEFINED;
|
||||
}
|
||||
|
|
|
@ -31,7 +31,8 @@ enum CommandCodeEnum
|
|||
F61 = 161,
|
||||
F81 = 181,
|
||||
F82 = 182,
|
||||
F83 = 183
|
||||
F83 = 183,
|
||||
F84 = 184
|
||||
};
|
||||
|
||||
//#define NULL 0
|
||||
|
@ -62,6 +63,18 @@ public:
|
|||
private:
|
||||
CommandCodeEnum getGCodeEnum(char* code);
|
||||
void getParameter(char* charPointer);
|
||||
|
||||
double axisValue[3] = { 0.0, 0.0, 0.0 };
|
||||
long axisSpeedValue[3] = { 0, 0, 0 };
|
||||
double speedValue = 0.0;
|
||||
long parameterId = 0;
|
||||
long parameterValue = 0;
|
||||
long parameterValue2 = 0;
|
||||
long element = 0;
|
||||
long time = 0;
|
||||
long mode = 0;
|
||||
long msgQueue = 0;
|
||||
|
||||
};
|
||||
|
||||
#endif /* COMMAND_H_ */
|
||||
|
|
46
src/Config.h
46
src/Config.h
|
@ -12,25 +12,25 @@ const int LOGGING = 0;
|
|||
|
||||
const int INCOMING_CMD_BUF_SIZE = 50;
|
||||
|
||||
//const unsigned long STEPS_FOR_ACC_DEC = 20;
|
||||
//const unsigned int MAX_ACCELERATION_STEPS_PER_SECOND = 2;
|
||||
|
||||
//const unsigned int MOVEMENT_STEPS_ACC_DEC = 100;
|
||||
//const unsigned int MOVEMENT_MAX_STEPS_PER_SECOND = 1000;
|
||||
//const unsigned int MOVEMENT_HOME_SPEED_S_P_S = 200;
|
||||
//const unsigned int MOVEMENT_TIMEOUT = 30;
|
||||
//const unsigned int INVERT_ENDSTOPS = 1;
|
||||
//const bool AXIS_HOME_UP_X = false;
|
||||
//const bool AXIS_HOME_UP_Y = false;
|
||||
//const bool AXIS_HOME_UP_Z = true;
|
||||
|
||||
/*
|
||||
const String COMM_REPORT_CMD_IDLE = "R00";
|
||||
const String COMM_REPORT_CMD_START = "R01";
|
||||
const String COMM_REPORT_CMD_DONE = "R02";
|
||||
const String COMM_REPORT_CMD_ERROR = "R03";
|
||||
const String COMM_REPORT_CMD_BUSY = "R04";
|
||||
const String COMM_REPORT_CMD_STATUS = "R05";
|
||||
const String COMM_REPORT_CALIB_STATUS = "R06";
|
||||
const String COMM_REPORT_COMMENT = "R99";
|
||||
*/
|
||||
|
||||
const char COMM_REPORT_CMD_IDLE[4] = {'R','0','0','\0'};
|
||||
const char COMM_REPORT_CMD_START[4] = {'R','0','1','\0'};
|
||||
const char COMM_REPORT_CMD_DONE[4] = {'R','0','2','\0'};
|
||||
const char COMM_REPORT_CMD_ERROR[4] = {'R','0','3','\0'};
|
||||
const char COMM_REPORT_CMD_BUSY[4] = {'R','0','4','\0'};
|
||||
const char COMM_REPORT_CMD_STATUS[4] = {'R','0','5','\0'};
|
||||
const char COMM_REPORT_CALIB_STATUS[4] = {'R','0','6','\0'};
|
||||
const char COMM_REPORT_NO_CONFIG[4] = {'R','8','8','\0'};
|
||||
const char COMM_REPORT_COMMENT[4] = {'R','9','9','\0'};
|
||||
|
||||
const int COMM_REPORT_MOVE_STATUS_IDLE = 0;
|
||||
const int COMM_REPORT_MOVE_STATUS_START_MOTOR = 1;
|
||||
|
@ -47,7 +47,7 @@ const int COMM_REPORT_CALIBRATE_STATUS_TO_END = 2;
|
|||
const int COMM_REPORT_CALIBRATE_STATUS_ERROR = -1;
|
||||
|
||||
|
||||
const int MOVEMENT_INTERRUPT_SPEED = 100; // Interrupt cycle in micro seconds
|
||||
const int MOVEMENT_INTERRUPT_SPEED = 200; // Interrupt cycle in micro seconds
|
||||
|
||||
const unsigned int MOVEMENT_SPEED_BASE_TIME = 2000;
|
||||
const unsigned int MOVEMENT_DELAY = 250;
|
||||
|
@ -55,6 +55,9 @@ const unsigned int MOVEMENT_DELAY = 250;
|
|||
const long PARAM_VERSION_DEFAULT = 1;
|
||||
const long PARAM_TEST_DEFAULT = 0;
|
||||
|
||||
const long PARAM_CONFIG_OK_DEFAULT = 0;
|
||||
const long PARAM_USE_EEPROM_DEFAULT = 1;
|
||||
|
||||
const long MOVEMENT_TIMEOUT_X_DEFAULT = 120;
|
||||
const long MOVEMENT_TIMEOUT_Y_DEFAULT = 120;
|
||||
const long MOVEMENT_TIMEOUT_Z_DEFAULT = 120;
|
||||
|
@ -98,6 +101,18 @@ const long ENCODER_ENABLED_X_DEFAULT = 0;
|
|||
const long ENCODER_ENABLED_Y_DEFAULT = 0;
|
||||
const long ENCODER_ENABLED_Z_DEFAULT = 0;
|
||||
|
||||
// Type of enocder.
|
||||
// 0 = non-differential encoder, channel A,B
|
||||
// 1 = differenttial encoder, channel A, A*, B, B*
|
||||
const long ENCODER_TYPE_X_DEFAULT = 0;
|
||||
const long ENCODER_TYPE_Y_DEFAULT = 0;
|
||||
const long ENCODER_TYPE_Z_DEFAULT = 0;
|
||||
|
||||
// Position = encoder position * scaling / 100
|
||||
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
|
||||
const long ENCODER_MISSED_STEPS_MAX_X_DEFAULT = 10;
|
||||
const long ENCODER_MISSED_STEPS_MAX_Y_DEFAULT = 10;
|
||||
|
@ -132,7 +147,6 @@ const long PIN_GUARD_5_ACTIVE_STATE_DEFAULT = 1;
|
|||
|
||||
const long STATUS_GENERAL_DEFAULT = 0;
|
||||
|
||||
|
||||
const String SOFTWARE_VERSION = "GENESIS V.01.07.EXPERIMENTAL";
|
||||
const char SOFTWARE_VERSION[] = "GENESIS.V.01.08.EXPERIMENTAL\0";
|
||||
|
||||
#endif /* CONFIG_H_ */
|
||||
|
|
|
@ -0,0 +1,49 @@
|
|||
/*
|
||||
* F84Handler.cpp
|
||||
*
|
||||
* Created on: 2017/04/13
|
||||
* Author: Rick Carlino
|
||||
*/
|
||||
|
||||
#include "F84Handler.h"
|
||||
|
||||
static F84Handler *instance;
|
||||
const double DO_RESET = 1;
|
||||
|
||||
F84Handler *F84Handler::getInstance()
|
||||
{
|
||||
if (!instance)
|
||||
{
|
||||
instance = new F84Handler();
|
||||
};
|
||||
return instance;
|
||||
};
|
||||
|
||||
F84Handler::F84Handler()
|
||||
{
|
||||
}
|
||||
|
||||
int F84Handler::execute(Command *command)
|
||||
{
|
||||
|
||||
if (command->getX() == DO_RESET)
|
||||
{
|
||||
Serial.print("R99 Will zero X");
|
||||
StepperControl::getInstance()->setPositionX(0);
|
||||
}
|
||||
|
||||
if (command->getY() == DO_RESET)
|
||||
{
|
||||
Serial.print("R99 Will zero Y");
|
||||
StepperControl::getInstance()->setPositionY(0);
|
||||
}
|
||||
|
||||
if (command->getZ() == DO_RESET)
|
||||
{
|
||||
Serial.print("R99 Will zero Z");
|
||||
StepperControl::getInstance()->setPositionZ(0);
|
||||
}
|
||||
|
||||
CurrentState::getInstance()->printQAndNewLine();
|
||||
return 0;
|
||||
}
|
|
@ -0,0 +1,31 @@
|
|||
/*
|
||||
* F84Handler.h
|
||||
*
|
||||
* Created on: 2017/4/13
|
||||
* Author: Rick Carlino
|
||||
*/
|
||||
|
||||
#ifndef F84HANDLER_H_
|
||||
#define F84HANDLER_H_
|
||||
#include "GCodeHandler.h"
|
||||
#include "Config.h"
|
||||
#include "CurrentState.h"
|
||||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
|
||||
class F84Handler : public GCodeHandler
|
||||
{
|
||||
public:
|
||||
static F84Handler *getInstance();
|
||||
int execute(Command *);
|
||||
|
||||
private:
|
||||
F84Handler();
|
||||
F84Handler(F84Handler const &);
|
||||
void operator=(F84Handler const &);
|
||||
long adjustStepAmount(long);
|
||||
long getNumberOfSteps(double, double);
|
||||
};
|
||||
|
||||
#endif /* F84HANDLER_H_ */
|
|
@ -25,10 +25,34 @@ int GCodeProcessor::execute(Command* command) {
|
|||
|
||||
int execution = 0;
|
||||
|
||||
|
||||
long Q = command->getQ();
|
||||
CurrentState::getInstance()->setQ(Q);
|
||||
|
||||
|
||||
// Do not execute the command when the config complete parameter is not
|
||||
// set by the raspberry pi and it's asked to do a move command
|
||||
|
||||
// Tim 2017-04-15 Disable until the raspberry code is ready
|
||||
/*
|
||||
if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
|
||||
if ( command->getCodeEnum() == G00 ||
|
||||
command->getCodeEnum() == G01 ||
|
||||
command->getCodeEnum() == F11 ||
|
||||
command->getCodeEnum() == F12 ||
|
||||
command->getCodeEnum() == F13 ||
|
||||
command->getCodeEnum() == F14 ||
|
||||
command->getCodeEnum() == F15 ||
|
||||
command->getCodeEnum() == F16 ) {
|
||||
|
||||
Serial.print(COMM_REPORT_NO_CONFIG);
|
||||
CurrentState::getInstance()->printQAndNewLine();
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
// Return error when no command or invalid command is found
|
||||
|
||||
if(command == NULL) {
|
||||
if(LOGGING) {
|
||||
printCommandLog(command);
|
||||
|
@ -43,6 +67,8 @@ int GCodeProcessor::execute(Command* command) {
|
|||
return -1;
|
||||
}
|
||||
|
||||
// Get the right handler for this command
|
||||
|
||||
GCodeHandler* handler = getGCodeHandler(command->getCodeEnum());
|
||||
|
||||
if(handler == NULL) {
|
||||
|
@ -50,6 +76,8 @@ int GCodeProcessor::execute(Command* command) {
|
|||
return -1;
|
||||
}
|
||||
|
||||
// Execute te command, report start and end
|
||||
|
||||
Serial.print(COMM_REPORT_CMD_START);
|
||||
CurrentState::getInstance()->printQAndNewLine();
|
||||
|
||||
|
@ -70,6 +98,10 @@ GCodeHandler* GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum) {
|
|||
|
||||
GCodeHandler* handler = NULL;
|
||||
|
||||
// These are if statements so they can be disabled as test
|
||||
// Usefull when running into memory issues again
|
||||
|
||||
|
||||
if (codeEnum == G00) {handler = G00Handler::getInstance();}
|
||||
|
||||
if (codeEnum == G28) {handler = G28Handler::getInstance();}
|
||||
|
@ -94,67 +126,12 @@ GCodeHandler* GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum) {
|
|||
if (codeEnum == F43) {handler = F43Handler::getInstance();}
|
||||
if (codeEnum == F44) {handler = F44Handler::getInstance();}
|
||||
|
||||
// if (codeEnum == F61) {handler = F61Handler::getInstance();}
|
||||
if (codeEnum == F61) {handler = F61Handler::getInstance();}
|
||||
|
||||
if (codeEnum == F81) {handler = F81Handler::getInstance();}
|
||||
if (codeEnum == F82) {handler = F82Handler::getInstance();}
|
||||
if (codeEnum == F83) {handler = F83Handler::getInstance();}
|
||||
|
||||
|
||||
/*
|
||||
switch(codeEnum) {
|
||||
case G00:
|
||||
return G00Handler::getInstance();
|
||||
case G28:
|
||||
return G28Handler::getInstance();
|
||||
|
||||
case F11:
|
||||
return F11Handler::getInstance();
|
||||
case F12:
|
||||
return F12Handler::getInstance();
|
||||
case F13:
|
||||
return F13Handler::getInstance();
|
||||
|
||||
case F14:
|
||||
return F14Handler::getInstance();
|
||||
case F15:
|
||||
return F15Handler::getInstance();
|
||||
case F16:
|
||||
return F16Handler::getInstance();
|
||||
|
||||
case F20:
|
||||
return F20Handler::getInstance();
|
||||
case F21:
|
||||
return F21Handler::getInstance();
|
||||
case F22:
|
||||
return F22Handler::getInstance();
|
||||
|
||||
case F31:
|
||||
return F31Handler::getInstance();
|
||||
case F32:
|
||||
return F32Handler::getInstance();
|
||||
|
||||
case F41:
|
||||
return F41Handler::getInstance();
|
||||
case F42:
|
||||
return F42Handler::getInstance();
|
||||
case F43:
|
||||
return F43Handler::getInstance();
|
||||
case F44:
|
||||
return F44Handler::getInstance();
|
||||
|
||||
case F61:
|
||||
return F61Handler::getInstance();
|
||||
|
||||
case F81:
|
||||
return F81Handler::getInstance();
|
||||
case F82:
|
||||
return F82Handler::getInstance();
|
||||
case F83:
|
||||
return F83Handler::getInstance();
|
||||
|
||||
}
|
||||
*/
|
||||
if (codeEnum == F84) {handler = F84Handler::getInstance();}
|
||||
|
||||
|
||||
return handler;
|
||||
|
|
|
@ -35,11 +35,12 @@
|
|||
#include "F43Handler.h"
|
||||
#include "F44Handler.h"
|
||||
|
||||
//#include "F61Handler.h"
|
||||
#include "F61Handler.h"
|
||||
|
||||
#include "F81Handler.h"
|
||||
#include "F82Handler.h"
|
||||
#include "F83Handler.h"
|
||||
#include "F84Handler.h"
|
||||
|
||||
class GCodeProcessor {
|
||||
public:
|
||||
|
|
|
@ -0,0 +1,52 @@
|
|||
#if (ARDUINO >= 100)
|
||||
#include <Arduino.h>
|
||||
#else
|
||||
#include <WProgram.h>
|
||||
#endif
|
||||
|
||||
extern unsigned int __heap_start;
|
||||
extern void *__brkval;
|
||||
|
||||
/*
|
||||
* The free list structure as maintained by the
|
||||
* avr-libc memory allocation routines.
|
||||
*/
|
||||
struct __freelist
|
||||
{
|
||||
size_t sz;
|
||||
struct __freelist *nx;
|
||||
};
|
||||
|
||||
/* The head of the free list structure */
|
||||
extern struct __freelist *__flp;
|
||||
|
||||
#include "MemoryFree.h"
|
||||
|
||||
/* Calculates the size of the free list */
|
||||
int freeListSize()
|
||||
{
|
||||
struct __freelist* current;
|
||||
int total = 0;
|
||||
for (current = __flp; current; current = current->nx)
|
||||
{
|
||||
total += 2; /* Add two bytes for the memory block's header */
|
||||
total += (int) current->sz;
|
||||
}
|
||||
|
||||
return total;
|
||||
}
|
||||
|
||||
int freeMemory()
|
||||
{
|
||||
int free_memory;
|
||||
if ((int)__brkval == 0)
|
||||
{
|
||||
free_memory = ((int)&free_memory) - ((int)&__heap_start);
|
||||
}
|
||||
else
|
||||
{
|
||||
free_memory = ((int)&free_memory) - ((int)__brkval);
|
||||
free_memory += freeListSize();
|
||||
}
|
||||
return free_memory;
|
||||
}
|
|
@ -0,0 +1,18 @@
|
|||
// MemoryFree library based on code posted here:
|
||||
// http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1213583720/15
|
||||
// Extended by Matthew Murdoch to include walking of the free list.
|
||||
|
||||
#ifndef MEMORY_FREE_H
|
||||
#define MEMORY_FREE_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
int freeMemory();
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -14,12 +14,20 @@ ParameterList * ParameterList::getInstance() {
|
|||
ParameterList::ParameterList() {
|
||||
// at the first boot, load default parameters and set the parameter version
|
||||
// so during subsequent boots the values are just loaded from eeprom
|
||||
// unless the eeprom is disabled with a parameter
|
||||
|
||||
int paramChangeNr = 0;
|
||||
|
||||
int paramVersion = readValueEeprom(0);
|
||||
if (paramVersion <= 0) {
|
||||
setAllValuesToDefault();
|
||||
writeAllValuesToEeprom();
|
||||
} else {
|
||||
readAllValuesFromEeprom();
|
||||
//if (readValueEeprom(PARAM_USE_EEPROM) == 1) {
|
||||
readAllValuesFromEeprom();
|
||||
//} else {
|
||||
// setAllValuesToDefault();
|
||||
//}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -52,6 +60,12 @@ int ParameterList::readValue(int id) {
|
|||
|
||||
int ParameterList::writeValue(int id, int value) {
|
||||
|
||||
if (paramChangeNr < 9999) {
|
||||
paramChangeNr++;
|
||||
} else {
|
||||
paramChangeNr = 0;
|
||||
}
|
||||
|
||||
// Check if the value is a valid parameter
|
||||
if (validParam(id)) {
|
||||
// Store the value in memory
|
||||
|
@ -108,6 +122,11 @@ int ParameterList::getValue(int id) {
|
|||
return paramValues[id];
|
||||
}
|
||||
|
||||
int ParameterList::paramChangeNumber() {
|
||||
return paramChangeNr;
|
||||
}
|
||||
|
||||
|
||||
// ===== eeprom handling ====
|
||||
|
||||
int ParameterList::readValueEeprom(int id) {
|
||||
|
@ -183,6 +202,8 @@ void ParameterList::loadDefaultValue(int id) {
|
|||
{
|
||||
case PARAM_VERSION : paramValues[id] = PARAM_VERSION_DEFAULT; break;
|
||||
case PARAM_TEST : paramValues[id] = PARAM_TEST_DEFAULT; break;
|
||||
case PARAM_CONFIG_OK : paramValues[id] = PARAM_CONFIG_OK_DEFAULT; break;
|
||||
case PARAM_USE_EEPROM : paramValues[id] = PARAM_USE_EEPROM; break;
|
||||
|
||||
case MOVEMENT_TIMEOUT_X : paramValues[id] = MOVEMENT_TIMEOUT_X_DEFAULT; break;
|
||||
case MOVEMENT_TIMEOUT_Y : paramValues[id] = MOVEMENT_TIMEOUT_Y_DEFAULT; break;
|
||||
|
@ -223,15 +244,22 @@ void ParameterList::loadDefaultValue(int id) {
|
|||
case ENCODER_ENABLED_Y : paramValues[id] = ENCODER_ENABLED_Y_DEFAULT; break;
|
||||
case ENCODER_ENABLED_Z : paramValues[id] = ENCODER_ENABLED_Z_DEFAULT; break;
|
||||
|
||||
case ENCODER_TYPE_X : paramValues[id] = ENCODER_TYPE_X_DEFAULT; break;
|
||||
case ENCODER_TYPE_Y : paramValues[id] = ENCODER_TYPE_Y_DEFAULT; break;
|
||||
case ENCODER_TYPE_Z : paramValues[id] = ENCODER_TYPE_Z_DEFAULT; break;
|
||||
|
||||
case ENCODER_MISSED_STEPS_MAX_X : paramValues[id] = ENCODER_MISSED_STEPS_MAX_X_DEFAULT; break;
|
||||
case ENCODER_MISSED_STEPS_MAX_Y : paramValues[id] = ENCODER_MISSED_STEPS_MAX_Y_DEFAULT; break;
|
||||
case ENCODER_MISSED_STEPS_MAX_Z : paramValues[id] = ENCODER_MISSED_STEPS_MAX_Z_DEFAULT; break;
|
||||
|
||||
case ENCODER_SCALING_X : paramValues[id] = ENCODER_SCALING_X_DEFAULT; break;
|
||||
case ENCODER_SCALING_Y : paramValues[id] = ENCODER_SCALING_Y_DEFAULT; break;
|
||||
case ENCODER_SCALING_Z : paramValues[id] = ENCODER_SCALING_Z_DEFAULT; break;
|
||||
|
||||
case ENCODER_MISSED_STEPS_DECAY_X : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_X_DEFAULT; break;
|
||||
case ENCODER_MISSED_STEPS_DECAY_Y : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT; break;
|
||||
case ENCODER_MISSED_STEPS_DECAY_Z : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT; break;
|
||||
|
||||
|
||||
case PIN_GUARD_1_PIN_NR : paramValues[id] = PIN_GUARD_1_PIN_NR_DEFAULT; break;
|
||||
case PIN_GUARD_1_TIME_OUT : paramValues[id] = PIN_GUARD_1_TIME_OUT_DEFAULT; break;
|
||||
case PIN_GUARD_1_ACTIVE_STATE : paramValues[id] = PIN_GUARD_1_ACTIVE_STATE_DEFAULT; break;
|
||||
|
@ -262,6 +290,8 @@ bool ParameterList::validParam(int id) {
|
|||
switch(id)
|
||||
{
|
||||
case PARAM_VERSION:
|
||||
case PARAM_CONFIG_OK:
|
||||
case PARAM_USE_EEPROM:
|
||||
case MOVEMENT_TIMEOUT_X:
|
||||
case MOVEMENT_TIMEOUT_Y:
|
||||
case MOVEMENT_TIMEOUT_Z:
|
||||
|
@ -291,9 +321,15 @@ bool ParameterList::validParam(int id) {
|
|||
case ENCODER_ENABLED_X:
|
||||
case ENCODER_ENABLED_Y:
|
||||
case ENCODER_ENABLED_Z:
|
||||
case ENCODER_TYPE_X:
|
||||
case ENCODER_TYPE_Y:
|
||||
case ENCODER_TYPE_Z:
|
||||
case ENCODER_MISSED_STEPS_MAX_X:
|
||||
case ENCODER_MISSED_STEPS_MAX_Y:
|
||||
case ENCODER_MISSED_STEPS_MAX_Z:
|
||||
case ENCODER_SCALING_X:
|
||||
case ENCODER_SCALING_Y:
|
||||
case ENCODER_SCALING_Z:
|
||||
case ENCODER_MISSED_STEPS_DECAY_X:
|
||||
case ENCODER_MISSED_STEPS_DECAY_Y:
|
||||
case ENCODER_MISSED_STEPS_DECAY_Z:
|
||||
|
|
|
@ -7,13 +7,15 @@
|
|||
#include "CurrentState.h"
|
||||
|
||||
//#define NULL 0
|
||||
const int PARAM_NR_OF_PARAMS = 300;
|
||||
const int PARAM_NR_OF_PARAMS = 225;
|
||||
|
||||
|
||||
enum ParamListEnum
|
||||
{
|
||||
PARAM_VERSION = 0,
|
||||
PARAM_TEST = 1,
|
||||
PARAM_CONFIG_OK = 2,
|
||||
PARAM_USE_EEPROM = 3,
|
||||
|
||||
// stepper motor settings
|
||||
|
||||
|
@ -57,10 +59,18 @@ enum ParamListEnum
|
|||
ENCODER_ENABLED_Y = 102,
|
||||
ENCODER_ENABLED_Z = 103,
|
||||
|
||||
ENCODER_TYPE_X = 105,
|
||||
ENCODER_TYPE_Y = 106,
|
||||
ENCODER_TYPE_Z = 107,
|
||||
|
||||
ENCODER_MISSED_STEPS_MAX_X = 111,
|
||||
ENCODER_MISSED_STEPS_MAX_Y = 112,
|
||||
ENCODER_MISSED_STEPS_MAX_Z = 113,
|
||||
|
||||
ENCODER_SCALING_X = 115,
|
||||
ENCODER_SCALING_Y = 116,
|
||||
ENCODER_SCALING_Z = 117,
|
||||
|
||||
ENCODER_MISSED_STEPS_DECAY_X = 121,
|
||||
ENCODER_MISSED_STEPS_DECAY_Y = 122,
|
||||
ENCODER_MISSED_STEPS_DECAY_Z = 123,
|
||||
|
@ -119,10 +129,15 @@ public:
|
|||
|
||||
void sendConfigToModules();
|
||||
|
||||
int paramChangeNumber();
|
||||
|
||||
private:
|
||||
ParameterList();
|
||||
ParameterList(ParameterList const&);
|
||||
void operator=(ParameterList const&);
|
||||
|
||||
int paramChangeNr;
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -65,10 +65,6 @@ StepperControl::StepperControl() {
|
|||
|
||||
// Initialize some variables for testing
|
||||
|
||||
//motorConsMissedStepsMax[0] = 50;
|
||||
//motorConsMissedStepsMax[1] = 50;
|
||||
//motorConsMissedStepsMax[2] = 50;
|
||||
|
||||
motorMotorsEnabled = false;
|
||||
|
||||
motorConsMissedSteps[0] = 0;
|
||||
|
@ -85,6 +81,24 @@ StepperControl::StepperControl() {
|
|||
axisY.label = 'Y';
|
||||
axisZ.label = 'Z';
|
||||
|
||||
// Create the encoder controller
|
||||
|
||||
encoderX = StepperControlEncoder();
|
||||
encoderY = StepperControlEncoder();
|
||||
encoderZ = StepperControlEncoder();
|
||||
|
||||
// Load settings
|
||||
|
||||
loadSettings();
|
||||
|
||||
|
||||
motorMotorsEnabled = false;
|
||||
}
|
||||
|
||||
void StepperControl::loadSettings() {
|
||||
|
||||
// Load motor settings
|
||||
|
||||
axisX.loadPinNumbers(X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, E_STEP_PIN, E_DIR_PIN, E_ENABLE_PIN);
|
||||
axisY.loadPinNumbers(Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, 0, 0, 0);
|
||||
axisZ.loadPinNumbers(Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, 0, 0, 0);
|
||||
|
@ -94,21 +108,44 @@ StepperControl::StepperControl() {
|
|||
axisSubStep[2] = COMM_REPORT_MOVE_STATUS_IDLE;
|
||||
|
||||
loadMotorSettings();
|
||||
|
||||
// Load encoder settings
|
||||
|
||||
loadEncoderSettings();
|
||||
// Create the encoder controller
|
||||
|
||||
encoderX = StepperControlEncoder();
|
||||
encoderY = StepperControlEncoder();
|
||||
encoderZ = StepperControlEncoder();
|
||||
encoderX.loadPinNumbers(X_ENCDR_A, X_ENCDR_B, X_ENCDR_A_Q, X_ENCDR_B_Q);
|
||||
encoderY.loadPinNumbers(Y_ENCDR_A, Y_ENCDR_B, Y_ENCDR_A_Q, Y_ENCDR_B_Q);
|
||||
encoderZ.loadPinNumbers(Z_ENCDR_A, Z_ENCDR_B, Z_ENCDR_A_Q, Z_ENCDR_B_Q);
|
||||
|
||||
encoderX.loadPinNumbers(X_ENCDR_A, X_ENCDR_B);
|
||||
encoderY.loadPinNumbers(Y_ENCDR_A, Y_ENCDR_B);
|
||||
encoderZ.loadPinNumbers(Z_ENCDR_A, Z_ENCDR_B);
|
||||
encoderX.loadSettings( motorConsEncoderType[0], motorConsEncoderScaling[0]);
|
||||
encoderY.loadSettings( motorConsEncoderType[1], motorConsEncoderScaling[1]);
|
||||
encoderZ.loadSettings( motorConsEncoderType[2], motorConsEncoderScaling[2]);
|
||||
|
||||
motorMotorsEnabled = false;
|
||||
}
|
||||
|
||||
void StepperControl::test() {
|
||||
|
||||
Serial.print("R99");
|
||||
Serial.print(" mot x = ");
|
||||
Serial.print(axisX.currentPosition());
|
||||
Serial.print(" enc x = ");
|
||||
Serial.print(encoderX.currentPosition());
|
||||
Serial.print("\r\n");
|
||||
|
||||
Serial.print("R99");
|
||||
Serial.print(" mot y = ");
|
||||
Serial.print(axisY.currentPosition());
|
||||
Serial.print(" enc y = ");
|
||||
Serial.print(encoderY.currentPosition());
|
||||
Serial.print("\r\n");
|
||||
|
||||
Serial.print("R99");
|
||||
Serial.print(" mot z = ");
|
||||
Serial.print(axisZ.currentPosition());
|
||||
Serial.print(" enc z = ");
|
||||
Serial.print(encoderZ.currentPosition());
|
||||
Serial.print("\r\n");
|
||||
|
||||
// read changes in encoder
|
||||
//encoderX.readEncoder();
|
||||
//encoderY.readEncoder();
|
||||
|
@ -253,9 +290,9 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
//encoderY.currentPosition();
|
||||
//encoderZ.currentPosition();
|
||||
|
||||
//axisX.checkTiming();
|
||||
//axisY.checkTiming();
|
||||
//axisZ.checkTiming();
|
||||
//axisX.checkTiming();
|
||||
//axisY.checkTiming();
|
||||
//axisZ.checkTiming();
|
||||
|
||||
//checkAxisVsEncoder(&axisX, &encoderX, &motorConsMissedSteps[0], &motorLastPosition[0], &motorConsMissedStepsDecay[0], &motorConsEncoderEnabled[0]);
|
||||
//checkAxisVsEncoder(&axisY, &encoderY, &motorConsMissedSteps[1], &motorLastPosition[1], &motorConsMissedStepsDecay[1], &motorConsEncoderEnabled[1]);
|
||||
|
@ -353,12 +390,15 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
|
||||
// Check if there is an emergency stop command
|
||||
if (Serial.available() > 0) {
|
||||
Serial.print("R99 emergency stop\r\n");
|
||||
incomingByte = Serial.read();
|
||||
incomingByte = Serial.read();
|
||||
if (incomingByte == 69 || incomingByte == 101) {
|
||||
Serial.print("R99 emergency stop\r\n");
|
||||
axisX.deactivateAxis();
|
||||
axisY.deactivateAxis();
|
||||
axisZ.deactivateAxis();
|
||||
error = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (error == 1) {
|
||||
Serial.print("R99 error\r\n");
|
||||
|
@ -434,7 +474,7 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
|
|||
CurrentState::getInstance()->setY(currentPoint[1]);
|
||||
CurrentState::getInstance()->setZ(currentPoint[2]);
|
||||
|
||||
storeEndStops();
|
||||
storeEndStops();
|
||||
reportEndStops();
|
||||
reportPosition();
|
||||
|
||||
|
@ -480,8 +520,8 @@ int StepperControl::calibrateAxis(int axis) {
|
|||
int parEndInv;
|
||||
int parNbrStp;
|
||||
|
||||
float * missedSteps;
|
||||
int * missedStepsMax;
|
||||
float * missedSteps;
|
||||
int * missedStepsMax;
|
||||
long * lastPosition;
|
||||
float * encoderStepDecay;
|
||||
bool * encoderEnabled;
|
||||
|
@ -730,23 +770,6 @@ int StepperControl::calibrateAxis(int axis) {
|
|||
//Serial.print("\r\n");
|
||||
CurrentState::getInstance()->printQAndNewLine();
|
||||
}
|
||||
/*
|
||||
if (stepsCount % (speedMin[axis] / 6) == 0)
|
||||
{
|
||||
Serial.print("R99");
|
||||
Serial.print(" step count ");
|
||||
Serial.print(stepsCount);
|
||||
Serial.print(" missed steps ");
|
||||
Serial.print(*missedSteps);
|
||||
Serial.print(" max steps ");
|
||||
Serial.print(*missedStepsMax);
|
||||
Serial.print(" cur pos mtr ");
|
||||
Serial.print(calibAxis->currentPosition());
|
||||
Serial.print(" cur pos enc ");
|
||||
Serial.print(calibEncoder->currentPosition());
|
||||
Serial.print("\r\n");
|
||||
}
|
||||
*/
|
||||
|
||||
calibAxis->resetMotorStep();
|
||||
delayMicroseconds(100000 / speedMin[axis] /2);
|
||||
|
@ -785,16 +808,16 @@ int StepperControl::calibrateAxis(int axis) {
|
|||
Serial.print("\r\n");
|
||||
}
|
||||
|
||||
*axisStatus = COMM_REPORT_MOVE_STATUS_STOP_MOTOR;
|
||||
reportStatus(&axisX, axisSubStep[0]);
|
||||
*axisStatus = COMM_REPORT_MOVE_STATUS_STOP_MOTOR;
|
||||
reportStatus(&axisX, axisSubStep[0]);
|
||||
|
||||
calibAxis->disableMotor();
|
||||
|
||||
storeEndStops();
|
||||
storeEndStops();
|
||||
reportEndStops();
|
||||
|
||||
|
||||
switch (axis) {
|
||||
switch (axis) {
|
||||
case 0:
|
||||
CurrentState::getInstance()->setX(stepsCount);
|
||||
break;
|
||||
|
@ -809,8 +832,8 @@ int StepperControl::calibrateAxis(int axis) {
|
|||
reportPosition();
|
||||
|
||||
|
||||
*axisStatus = COMM_REPORT_MOVE_STATUS_IDLE;
|
||||
reportStatus(&axisX, axisSubStep[0]);
|
||||
*axisStatus = COMM_REPORT_MOVE_STATUS_IDLE;
|
||||
reportStatus(&axisX, axisSubStep[0]);
|
||||
|
||||
reportCalib(&axisX, COMM_REPORT_CALIBRATE_STATUS_IDLE);
|
||||
|
||||
|
@ -825,9 +848,9 @@ void StepperControl::handleMovementInterrupt(void){
|
|||
encoderY.readEncoder();
|
||||
encoderZ.readEncoder();
|
||||
|
||||
axisX.checkTiming();
|
||||
axisY.checkTiming();
|
||||
axisZ.checkTiming();
|
||||
axisX.checkTiming();
|
||||
axisY.checkTiming();
|
||||
axisZ.checkTiming();
|
||||
|
||||
checkAxisVsEncoder(&axisX, &encoderX, &motorConsMissedSteps[0], &motorLastPosition[0], &motorConsMissedStepsDecay[0], &motorConsEncoderEnabled[0]);
|
||||
checkAxisVsEncoder(&axisY, &encoderY, &motorConsMissedSteps[1], &motorLastPosition[1], &motorConsMissedStepsDecay[1], &motorConsEncoderEnabled[1]);
|
||||
|
@ -912,19 +935,19 @@ void StepperControl::loadMotorSettings() {
|
|||
speedMax[1] = ParameterList::getInstance()->getValue(MOVEMENT_MAX_SPD_Y);
|
||||
speedMax[2] = ParameterList::getInstance()->getValue(MOVEMENT_MAX_SPD_Z);
|
||||
|
||||
speedMin[0] = ParameterList::getInstance()->getValue(MOVEMENT_MIN_SPD_X);
|
||||
speedMin[0] = ParameterList::getInstance()->getValue(MOVEMENT_MIN_SPD_X);
|
||||
speedMin[1] = ParameterList::getInstance()->getValue(MOVEMENT_MIN_SPD_Y);
|
||||
speedMin[2] = ParameterList::getInstance()->getValue(MOVEMENT_MIN_SPD_Z);
|
||||
|
||||
stepsAcc[0] = ParameterList::getInstance()->getValue(MOVEMENT_STEPS_ACC_DEC_X);
|
||||
stepsAcc[0] = ParameterList::getInstance()->getValue(MOVEMENT_STEPS_ACC_DEC_X);
|
||||
stepsAcc[1] = ParameterList::getInstance()->getValue(MOVEMENT_STEPS_ACC_DEC_Y);
|
||||
stepsAcc[2] = ParameterList::getInstance()->getValue(MOVEMENT_STEPS_ACC_DEC_Z);
|
||||
|
||||
motorInv[0] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_MOTOR_X);
|
||||
motorInv[0] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_MOTOR_X);
|
||||
motorInv[1] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_MOTOR_Y);
|
||||
motorInv[2] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_MOTOR_Z);
|
||||
|
||||
endStInv[0] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_ENDPOINTS_X);
|
||||
endStInv[0] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_ENDPOINTS_X);
|
||||
endStInv[1] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_ENDPOINTS_Y);
|
||||
endStInv[2] = ParameterList::getInstance()->getValue(MOVEMENT_INVERT_ENDPOINTS_Z);
|
||||
|
||||
|
@ -961,22 +984,30 @@ void StepperControl::loadEncoderSettings() {
|
|||
|
||||
// Load encoder settings
|
||||
|
||||
motorConsMissedStepsMax[0] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_MAX_X);
|
||||
motorConsMissedStepsMax[1] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_MAX_Y);
|
||||
motorConsMissedStepsMax[2] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_MAX_Z);
|
||||
motorConsMissedStepsMax[0] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_MAX_X);
|
||||
motorConsMissedStepsMax[1] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_MAX_Y);
|
||||
motorConsMissedStepsMax[2] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_MAX_Z);
|
||||
|
||||
motorConsMissedStepsDecay[0] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_DECAY_X);
|
||||
motorConsMissedStepsDecay[1] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_DECAY_Y);
|
||||
motorConsMissedStepsDecay[2] = ParameterList::getInstance()->getValue(ENCODER_MISSED_STEPS_DECAY_Z);
|
||||
|
||||
motorConsMissedStepsDecay[0] = motorConsMissedStepsDecay[0] / 100;
|
||||
motorConsMissedStepsDecay[1] = motorConsMissedStepsDecay[1] / 100;
|
||||
motorConsMissedStepsDecay[2] = motorConsMissedStepsDecay[2] / 100;
|
||||
motorConsMissedStepsDecay[0] = motorConsMissedStepsDecay[0] / 100;
|
||||
motorConsMissedStepsDecay[1] = motorConsMissedStepsDecay[1] / 100;
|
||||
motorConsMissedStepsDecay[2] = motorConsMissedStepsDecay[2] / 100;
|
||||
|
||||
motorConsMissedStepsDecay[0] = min(max(motorConsMissedStepsDecay[0],0.01),99);
|
||||
motorConsMissedStepsDecay[1] = min(max(motorConsMissedStepsDecay[1],0.01),99);
|
||||
motorConsMissedStepsDecay[2] = min(max(motorConsMissedStepsDecay[2],0.01),99);
|
||||
|
||||
motorConsEncoderType[0] = ParameterList::getInstance()->getValue(ENCODER_TYPE_X);
|
||||
motorConsEncoderType[1] = ParameterList::getInstance()->getValue(ENCODER_TYPE_Y);
|
||||
motorConsEncoderType[2] = ParameterList::getInstance()->getValue(ENCODER_TYPE_Z);
|
||||
|
||||
motorConsEncoderScaling[0] = ParameterList::getInstance()->getValue(ENCODER_SCALING_X);
|
||||
motorConsEncoderScaling[1] = ParameterList::getInstance()->getValue(ENCODER_SCALING_Y);
|
||||
motorConsEncoderScaling[2] = ParameterList::getInstance()->getValue(ENCODER_SCALING_Z);
|
||||
|
||||
if (ParameterList::getInstance()->getValue(ENCODER_ENABLED_X) == 1) {
|
||||
motorConsEncoderEnabled[0] = true;
|
||||
} else {
|
||||
|
@ -994,6 +1025,7 @@ void StepperControl::loadEncoderSettings() {
|
|||
} else {
|
||||
motorConsEncoderEnabled[2] = false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
unsigned long StepperControl::getMaxLength(unsigned long lengths[3]) {
|
||||
|
@ -1009,7 +1041,7 @@ unsigned long StepperControl::getMaxLength(unsigned long lengths[3]) {
|
|||
void StepperControl::enableMotors() {
|
||||
motorMotorsEnabled = true;
|
||||
|
||||
axisX.enableMotor();
|
||||
axisX.enableMotor();
|
||||
axisY.enableMotor();
|
||||
axisZ.enableMotor();
|
||||
delay(100);
|
||||
|
@ -1018,7 +1050,7 @@ void StepperControl::enableMotors() {
|
|||
void StepperControl::disableMotors() {
|
||||
motorMotorsEnabled = false;
|
||||
|
||||
axisX.disableMotor();
|
||||
axisX.disableMotor();
|
||||
axisY.disableMotor();
|
||||
//axisZ.disableMotor();
|
||||
delay(100);
|
||||
|
@ -1039,6 +1071,28 @@ bool StepperControl::endStopsReached() {
|
|||
|
||||
}
|
||||
|
||||
void StepperControl::storePosition(){
|
||||
|
||||
if (motorConsEncoderEnabled[0]) {
|
||||
CurrentState::getInstance()->setX(encoderX.currentPosition());
|
||||
} else {
|
||||
CurrentState::getInstance()->setX(axisX.currentPosition());
|
||||
}
|
||||
|
||||
if (motorConsEncoderEnabled[1]) {
|
||||
CurrentState::getInstance()->setY(encoderY.currentPosition());
|
||||
} else {
|
||||
CurrentState::getInstance()->setY(axisY.currentPosition());
|
||||
}
|
||||
|
||||
if (motorConsEncoderEnabled[2]) {
|
||||
CurrentState::getInstance()->setZ(encoderZ.currentPosition());
|
||||
} else {
|
||||
CurrentState::getInstance()->setZ(axisZ.currentPosition());
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void StepperControl::reportEndStops() {
|
||||
CurrentState::getInstance()->printEndStops();
|
||||
}
|
||||
|
@ -1050,3 +1104,18 @@ void StepperControl::reportPosition(){
|
|||
void StepperControl::storeEndStops() {
|
||||
CurrentState::getInstance()->storeEndStops();
|
||||
}
|
||||
|
||||
void StepperControl::setPositionX(long pos) {
|
||||
axisX.setCurrentPosition(pos);
|
||||
encoderX.setPosition(pos);
|
||||
}
|
||||
|
||||
void StepperControl::setPositionY(long pos) {
|
||||
axisY.setCurrentPosition(pos);
|
||||
encoderY.setPosition(pos);
|
||||
}
|
||||
|
||||
void StepperControl::setPositionZ(long pos) {
|
||||
axisZ.setCurrentPosition(pos);
|
||||
encoderZ.setPosition(pos);
|
||||
}
|
||||
|
|
|
@ -41,6 +41,13 @@ public:
|
|||
void disableMotors();
|
||||
bool motorsEnabled();
|
||||
|
||||
void storePosition();
|
||||
void loadSettings();
|
||||
|
||||
void setPositionX(long pos);
|
||||
void setPositionY(long pos);
|
||||
void setPositionZ(long pos);
|
||||
|
||||
void test();
|
||||
void test2();
|
||||
|
||||
|
@ -89,6 +96,8 @@ private:
|
|||
int motorConsMissedStepsMax[3];
|
||||
float motorConsMissedStepsDecay[3];
|
||||
bool motorConsEncoderEnabled[3];
|
||||
int motorConsEncoderType[3];
|
||||
int motorConsEncoderScaling[3];
|
||||
|
||||
bool motorMotorsEnabled;
|
||||
};
|
||||
|
|
|
@ -3,13 +3,26 @@
|
|||
StepperControlEncoder::StepperControlEncoder() {
|
||||
//lastCalcLog = 0;
|
||||
|
||||
pinChannelA = 0;
|
||||
pinChannelB = 0;
|
||||
pinChannelA = 0;
|
||||
pinChannelB = 0;
|
||||
|
||||
position = 0;
|
||||
position = 0;
|
||||
encoderType = 0; // default type
|
||||
scalingFactor = 100;
|
||||
|
||||
curValChannelA = false;
|
||||
curValChannelA = false;
|
||||
prvValChannelA = false;
|
||||
prvValChannelA = false;
|
||||
|
||||
readChannelA = false;
|
||||
readChannelAQ = false;
|
||||
readChannelB = false;
|
||||
readChannelBQ = false;
|
||||
}
|
||||
|
||||
void StepperControlEncoder::test() {
|
||||
/*
|
||||
Serial.print("R88 ");
|
||||
Serial.print("position ");
|
||||
Serial.print(position);
|
||||
|
@ -22,22 +35,37 @@ void StepperControlEncoder::test() {
|
|||
Serial.print(" -> ");
|
||||
Serial.print(curValChannelB);
|
||||
Serial.print("\r\n");
|
||||
*/
|
||||
}
|
||||
|
||||
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB) {
|
||||
pinChannelA = channelA;
|
||||
pinChannelB = channelB;
|
||||
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ) {
|
||||
pinChannelA = channelA;
|
||||
pinChannelB = channelB;
|
||||
pinChannelAQ = channelAQ;
|
||||
pinChannelBQ = channelBQ;
|
||||
|
||||
readChannels();
|
||||
shiftChannels();
|
||||
}
|
||||
|
||||
void StepperControlEncoder::loadSettings(int encType, int scaling) {
|
||||
encoderType = encType;
|
||||
scalingFactor = scaling;
|
||||
}
|
||||
|
||||
void StepperControlEncoder::setPosition(long newPosition) {
|
||||
position = newPosition;
|
||||
}
|
||||
|
||||
long StepperControlEncoder::currentPosition() {
|
||||
return position;
|
||||
|
||||
// Apply scaling to the output of the encoder, except when scaling is zero or lower
|
||||
|
||||
if (scalingFactor == 100 || scalingFactor <= 0) {
|
||||
return position;
|
||||
} else {
|
||||
return position * scalingFactor / 100;
|
||||
}
|
||||
}
|
||||
|
||||
/* Check the encoder channels for movement accoridng to thisspecification
|
||||
|
@ -78,18 +106,46 @@ void StepperControlEncoder::readEncoder() {
|
|||
|
||||
position += delta;
|
||||
|
||||
//if (delta != 0) {
|
||||
// test();
|
||||
//}
|
||||
|
||||
}
|
||||
|
||||
void StepperControlEncoder::readChannels() {
|
||||
curValChannelA = digitalRead(pinChannelA);
|
||||
curValChannelB = digitalRead(pinChannelB);
|
||||
|
||||
// read the new values from the coder
|
||||
|
||||
readChannelA = digitalRead(pinChannelA);
|
||||
readChannelAQ = digitalRead(pinChannelAQ);
|
||||
readChannelB = digitalRead(pinChannelB);
|
||||
readChannelBQ = digitalRead(pinChannelBQ);
|
||||
|
||||
if (encoderType == 1) {
|
||||
|
||||
// differential encoder
|
||||
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ)) {
|
||||
curValChannelA = readChannelA;
|
||||
curValChannelB = readChannelB;
|
||||
}
|
||||
}
|
||||
else {
|
||||
|
||||
// encoderType <= 0
|
||||
// non-differential incremental encoder
|
||||
curValChannelA = readChannelA;
|
||||
curValChannelB = readChannelB;
|
||||
}
|
||||
|
||||
|
||||
//curValChannelA = readChannelA;
|
||||
//curValChannelB = readChannelB;
|
||||
|
||||
// curValChannelA = digitalRead(pinChannelA);
|
||||
// curValChannelB = digitalRead(pinChannelB);
|
||||
|
||||
}
|
||||
|
||||
void StepperControlEncoder::shiftChannels() {
|
||||
|
||||
// Save the current enoder status to later on compare with new values
|
||||
|
||||
prvValChannelA = curValChannelA;
|
||||
prvValChannelB = curValChannelB;
|
||||
}
|
||||
|
|
|
@ -22,7 +22,8 @@ public:
|
|||
|
||||
StepperControlEncoder();
|
||||
|
||||
void loadPinNumbers(int channelA, int channelB);
|
||||
void loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ);
|
||||
void loadSettings(int encType, int scaling);
|
||||
|
||||
void setPosition(long newPosition);
|
||||
long currentPosition();
|
||||
|
@ -36,7 +37,9 @@ private:
|
|||
|
||||
// pin settings
|
||||
int pinChannelA;
|
||||
int pinChannelAQ;
|
||||
int pinChannelB;
|
||||
int pinChannelBQ;
|
||||
|
||||
// channels
|
||||
bool prvValChannelA;
|
||||
|
@ -44,8 +47,15 @@ private:
|
|||
bool curValChannelA;
|
||||
bool curValChannelB;
|
||||
|
||||
bool readChannelA;
|
||||
bool readChannelAQ;
|
||||
bool readChannelB;
|
||||
bool readChannelBQ;
|
||||
|
||||
// encoder
|
||||
long position;
|
||||
int scalingFactor;
|
||||
int encoderType;
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -3,15 +3,20 @@
|
|||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
//#include "ServoControl.h"
|
||||
#include "ServoControl.h"
|
||||
#include "PinGuard.h"
|
||||
#include "TimerOne.h"
|
||||
#include "MemoryFree.h"
|
||||
|
||||
|
||||
static char commandEndChar = 0x0A;
|
||||
static GCodeProcessor* gCodeProcessor = new GCodeProcessor();
|
||||
|
||||
unsigned long lastAction;
|
||||
unsigned long currentTime;
|
||||
unsigned long cycleCounter = 0;
|
||||
|
||||
int lastParamChangeNr = 0;
|
||||
|
||||
String commandString = "";
|
||||
char incomingChar = 0;
|
||||
|
@ -94,10 +99,6 @@ void setup() {
|
|||
|
||||
delay(100);
|
||||
|
||||
//ParameterList::getInstance()->setAllValuesToDefault();
|
||||
//ParameterList::getInstance()->writeAllValuesToEeprom();
|
||||
//ParameterList::getInstance()->readAllValuesFromEeprom();
|
||||
|
||||
// Start the motor handling
|
||||
//ServoControl::getInstance()->attach();
|
||||
|
||||
|
@ -107,9 +108,10 @@ void setup() {
|
|||
// Get the settings for the pin guard
|
||||
PinGuard::getInstance()->loadConfig();
|
||||
|
||||
// Start the interrupt used for moviing
|
||||
// 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();
|
||||
|
@ -145,16 +147,12 @@ void loop() {
|
|||
//char commandChar[currentCommand.length()];
|
||||
//currentCommand.toCharArray(commandChar, currentCommand.length());
|
||||
|
||||
char commandChar[incomingCommandPointer + 1];
|
||||
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) {
|
||||
|
||||
|
||||
|
@ -181,6 +179,22 @@ void loop() {
|
|||
|
||||
//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
|
||||
|
||||
currentTime = millis();
|
||||
if (currentTime < lastAction) {
|
||||
|
||||
|
@ -191,18 +205,38 @@ void loop() {
|
|||
|
||||
if ((currentTime - lastAction) > 5000) {
|
||||
// After an idle time, send the idle message
|
||||
Serial.print("R00");
|
||||
|
||||
Serial.print(COMM_REPORT_CMD_IDLE);
|
||||
CurrentState::getInstance()->printQAndNewLine();
|
||||
|
||||
StepperControl::getInstance()->storePosition();
|
||||
CurrentState::getInstance()->printPosition();
|
||||
|
||||
CurrentState::getInstance()->storeEndStops();
|
||||
CurrentState::getInstance()->printEndStops();
|
||||
|
||||
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();
|
||||
|
||||
//ParameterList::getInstance()->readAllValues();
|
||||
|
||||
|
||||
StepperControl::getInstance()->test();
|
||||
//StepperControl::getInstance()->test();
|
||||
|
||||
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
|
||||
// Serial.print(COMM_REPORT_NO_CONFIG);
|
||||
// }
|
||||
|
||||
cycleCounter++;
|
||||
lastAction = millis();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1 +1 @@
|
|||
|
||||
// All code in farmbot_arduino_controller.cpp
|
|
@ -0,0 +1,176 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project DefaultTargets="Build" ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<ItemGroup Label="ProjectConfigurations">
|
||||
<ProjectConfiguration Include="Debug|Win32">
|
||||
<Configuration>Debug</Configuration>
|
||||
<Platform>Win32</Platform>
|
||||
</ProjectConfiguration>
|
||||
<ProjectConfiguration Include="Release|Win32">
|
||||
<Configuration>Release</Configuration>
|
||||
<Platform>Win32</Platform>
|
||||
</ProjectConfiguration>
|
||||
</ItemGroup>
|
||||
<PropertyGroup Label="Globals">
|
||||
<ProjectGuid>{C5F80730-F44F-4478-BDAE-6634EFC2CA88}</ProjectGuid>
|
||||
<RootNamespace>src</RootNamespace>
|
||||
<ProjectName>src</ProjectName>
|
||||
</PropertyGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.Default.props" />
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'" Label="Configuration">
|
||||
<ConfigurationType>Application</ConfigurationType>
|
||||
<UseDebugLibraries>true</UseDebugLibraries>
|
||||
<PlatformToolset>
|
||||
</PlatformToolset>
|
||||
<CharacterSet>MultiByte</CharacterSet>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'" Label="Configuration">
|
||||
<ConfigurationType>Application</ConfigurationType>
|
||||
<UseDebugLibraries>false</UseDebugLibraries>
|
||||
<PlatformToolset>
|
||||
</PlatformToolset>
|
||||
<WholeProgramOptimization>true</WholeProgramOptimization>
|
||||
<CharacterSet>MultiByte</CharacterSet>
|
||||
</PropertyGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.props" />
|
||||
<ImportGroup Label="ExtensionSettings">
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
|
||||
</ImportGroup>
|
||||
<PropertyGroup Label="UserMacros" />
|
||||
<PropertyGroup />
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
|
||||
<ClCompile>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<Optimization>Disabled</Optimization>
|
||||
<SDLCheck>true</SDLCheck>
|
||||
<AdditionalIncludeDirectories>$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\hardware\arduino\avr\libraries\EEPROM\src;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\libraries\Servo\src;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\libraries;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\hardware\arduino\avr\libraries;$(ProjectDir)..\..\..\..\Documents\Arduino\libraries;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\hardware\arduino\avr\cores\arduino;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\hardware\arduino\avr\variants\mega;$(ProjectDir)..\src;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\avr\;$(ProjectDir)..\..\..\..\..\..\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.8.1\include;%(AdditionalIncludeDirectories)</AdditionalIncludeDirectories>
|
||||
<ForcedIncludeFiles>$(ProjectDir)__vm\.src.vsarduino.h;%(ForcedIncludeFiles)</ForcedIncludeFiles>
|
||||
<IgnoreStandardIncludePath>false</IgnoreStandardIncludePath>
|
||||
<PreprocessorDefinitions>__AVR_ATmega2560__;_VMDEBUG=1;F_CPU=16000000L;ARDUINO=10802;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;%(PreprocessorDefinitions)</PreprocessorDefinitions>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
|
||||
<ClCompile>
|
||||
<WarningLevel>Level3</WarningLevel>
|
||||
<Optimization>MaxSpeed</Optimization>
|
||||
<FunctionLevelLinking>true</FunctionLevelLinking>
|
||||
<IntrinsicFunctions>true</IntrinsicFunctions>
|
||||
<SDLCheck>true</SDLCheck>
|
||||
</ClCompile>
|
||||
<Link>
|
||||
<GenerateDebugInformation>true</GenerateDebugInformation>
|
||||
<EnableCOMDATFolding>true</EnableCOMDATFolding>
|
||||
<OptimizeReferences>true</OptimizeReferences>
|
||||
</Link>
|
||||
</ItemDefinitionGroup>
|
||||
<ItemGroup>
|
||||
<ProjectCapability Include="VisualMicro" />
|
||||
</ItemGroup>
|
||||
<PropertyGroup>
|
||||
<DebuggerFlavor>VisualMicroDebugger</DebuggerFlavor>
|
||||
</PropertyGroup>
|
||||
<ItemGroup>
|
||||
<None Include="src.ino">
|
||||
<FileType>CppCode</FileType>
|
||||
</None>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClCompile Include="Command.cpp" />
|
||||
<ClCompile Include="CurrentState.cpp" />
|
||||
<ClCompile Include="F11Handler.cpp" />
|
||||
<ClCompile Include="F12Handler.cpp" />
|
||||
<ClCompile Include="F13Handler.cpp" />
|
||||
<ClCompile Include="F14Handler.cpp" />
|
||||
<ClCompile Include="F15Handler.cpp" />
|
||||
<ClCompile Include="F16Handler.cpp" />
|
||||
<ClCompile Include="F20Handler.cpp" />
|
||||
<ClCompile Include="F21Handler.cpp" />
|
||||
<ClCompile Include="F22Handler.cpp" />
|
||||
<ClCompile Include="F31Handler.cpp" />
|
||||
<ClCompile Include="F32Handler.cpp" />
|
||||
<ClCompile Include="F41Handler.cpp" />
|
||||
<ClCompile Include="F42Handler.cpp" />
|
||||
<ClCompile Include="F43Handler.cpp" />
|
||||
<ClCompile Include="F44Handler.cpp" />
|
||||
<ClCompile Include="F61Handler.cpp" />
|
||||
<ClCompile Include="F81Handler.cpp" />
|
||||
<ClCompile Include="F82Handler.cpp" />
|
||||
<ClCompile Include="F83Handler.cpp" />
|
||||
<ClCompile Include="F84Handler.cpp" />
|
||||
<ClCompile Include="farmbot_arduino_controller.cpp" />
|
||||
<ClCompile Include="G00Handler.cpp" />
|
||||
<ClCompile Include="G28Handler.cpp" />
|
||||
<ClCompile Include="GCodeHandler.cpp" />
|
||||
<ClCompile Include="GCodeProcessor.cpp" />
|
||||
<ClCompile Include="MemoryFree.cpp" />
|
||||
<ClCompile Include="ParameterList.cpp" />
|
||||
<ClCompile Include="PinControl.cpp" />
|
||||
<ClCompile Include="PinGuard.cpp" />
|
||||
<ClCompile Include="PinGuardPin.cpp" />
|
||||
<ClCompile Include="ServoControl.cpp" />
|
||||
<ClCompile Include="StatusList.cpp" />
|
||||
<ClCompile Include="StepperControl.cpp" />
|
||||
<ClCompile Include="StepperControlAxis.cpp" />
|
||||
<ClCompile Include="StepperControlEncoder.cpp" />
|
||||
<ClCompile Include="TimerOne.cpp" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClInclude Include="Command.h" />
|
||||
<ClInclude Include="Config.h" />
|
||||
<ClInclude Include="CurrentState.h" />
|
||||
<ClInclude Include="F11Handler.h" />
|
||||
<ClInclude Include="F12Handler.h" />
|
||||
<ClInclude Include="F13Handler.h" />
|
||||
<ClInclude Include="F14Handler.h" />
|
||||
<ClInclude Include="F15Handler.h" />
|
||||
<ClInclude Include="F16Handler.h" />
|
||||
<ClInclude Include="F20Handler.h" />
|
||||
<ClInclude Include="F21Handler.h" />
|
||||
<ClInclude Include="F22Handler.h" />
|
||||
<ClInclude Include="F31Handler.h" />
|
||||
<ClInclude Include="F32Handler.h" />
|
||||
<ClInclude Include="F41Handler.h" />
|
||||
<ClInclude Include="F42Handler.h" />
|
||||
<ClInclude Include="F43Handler.h" />
|
||||
<ClInclude Include="F44Handler.h" />
|
||||
<ClInclude Include="F61Handler.h" />
|
||||
<ClInclude Include="F81Handler.h" />
|
||||
<ClInclude Include="F82Handler.h" />
|
||||
<ClInclude Include="F83Handler.h" />
|
||||
<ClInclude Include="F84Handler.h" />
|
||||
<ClInclude Include="farmbot_arduino_controller.h" />
|
||||
<ClInclude Include="G00Handler.h" />
|
||||
<ClInclude Include="G28Handler.h" />
|
||||
<ClInclude Include="GCodeHandler.h" />
|
||||
<ClInclude Include="GCodeProcessor.h" />
|
||||
<ClInclude Include="known_16bit_timers.h" />
|
||||
<ClInclude Include="MemoryFree.h" />
|
||||
<ClInclude Include="ParameterList.h" />
|
||||
<ClInclude Include="PinControl.h" />
|
||||
<ClInclude Include="PinGuard.h" />
|
||||
<ClInclude Include="PinGuardPin.h" />
|
||||
<ClInclude Include="pins.h" />
|
||||
<ClInclude Include="ServoControl.h" />
|
||||
<ClInclude Include="StatusList.h" />
|
||||
<ClInclude Include="StepperControl.h" />
|
||||
<ClInclude Include="StepperControlAxis.h" />
|
||||
<ClInclude Include="StepperControlEncoder.h" />
|
||||
<ClInclude Include="TimerOne.h" />
|
||||
<ClInclude Include="__vm\.src.vsarduino.h" />
|
||||
</ItemGroup>
|
||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
|
||||
<ImportGroup Label="ExtensionTargets">
|
||||
</ImportGroup>
|
||||
<ProjectExtensions>
|
||||
<VisualStudio>
|
||||
<UserProperties vm.programmer_name="avrisp" arduino.upload.port="COM3" />
|
||||
</VisualStudio>
|
||||
</ProjectExtensions>
|
||||
</Project>
|
|
@ -0,0 +1,264 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<ItemGroup>
|
||||
<Filter Include="Source Files">
|
||||
<UniqueIdentifier>{4FC737F1-C7A5-4376-A066-2A32D752A2FF}</UniqueIdentifier>
|
||||
<Extensions>cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx</Extensions>
|
||||
</Filter>
|
||||
<Filter Include="Header Files">
|
||||
<UniqueIdentifier>{93995380-89BD-4b04-88EB-625FBE52EBFB}</UniqueIdentifier>
|
||||
<Extensions>h;hh;hpp;hxx;hm;inl;inc;xsd</Extensions>
|
||||
</Filter>
|
||||
<Filter Include="Resource Files">
|
||||
<UniqueIdentifier>{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}</UniqueIdentifier>
|
||||
<Extensions>rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms</Extensions>
|
||||
</Filter>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<None Include="src.ino" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClCompile Include="GCodeProcessor.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="Command.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="CurrentState.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F11Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F12Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F13Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F14Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F15Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F16Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F20Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F21Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F22Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F31Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F32Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F41Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F42Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F43Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F44Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F61Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F81Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F82Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F83Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="F84Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="farmbot_arduino_controller.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="G00Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="G28Handler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="GCodeHandler.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="PinGuardPin.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="MemoryFree.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="ParameterList.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="PinControl.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="PinGuard.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="ServoControl.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="StepperControlAxis.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="StepperControlEncoder.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="TimerOne.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="StatusList.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="StepperControl.cpp">
|
||||
<Filter>Source Files</Filter>
|
||||
</ClCompile>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClInclude Include="GCodeProcessor.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="known_16bit_timers.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="Command.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="Config.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="CurrentState.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F11Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F12Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F13Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F14Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F15Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F16Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F20Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F21Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F22Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F31Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F32Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F41Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F42Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F43Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F44Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F61Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F81Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F82Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F83Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="F84Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="farmbot_arduino_controller.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="G00Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="G28Handler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="GCodeHandler.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="PinGuardPin.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="pins.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="MemoryFree.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="ParameterList.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="PinControl.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="PinGuard.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="ServoControl.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="StepperControlAxis.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="StepperControlEncoder.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="TimerOne.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="StatusList.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="StepperControl.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="__vm\.src.vsarduino.h">
|
||||
<Filter>Header Files</Filter>
|
||||
</ClInclude>
|
||||
</ItemGroup>
|
||||
</Project>
|
Loading…
Reference in New Issue