Merge branch 'duet' of https://github.com/reprappro/RepRapFirmware into duet
This commit is contained in:
commit
6b5c21af23
9 changed files with 2496 additions and 2469 deletions
12
GCodes.cpp
12
GCodes.cpp
|
@ -369,6 +369,18 @@ void GCodes::QueueFileToPrint(char* fileName)
|
|||
platform->Message(HOST_MESSAGE, "GCode file not found\n");
|
||||
}
|
||||
|
||||
void GCodes::RunConfigurationGCodes()
|
||||
{
|
||||
fileToPrint = platform->GetFileStore(platform->GetSysDir(), platform->GetConfigFile(), false);
|
||||
if(fileToPrint == NULL)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Configuration file not found\n");
|
||||
return;
|
||||
}
|
||||
fileBeingPrinted = fileToPrint;
|
||||
fileToPrint = NULL;
|
||||
}
|
||||
|
||||
|
||||
// Function to handle dwell delays. Return true for
|
||||
// Dwell finished, false otherwise.
|
||||
|
|
1
GCodes.h
1
GCodes.h
|
@ -65,6 +65,7 @@ class GCodes
|
|||
void Spin();
|
||||
void Init();
|
||||
void Exit();
|
||||
void RunConfigurationGCodes();
|
||||
bool ReadMove(float* m, bool& ce);
|
||||
bool ReadHeat(float* h);
|
||||
void QueueFileToPrint(char* fileName);
|
||||
|
|
158
Platform.cpp
158
Platform.cpp
|
@ -88,86 +88,98 @@ void Platform::Init()
|
|||
sysDir = SYS_DIR;
|
||||
configFile = CONFIG_FILE;
|
||||
|
||||
if(!LoadFromStore())
|
||||
{
|
||||
// DRIVES
|
||||
|
||||
stepPins = STEP_PINS;
|
||||
directionPins = DIRECTION_PINS;
|
||||
enablePins = ENABLE_PINS;
|
||||
disableDrives = DISABLE_DRIVES;
|
||||
lowStopPins = LOW_STOP_PINS;
|
||||
highStopPins = HIGH_STOP_PINS;
|
||||
maxFeedrates = MAX_FEEDRATES;
|
||||
accelerations = ACCELERATIONS;
|
||||
driveStepsPerUnit = DRIVE_STEPS_PER_UNIT;
|
||||
instantDvs = INSTANT_DVS;
|
||||
potWipes = POT_WIPES;
|
||||
senseResistor = SENSE_RESISTOR;
|
||||
maxAtoDVoltage = MAX_A_TO_D_VOLTAGE;
|
||||
|
||||
|
||||
stepPins = STEP_PINS;
|
||||
directionPins = DIRECTION_PINS;
|
||||
enablePins = ENABLE_PINS;
|
||||
disableDrives = DISABLE_DRIVES;
|
||||
lowStopPins = LOW_STOP_PINS;
|
||||
highStopPins = HIGH_STOP_PINS;
|
||||
maxFeedrates = MAX_FEEDRATES;
|
||||
accelerations = ACCELERATIONS;
|
||||
driveStepsPerUnit = DRIVE_STEPS_PER_UNIT;
|
||||
instantDvs = INSTANT_DVS;
|
||||
potWipes = POT_WIPES;
|
||||
senseResistor = SENSE_RESISTOR;
|
||||
maxAtoDVoltage = MAX_A_TO_D_VOLTAGE;
|
||||
|
||||
// AXES
|
||||
|
||||
axisLengths = AXIS_LENGTHS;
|
||||
homeFeedrates = HOME_FEEDRATES;
|
||||
headOffsets = HEAD_OFFSETS;
|
||||
|
||||
|
||||
axisLengths = AXIS_LENGTHS;
|
||||
homeFeedrates = HOME_FEEDRATES;
|
||||
headOffsets = HEAD_OFFSETS;
|
||||
|
||||
// HEATERS - Bed is assumed to be the first
|
||||
|
||||
tempSensePins = TEMP_SENSE_PINS;
|
||||
heatOnPins = HEAT_ON_PINS;
|
||||
thermistorBetas = THERMISTOR_BETAS;
|
||||
thermistorSeriesRs = THERMISTOR_SERIES_RS;
|
||||
thermistorInfRs = THERMISTOR_25_RS;
|
||||
usePID = USE_PID;
|
||||
pidKis = PID_KIS;
|
||||
pidKds = PID_KDS;
|
||||
pidKps = PID_KPS;
|
||||
fullPidBand = FULL_PID_BAND;
|
||||
pidMin = PID_MIN;
|
||||
pidMax = PID_MAX;
|
||||
dMix = D_MIX;
|
||||
heatSampleTime = HEAT_SAMPLE_TIME;
|
||||
standbyTemperatures = STANDBY_TEMPERATURES;
|
||||
activeTemperatures = ACTIVE_TEMPERATURES;
|
||||
|
||||
webDir = WEB_DIR;
|
||||
gcodeDir = GCODE_DIR;
|
||||
tempDir = TEMP_DIR;
|
||||
}
|
||||
|
||||
|
||||
tempSensePins = TEMP_SENSE_PINS;
|
||||
heatOnPins = HEAT_ON_PINS;
|
||||
thermistorBetas = THERMISTOR_BETAS;
|
||||
thermistorSeriesRs = THERMISTOR_SERIES_RS;
|
||||
thermistorInfRs = THERMISTOR_25_RS;
|
||||
usePID = USE_PID;
|
||||
pidKis = PID_KIS;
|
||||
pidKds = PID_KDS;
|
||||
pidKps = PID_KPS;
|
||||
fullPidBand = FULL_PID_BAND;
|
||||
pidMin = PID_MIN;
|
||||
pidMax = PID_MAX;
|
||||
dMix = D_MIX;
|
||||
heatSampleTime = HEAT_SAMPLE_TIME;
|
||||
standbyTemperatures = STANDBY_TEMPERATURES;
|
||||
activeTemperatures = ACTIVE_TEMPERATURES;
|
||||
|
||||
webDir = WEB_DIR;
|
||||
gcodeDir = GCODE_DIR;
|
||||
tempDir = TEMP_DIR;
|
||||
|
||||
for(i = 0; i < DRIVES; i++)
|
||||
{
|
||||
if(stepPins[i] >= 0)
|
||||
pinMode(stepPins[i], OUTPUT);
|
||||
if(directionPins[i] >= 0)
|
||||
pinMode(directionPins[i], OUTPUT);
|
||||
if(enablePins[i] >= 0)
|
||||
{
|
||||
pinMode(enablePins[i], OUTPUT);
|
||||
digitalWrite(enablePins[i], ENABLE);
|
||||
}
|
||||
|
||||
if(stepPins[i] >= 0)
|
||||
{
|
||||
if(i > Z_AXIS)
|
||||
pinModeNonDue(stepPins[i], OUTPUT);
|
||||
else
|
||||
pinMode(stepPins[i], OUTPUT);
|
||||
}
|
||||
if(directionPins[i] >= 0)
|
||||
{
|
||||
if(i > Z_AXIS)
|
||||
pinModeNonDue(directionPins[i], OUTPUT);
|
||||
else
|
||||
pinMode(directionPins[i], OUTPUT);
|
||||
}
|
||||
if(enablePins[i] >= 0)
|
||||
{
|
||||
if(i >= Z_AXIS)
|
||||
pinModeNonDue(enablePins[i], OUTPUT);
|
||||
else
|
||||
pinMode(enablePins[i], OUTPUT);
|
||||
}
|
||||
Disable(i);
|
||||
driveEnabled[i] = false;
|
||||
}
|
||||
|
||||
|
||||
for(i = 0; i < AXES; i++)
|
||||
{
|
||||
if(lowStopPins[i] >= 0)
|
||||
{
|
||||
pinMode(lowStopPins[i], INPUT);
|
||||
digitalWrite(lowStopPins[i], HIGH); // Turn on pullup
|
||||
}
|
||||
if(highStopPins[i] >= 0)
|
||||
{
|
||||
pinMode(highStopPins[i], INPUT);
|
||||
digitalWrite(highStopPins[i], HIGH); // Turn on pullup
|
||||
}
|
||||
if(lowStopPins[i] >= 0)
|
||||
{
|
||||
pinMode(lowStopPins[i], INPUT);
|
||||
digitalWrite(lowStopPins[i], HIGH); // Turn on pullup
|
||||
}
|
||||
if(highStopPins[i] >= 0)
|
||||
{
|
||||
pinMode(highStopPins[i], INPUT);
|
||||
digitalWrite(highStopPins[i], HIGH); // Turn on pullup
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
for(i = 0; i < HEATERS; i++)
|
||||
{
|
||||
if(heatOnPins[i] >= 0)
|
||||
pinMode(heatOnPins[i], OUTPUT);
|
||||
pinModeNonDue(heatOnPins[i], OUTPUT);
|
||||
thermistorInfRs[i] = ( thermistorInfRs[i]*exp(-thermistorBetas[i]/(25.0 - ABS_ZERO)) );
|
||||
}
|
||||
|
||||
|
@ -183,12 +195,6 @@ void Platform::Diagnostics()
|
|||
Message(HOST_MESSAGE, "Platform Diagnostics:\n");
|
||||
}
|
||||
|
||||
// Load settings from local storage; return true if successful, false otherwise
|
||||
|
||||
bool Platform::LoadFromStore()
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
//===========================================================================
|
||||
//=============================Thermal Settings ============================
|
||||
|
@ -224,20 +230,20 @@ void Platform::SetHeater(int8_t heater, const float& power)
|
|||
if(heatOnPins[heater] < 0)
|
||||
return;
|
||||
|
||||
if(power <= 0.00)
|
||||
if(power <= 0.0)
|
||||
{
|
||||
analogWrite(heatOnPins[heater], 0);
|
||||
analogWriteNonDue(heatOnPins[heater], 0);
|
||||
return;
|
||||
}
|
||||
|
||||
if(power >= 1.0)
|
||||
{
|
||||
analogWrite(heatOnPins[heater], 255);
|
||||
analogWriteNonDue(heatOnPins[heater], 255);
|
||||
return;
|
||||
}
|
||||
|
||||
byte p = (byte)(255.0*power);
|
||||
analogWrite(heatOnPins[heater], p);
|
||||
analogWriteNonDue(heatOnPins[heater], p);
|
||||
}
|
||||
|
||||
|
||||
|
|
112
Platform.h
112
Platform.h
|
@ -68,11 +68,11 @@ Licence: GPL
|
|||
|
||||
// DRIVES
|
||||
|
||||
#define STEP_PINS {14, 25, 5, 68}
|
||||
#define DIRECTION_PINS {15, 26, 4, 69}
|
||||
#define STEP_PINS {14, 25, 5, X2}
|
||||
#define DIRECTION_PINS {15, 26, 4, X3}
|
||||
#define FORWARDS true // What to send to go...
|
||||
#define BACKWARDS false // ...in each direction
|
||||
#define ENABLE_PINS {29, 27, 138, 25}
|
||||
#define ENABLE_PINS {29, 27, X1, X0}
|
||||
#define ENABLE false // What to send to enable...
|
||||
#define DISABLE true // ...and disable a drive
|
||||
#define DISABLE_DRIVES {false, false, true, false} // Set true to disable a drive when it becomes idle
|
||||
|
@ -99,12 +99,12 @@ Licence: GPL
|
|||
#define X_AXIS 0 // The index of the X axis
|
||||
#define Y_AXIS 1 // The index of the Y axis
|
||||
#define Z_AXIS 2 // The index of the Z axis
|
||||
|
||||
#define E_AXIS 3 // The index of the extruder
|
||||
|
||||
// HEATERS - The bed is assumed to be the first
|
||||
|
||||
#define TEMP_SENSE_PINS {5, 4} // Analogue pin numbers
|
||||
#define HEAT_ON_PINS {53, 40}
|
||||
#define HEAT_ON_PINS {X7, X5}
|
||||
#define THERMISTOR_BETAS {3480.0, 3960.0} // Bed thermistor: RS 484-0149; EPCOS B57550G103J; Extruder thermistor: RS 198-961
|
||||
#define THERMISTOR_SERIES_RS {1000, 1000} // Ohms in series with the thermistors
|
||||
#define THERMISTOR_25_RS {10000.0, 100000.0} // Thermistor ohms at 25 C = 298.15 K
|
||||
|
@ -355,22 +355,11 @@ class Platform
|
|||
|
||||
MassStorage* GetMassStorage();
|
||||
FileStore* GetFileStore(char* directory, char* fileName, bool write);
|
||||
|
||||
// char* FileList(char* directory); // Returns a ,-separated list of all the files in the named directory (for example on an SD card).
|
||||
// int OpenFile(char* directory, char* fileName, bool write); // Open a local file (for example on an SD card).
|
||||
// void GoToEnd(int file); // Position the file at the end (so you can write on the end).
|
||||
// bool Read(int file, char& b); // Read a single byte from a file into b,
|
||||
// returned value is false for EoF, true otherwise
|
||||
// void Write(int file, char* s); // Write the string to a file.
|
||||
// void Write(int file, char b); // Write the byte b to a file.
|
||||
// unsigned long Length(int file); // File size in bytes
|
||||
char* GetWebDir(); // Where the htm etc files are
|
||||
char* GetGCodeDir(); // Where the gcodes are
|
||||
char* GetSysDir(); // Where the system files are
|
||||
char* GetTempDir(); // Where temporary files are
|
||||
char* GetConfigFile(); // Where the configuration is stored (in the system dir).
|
||||
// void Close(int file); // Close a file or device, writing any unwritten buffer contents first.
|
||||
// bool DeleteFile(char* directory, char* fileName); // Delete a file
|
||||
|
||||
void Message(char type, char* message); // Send a message. Messages may simply flash an LED, or,
|
||||
// say, display the messages on an LCD. This may also transmit the messages to the host.
|
||||
|
@ -421,10 +410,6 @@ class Platform
|
|||
|
||||
bool active;
|
||||
|
||||
// Load settings from local storage
|
||||
|
||||
bool LoadFromStore();
|
||||
|
||||
void InitialiseInterrupts();
|
||||
|
||||
char* CombineName(char* result, char* directory, char* fileName);
|
||||
|
@ -437,6 +422,7 @@ class Platform
|
|||
int8_t directionPins[DRIVES];
|
||||
int8_t enablePins[DRIVES];
|
||||
bool disableDrives[DRIVES];
|
||||
bool driveEnabled[DRIVES];
|
||||
int8_t lowStopPins[DRIVES];
|
||||
int8_t highStopPins[DRIVES];
|
||||
float maxFeedrates[DRIVES];
|
||||
|
@ -625,35 +611,6 @@ inline void Network::Spin()
|
|||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
// Serial input
|
||||
|
||||
// Byte available from (for example) USB?
|
||||
|
||||
//inline bool Platform::SerialAvailable()
|
||||
//{
|
||||
// return Serial.available() > 0;
|
||||
//}
|
||||
|
||||
// Read a serial byte into b; result is true unless no byte is available
|
||||
|
||||
//inline bool Platform::SerialRead(char& b)
|
||||
//{
|
||||
// int incomingByte = Serial.read();
|
||||
// if(incomingByte < 0)
|
||||
// return false;
|
||||
// b = (char)incomingByte;
|
||||
// return true;
|
||||
//}
|
||||
|
||||
//*****************************************************************************************************************
|
||||
|
||||
// Drive the RepRap machine - Movement
|
||||
|
@ -675,17 +632,46 @@ inline float Platform::InstantDv(int8_t drive)
|
|||
|
||||
inline void Platform::SetDirection(byte drive, bool direction)
|
||||
{
|
||||
if(directionPins[drive] >= 0)
|
||||
digitalWrite(directionPins[drive], direction);
|
||||
if(directionPins[drive] < 0)
|
||||
return;
|
||||
if(drive == AXES)
|
||||
digitalWriteNonDue(directionPins[drive], direction);
|
||||
else
|
||||
digitalWrite(directionPins[drive], direction);
|
||||
}
|
||||
|
||||
inline void Platform::Disable(byte drive)
|
||||
{
|
||||
if(enablePins[drive] < 0)
|
||||
return;
|
||||
if(drive >= Z_AXIS)
|
||||
digitalWriteNonDue(enablePins[drive], DISABLE);
|
||||
else
|
||||
digitalWrite(enablePins[drive], DISABLE);
|
||||
driveEnabled[drive] = false;
|
||||
}
|
||||
|
||||
inline void Platform::Step(byte drive)
|
||||
{
|
||||
if(stepPins[drive] >= 0)
|
||||
{
|
||||
digitalWrite(stepPins[drive], 0);
|
||||
digitalWrite(stepPins[drive], 1);
|
||||
}
|
||||
if(stepPins[drive] < 0)
|
||||
return;
|
||||
if(!driveEnabled[drive] && enablePins[drive] >= 0)
|
||||
{
|
||||
if(drive >= Z_AXIS)
|
||||
digitalWriteNonDue(enablePins[drive], ENABLE);
|
||||
else
|
||||
digitalWrite(enablePins[drive], ENABLE);
|
||||
driveEnabled[drive] = true;
|
||||
}
|
||||
if(drive == AXES)
|
||||
{
|
||||
digitalWriteNonDue(stepPins[drive], 0);
|
||||
digitalWriteNonDue(stepPins[drive], 1);
|
||||
} else
|
||||
{
|
||||
digitalWrite(stepPins[drive], 0);
|
||||
digitalWrite(stepPins[drive], 1);
|
||||
}
|
||||
}
|
||||
|
||||
// current is in mA
|
||||
|
@ -694,12 +680,24 @@ inline void Platform::SetMotorCurrent(byte drive, float current)
|
|||
{
|
||||
if(potWipes[drive] < 0)
|
||||
return;
|
||||
unsigned short pot = (unsigned short)(0.256*current*8.0*senseResistor/maxAtoDVoltage);
|
||||
if(drive<2)
|
||||
{
|
||||
mcp.setNonVolatileWiper(potWipes[drive], 0x55);
|
||||
mcp.setVolatileWiper(potWipes[drive], 0x55);
|
||||
} else
|
||||
{
|
||||
mcp.setNonVolatileWiper(potWipes[drive], 0xAA);
|
||||
mcp.setVolatileWiper(potWipes[drive], 0xAA);
|
||||
}
|
||||
/* unsigned short pot = (unsigned short)(0.256*current*8.0*senseResistor/maxAtoDVoltage);
|
||||
//if(drive < Z_AXIS)
|
||||
// pot = 256 - pot;
|
||||
Message(HOST_MESSAGE, "Set pot to: ");
|
||||
sprintf(scratchString, "%d", pot);
|
||||
Message(HOST_MESSAGE, scratchString);
|
||||
Message(HOST_MESSAGE, "\n");
|
||||
mcp.setNonVolatileWiper(potWipes[drive], pot);
|
||||
mcp.setVolatileWiper(potWipes[drive], pot);*/
|
||||
}
|
||||
|
||||
inline float Platform::HomeFeedRate(int8_t drive)
|
||||
|
|
Binary file not shown.
File diff suppressed because it is too large
Load diff
|
@ -175,8 +175,9 @@ void RepRap::Init()
|
|||
webserver->Init();
|
||||
move->Init();
|
||||
heat->Init();
|
||||
platform->Message(HOST_MESSAGE, "RepRapPro RepRap Firmware (Re)Started\n");
|
||||
active = true;
|
||||
gCodes->RunConfigurationGCodes();
|
||||
platform->Message(HOST_MESSAGE, "RepRapPro RepRap Firmware (Re)Started\n");
|
||||
}
|
||||
|
||||
void RepRap::Exit()
|
||||
|
|
11
SD-image/sys/config.g
Normal file
11
SD-image/sys/config.g
Normal file
|
@ -0,0 +1,11 @@
|
|||
; RepRapPro Ormerod
|
||||
; Standard configuration G Codes
|
||||
M111 S1; Debug on
|
||||
G21 ; mm
|
||||
G90 ; Absolute positioning
|
||||
M83 ; Extrusion relative
|
||||
M107; Fan off
|
||||
M906 X250 Y250 Z250 E250 ; Motor currents (mA)
|
||||
T0 ; Extruder 0
|
||||
|
||||
|
Reference in a new issue