Version 0.78p
Fixed bug that caused the cooling fan PWM frequency to be 165kHz. It is now 25kHz. Fan RPM is now included in the web interface status response (thanks zpl). Many more error messages are now reported to the web interface as well as the USB interface. Interrupt-driven network timer task to better cope with slow SD card writes (thanks zpl) Module SamNonDuePin is now used for all digital and PWM pin I/O.
This commit is contained in:
parent
3a815ccb7c
commit
b30e6ad4e1
20 changed files with 544 additions and 626 deletions
|
@ -1,4 +1,4 @@
|
|||
Additional functionality in 0.78g-dc42 release compared to RRP 0.78:
|
||||
Additional functionality in 0.78p-dc42 release compared to RRP 0.78a:
|
||||
|
||||
* The Duet can serve all the files needed by the web interface
|
||||
|
||||
|
@ -52,17 +52,17 @@ Additional functionality in 0.78g-dc42 release compared to RRP 0.78:
|
|||
|
||||
* When using a Z probe, Z homing and bed probing are done in two stages (a fast stage followed by a slow stage) for better accuracy.
|
||||
|
||||
* The default initial Z homing and bed probing speed has been increased. This is possible because Z homing and bed probing slow down when the probe reading is approaching the target value.
|
||||
|
||||
* M116 takes an optional P parameter to specify which tool to wait for. If no P parameter is given, it waits for all tools and the bed as before. The main purpose of this is that on a tool change, you can wait for the new tool to heat up to operating temperature but not wait for the old tool to cool down to standby temperature.
|
||||
|
||||
* When fetching file info, if the gcode file contains more than one 'filament used' comment, the filament lengths in all of them are returned to the web interface
|
||||
|
||||
* The active and standby temperatures of all heaters are included in the status poll response
|
||||
|
||||
* The default initial Z homing and bed probing speed has been increased. This is possible because Z homing and bed probing slow down when the probe reading is approaching the target value.
|
||||
|
||||
* The M220 and M221 commands now return the override factors if no S parameter is provided
|
||||
|
||||
* Temperature errors are reported to the web server as well as to USB
|
||||
* Temperature errors are reported to the web server as well as to the USB interface
|
||||
|
||||
* The Heat section of the M122 diagnostics report now shows the accumulated PID I-term
|
||||
|
||||
|
@ -72,13 +72,13 @@ Additional functionality in 0.78g-dc42 release compared to RRP 0.78:
|
|||
|
||||
* M104 and M109 commands now accept an optional T parameter to specify the tool number, as generated by slic3r in multi-media gcode files.
|
||||
|
||||
* Movement code from RepRapPro's 0.89 dev version incorporated, including 5-point manual or automatic bed compensation mechanism. A bug fix to this was added in version 0.78g.
|
||||
* Movement code from RepRapPro's 0.89 dev version incorporated, including 5-point manual or automatic bed compensation mechanism. Fixed a bug that caused the head to try to move beyond the axis limits when 5-point auto compensation was used and G32 was executed more than once.
|
||||
|
||||
* Heater status (off/standby/on) is included in the status poll response for the web interface. This will be used in a future version of the web interface.
|
||||
* Heater status (off/standby/on/fault) is included in the status poll response for the web interface
|
||||
|
||||
* Incorporated code from RepRapPro 0.89 dev version to allow many more M-commands to return the existing values as well as set them.
|
||||
|
||||
* Incorporated code from RepRapPro 0.89 dev branch to implement the M119 and M135 commands. There is currently a bug in the M135 (set heat sample interval) command, which means that if you change the interval from its default value of 0.5 seconds then you need to adjust the I parameter by the same ratio and the D parameter by the inverse ratio.
|
||||
* Incorporated code from RepRapPro 0.89 dev branch to implement the M119 and M135 commands. Fixed a bug in the M135 (set heat sample interval) command, which meant that if you changed the interval from its default value of 0.5 seconds, you needed to adjust the I parameter by the same ratio and the D parameter by the inverse ratio.
|
||||
|
||||
* Extrusion totals are reset to zero when starting a new print from SD card.
|
||||
|
||||
|
@ -86,6 +86,10 @@ Additional functionality in 0.78g-dc42 release compared to RRP 0.78:
|
|||
|
||||
* Telnet server supported (thanks zombiepantslol)
|
||||
|
||||
* Fan RPM supported (thanks zombiepantslol)
|
||||
|
||||
* Interrupt-driven network timing to better handle slow writes to SD card (thanks zombiepantslol)
|
||||
|
||||
* Bug fix: uploading file whose name includes an uppercase G now works. Similarly for setting a machine name containing an uppercase G (M550) or password containing an uppercase G (M551)
|
||||
|
||||
* Bug fix: if the machine name in an M550 command is followed by a tab character, then the name is assumed to terminate just before the tab character. Similarly for passwords set using M551.
|
||||
|
@ -108,8 +112,9 @@ Additional functionality in 0.78g-dc42 release compared to RRP 0.78:
|
|||
|
||||
* Bug fix: if the last command in a macro file did not have a newline character at the end then the command might not be fully executed
|
||||
|
||||
* Bug fix: the cooling fan PWM frequency was set to a frequency that was much too high for the mosfet to handle. It has been changed to 25kHz so that it can be used to control 4-wire PWM fans meeting the Intel specification.
|
||||
|
||||
Additional functionality in web interface 0.95 compared to RRP 0.65:
|
||||
Additional functionality in web interface 1.00 compared to RRP 0.65:
|
||||
|
||||
* Faster (>6Mbytes/min), more reliable file uploading, with reporting and graceful recovery if an upload fails
|
||||
|
||||
|
@ -129,4 +134,12 @@ Additional functionality in web interface 0.95 compared to RRP 0.65:
|
|||
|
||||
* Additional status Halted is shown (if emergency stop has been used) as well as Ready and Active
|
||||
|
||||
* The Print Status tab includes slider controls to allow the speed and extrusion factor to be adjusted during printing
|
||||
* The Print Status tab includes slider controls to allow the speed and extrusion factors to be adjusted during printing
|
||||
|
||||
* A second heated print head is supported
|
||||
|
||||
* The active and standby temperature settings of each print head, and the active temperature setting of the bed, are displayed along with the current temperature. The active and standby temperatures can both be set.
|
||||
|
||||
* The status of each heater (off/standby/active/fault) is displayed.
|
||||
|
||||
* If a browser session is reconnected while a print is in progress, the print status is retrieved and displayed.
|
||||
|
|
|
@ -24,8 +24,8 @@ Licence: GPL
|
|||
#define CONFIGURATION_H
|
||||
|
||||
#define NAME "RepRapFirmware"
|
||||
#define VERSION "0.78o-dc42"
|
||||
#define DATE "2014-08-26"
|
||||
#define VERSION "0.78p-dc42"
|
||||
#define DATE "2014-08-29"
|
||||
#define AUTHORS "reprappro, dc42, zpl"
|
||||
|
||||
// Other firmware that we might switch to be compatible with.
|
||||
|
|
131
GCodes.cpp
131
GCodes.cpp
|
@ -350,8 +350,7 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
|
|||
gb->GetFloatArray(eMovement, eMoveCount);
|
||||
if(tool->DriveCount() != eMoveCount)
|
||||
{
|
||||
scratchString.printf("Wrong number of extruder drives for the selected tool: %s\n", gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Wrong number of extruder drives for the selected tool: %s\n", gb->Buffer());
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -490,12 +489,10 @@ bool GCodes::DoFileCannedCycles(const char* fileName)
|
|||
if (f == NULL)
|
||||
{
|
||||
// Don't use snprintf into scratchString here, because fileName may be aliased to scratchString
|
||||
platform->Message(HOST_MESSAGE, "Macro file ");
|
||||
platform->Message(HOST_MESSAGE, fileName);
|
||||
platform->Message(HOST_MESSAGE, " not found.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Macro file %s not found.\n", fileName);
|
||||
if(!Pop())
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Cannot pop the stack.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Cannot pop the stack.\n");
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
@ -1008,7 +1005,7 @@ bool GCodes::OpenFileToWrite(const char* directory, const char* fileName, GCodeB
|
|||
eofStringCounter = 0;
|
||||
if (fileBeingWritten == NULL)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Can't open GCode file for writing.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Can't open GCode file \"%s\" for writing.\n", fileName);
|
||||
return false;
|
||||
}
|
||||
else
|
||||
|
@ -1022,7 +1019,7 @@ void GCodes::WriteHTMLToFile(char b, GCodeBuffer *gb)
|
|||
{
|
||||
if (fileBeingWritten == NULL)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to write to a null file.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Attempt to write to a null file.\n");
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1058,7 +1055,7 @@ void GCodes::WriteGCodeToFile(GCodeBuffer *gb)
|
|||
{
|
||||
if (fileBeingWritten == NULL)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to write to a null file.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Attempt to write to a null file.\n");
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1085,7 +1082,7 @@ void GCodes::WriteGCodeToFile(GCodeBuffer *gb)
|
|||
{
|
||||
if (gb->Seen('P'))
|
||||
{
|
||||
scratchString.printf("%s", gb->GetIValue());
|
||||
scratchString.printf("%d", gb->GetIValue());
|
||||
HandleReply(false, gb == serialGCode, scratchString.Pointer(), 'G', 998, true);
|
||||
return;
|
||||
}
|
||||
|
@ -1120,7 +1117,7 @@ void GCodes::QueueFileToPrint(const char* fileName)
|
|||
}
|
||||
else
|
||||
{
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCode file not found\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCode file \"%s\" not found\n", fileName);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1128,8 +1125,7 @@ void GCodes::DeleteFile(const char* fileName)
|
|||
{
|
||||
if(!platform->GetMassStorage()->Delete(platform->GetGCodeDir(), fileName))
|
||||
{
|
||||
scratchString.printf("Unsuccessful attempt to delete: %s\n", fileName);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Unsuccessful attempt to delete file \"%s\"\n", fileName);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1142,7 +1138,7 @@ bool GCodes::SendConfigToLine()
|
|||
configFile = platform->GetFileStore(platform->GetSysDir(), platform->GetConfigFile(), false);
|
||||
if (configFile == NULL)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Configuration file not found\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Configuration file not found\n");
|
||||
return true;
|
||||
}
|
||||
platform->GetLine()->Write('\n', true);
|
||||
|
@ -1331,9 +1327,7 @@ void GCodes::SetEthernetAddress(GCodeBuffer *gb, int mCode)
|
|||
ipp++;
|
||||
if (ipp > 3)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Dud IP address: ");
|
||||
platform->Message(HOST_MESSAGE, gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Dud IP address: %s\n", gb->Buffer());
|
||||
return;
|
||||
}
|
||||
sp++;
|
||||
|
@ -1360,14 +1354,12 @@ void GCodes::SetEthernetAddress(GCodeBuffer *gb, int mCode)
|
|||
break;
|
||||
|
||||
default:
|
||||
platform->Message(HOST_MESSAGE, "Setting ether parameter - dud code.");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Setting ether parameter - dud code.");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Dud IP address: ");
|
||||
platform->Message(HOST_MESSAGE, gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Dud IP address: %s\n", gb->Buffer());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1387,9 +1379,7 @@ void GCodes::SetMACAddress(GCodeBuffer *gb)
|
|||
ipp++;
|
||||
if(ipp > 5)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Dud MAC address: ");
|
||||
platform->Message(HOST_MESSAGE, gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Dud MAC address: %s\n", gb->Buffer());
|
||||
return;
|
||||
}
|
||||
sp++;
|
||||
|
@ -1407,9 +1397,7 @@ void GCodes::SetMACAddress(GCodeBuffer *gb)
|
|||
}
|
||||
else
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Dud MAC address: ");
|
||||
platform->Message(HOST_MESSAGE, gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Dud MAC address: %s\n", gb->Buffer());
|
||||
}
|
||||
// snprintf(scratchString, STRING_LENGTH, "MAC: %x:%x:%x:%x:%x:%x\n", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
|
||||
// platform->Message(HOST_MESSAGE, scratchString);
|
||||
|
@ -1503,8 +1491,7 @@ void GCodes::HandleReply(bool error, bool fromLine, const char* reply, char gMOr
|
|||
|
||||
if (s != 0)
|
||||
{
|
||||
scratchString.printf("Emulation of %s is not yet supported.\n", s);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Emulation of %s is not yet supported.\n", s);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1638,7 +1625,7 @@ void GCodes::SetToolHeaters(Tool *tool, float temperature)
|
|||
{
|
||||
if(tool == NULL)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Setting temperature: no tool selected.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Setting temperature: no tool selected.\n");
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1928,7 +1915,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
break;
|
||||
|
||||
case 29: // End of file being written; should be intercepted before getting here
|
||||
platform->Message(HOST_MESSAGE, "GCode end-of-file being interpreted.\n");
|
||||
platform->Message(BOTH_MESSAGE, "GCode end-of-file being interpreted.\n");
|
||||
break;
|
||||
|
||||
case 30: // Delete file
|
||||
|
@ -1989,8 +1976,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
gb->GetFloatArray(eVals, eCount);
|
||||
if(eCount != DRIVES-AXES)
|
||||
{
|
||||
scratchString.printf("Setting steps/mm - wrong number of E drives: %s\n", gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Setting steps/mm - wrong number of E drives: %s\n", gb->Buffer());
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -2052,32 +2038,43 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
reply.copy("T:");
|
||||
for(int8_t heater = 1; heater < HEATERS; heater++)
|
||||
{
|
||||
if(reprap.GetHeat()->GetStatus(heater) != Heat::HS_off)
|
||||
Heat::HeaterStatus hs = reprap.GetHeat()->GetStatus(heater);
|
||||
if(hs != Heat::HS_off && hs != Heat::HS_fault)
|
||||
{
|
||||
reply.catf("%.1f ", reprap.GetHeat()->GetTemperature(heater));
|
||||
}
|
||||
}
|
||||
reply.catf("B: %.1f ", reprap.GetHeat()->GetTemperature(0));
|
||||
reply.catf("B: %.1f ", reprap.GetHeat()->GetTemperature(HOT_BED));
|
||||
break;
|
||||
|
||||
case 106: // Fan on or off
|
||||
if (gb->Seen('I'))
|
||||
{
|
||||
coolingInverted = (gb->GetIValue() > 0);
|
||||
}
|
||||
if (gb->Seen('S'))
|
||||
{
|
||||
float f = gb->GetFValue();
|
||||
f = min<float>(f, 255.0);
|
||||
f = max<float>(f, 0.0);
|
||||
if (coolingInverted)
|
||||
bool seen = false;
|
||||
if (gb->Seen('I'))
|
||||
{
|
||||
// Check if 1.0 or 255.0 may be used as the maximum value
|
||||
platform->CoolingFan((f <= 1.0 ? 1.0 : 255.0) - f);
|
||||
coolingInverted = (gb->GetIValue() > 0);
|
||||
seen = true;
|
||||
}
|
||||
else
|
||||
if (gb->Seen('S'))
|
||||
{
|
||||
platform->CoolingFan(f);
|
||||
float f = gb->GetFValue();
|
||||
f = min<float>(f, 255.0);
|
||||
f = max<float>(f, 0.0);
|
||||
if (coolingInverted)
|
||||
{
|
||||
// Check if 1.0 or 255.0 may be used as the maximum value
|
||||
platform->CoolingFan((f <= 1.0 ? 1.0 : 255.0) - f);
|
||||
}
|
||||
else
|
||||
{
|
||||
platform->CoolingFan(f);
|
||||
}
|
||||
seen = true;
|
||||
}
|
||||
|
||||
if (!seen)
|
||||
{
|
||||
reply.printf("Cooling inverted: %s", coolingInverted ? "yes" : "no");
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -2236,11 +2233,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
break;
|
||||
|
||||
case 126: // Valve open
|
||||
platform->Message(HOST_MESSAGE, "M126 - valves not yet implemented\n");
|
||||
platform->Message(BOTH_MESSAGE, "M126 - valves not yet implemented\n");
|
||||
break;
|
||||
|
||||
case 127: // Valve closed
|
||||
platform->Message(HOST_MESSAGE, "M127 - valves not yet implemented\n");
|
||||
platform->Message(BOTH_MESSAGE, "M127 - valves not yet implemented\n");
|
||||
break;
|
||||
|
||||
case 135: // Set PID sample interval
|
||||
|
@ -2273,7 +2270,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
break;
|
||||
|
||||
case 141: // Chamber temperature
|
||||
platform->Message(HOST_MESSAGE, "M141 - heated chamber not yet implemented\n");
|
||||
platform->Message(BOTH_MESSAGE, "M141 - heated chamber not yet implemented\n");
|
||||
break;
|
||||
|
||||
// case 160: //number of mixing filament drives TODO: With tools defined, is this needed?
|
||||
|
@ -2320,8 +2317,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
gb->GetFloatArray(eVals, eCount);
|
||||
if(eCount != DRIVES-AXES)
|
||||
{
|
||||
scratchString.printf("Setting accelerations - wrong number of E drives: %s\n", gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Setting accelerations - wrong number of E drives: %s\n", gb->Buffer());
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -2369,8 +2365,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
gb->GetFloatArray(eVals, eCount);
|
||||
if(eCount != DRIVES-AXES)
|
||||
{
|
||||
scratchString.printf("Setting feedrates - wrong number of E drives: %s\n", gb->Buffer());
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Setting feedrates - wrong number of E drives: %s\n", gb->Buffer());
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -3025,7 +3020,7 @@ bool GCodes::ChangeTool(int newToolNumber)
|
|||
return true;
|
||||
|
||||
default:
|
||||
platform->Message(HOST_MESSAGE, "Tool change - dud sequence number.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Tool change - dud sequence number.\n");
|
||||
}
|
||||
|
||||
toolChangeSequence = 0;
|
||||
|
@ -3108,9 +3103,7 @@ bool GCodeBuffer::Put(char c)
|
|||
Init();
|
||||
if (reprap.Debug() && gcodeBuffer[0] && !writingFileDirectory) // Don't bother with blank/comment lines
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, identity);
|
||||
platform->Message(HOST_MESSAGE, gcodeBuffer);
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(HOST_MESSAGE, "%s%s\n", identity, gcodeBuffer);
|
||||
}
|
||||
|
||||
// Deal with line numbers and checksums
|
||||
|
@ -3171,7 +3164,7 @@ bool GCodeBuffer::Put(char c)
|
|||
|
||||
if (gcodePointer >= GCODE_LENGTH)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "G Code buffer length overflow.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "G Code buffer length overflow.\n");
|
||||
gcodePointer = 0;
|
||||
gcodeBuffer[0] = 0;
|
||||
}
|
||||
|
@ -3202,7 +3195,7 @@ float GCodeBuffer::GetFValue()
|
|||
{
|
||||
if (readPointer < 0)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode float before a search.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float before a search.\n");
|
||||
readPointer = -1;
|
||||
return 0.0;
|
||||
}
|
||||
|
@ -3218,7 +3211,7 @@ const void GCodeBuffer::GetFloatArray(float a[], int& returnedLength)
|
|||
int length = 0;
|
||||
if(readPointer < 0)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode float array before a search.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float array before a search.\n");
|
||||
readPointer = -1;
|
||||
returnedLength = 0;
|
||||
return;
|
||||
|
@ -3229,8 +3222,7 @@ const void GCodeBuffer::GetFloatArray(float a[], int& returnedLength)
|
|||
{
|
||||
if(length >= returnedLength) // Array limit has been set in here
|
||||
{
|
||||
scratchString.printf("GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer);
|
||||
readPointer = -1;
|
||||
returnedLength = 0;
|
||||
return;
|
||||
|
@ -3273,7 +3265,7 @@ const void GCodeBuffer::GetLongArray(long l[], int& returnedLength)
|
|||
int length = 0;
|
||||
if(readPointer < 0)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode long array before a search.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode long array before a search.\n");
|
||||
readPointer = -1;
|
||||
return;
|
||||
}
|
||||
|
@ -3283,8 +3275,7 @@ const void GCodeBuffer::GetLongArray(long l[], int& returnedLength)
|
|||
{
|
||||
if(length >= returnedLength) // Array limit has been set in here
|
||||
{
|
||||
scratchString.printf("GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer);
|
||||
readPointer = -1;
|
||||
returnedLength = 0;
|
||||
return;
|
||||
|
@ -3313,7 +3304,7 @@ const char* GCodeBuffer::GetString()
|
|||
{
|
||||
if (readPointer < 0)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode string before a search.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode string before a search.\n");
|
||||
readPointer = -1;
|
||||
return "";
|
||||
}
|
||||
|
@ -3343,7 +3334,7 @@ const char* GCodeBuffer::GetUnprecedentedString()
|
|||
|
||||
if (!gcodeBuffer[readPointer])
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "GCodes: String expected but not seen.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: String expected but not seen.\n");
|
||||
readPointer = -1;
|
||||
return gcodeBuffer; // Good idea?
|
||||
}
|
||||
|
@ -3359,7 +3350,7 @@ long GCodeBuffer::GetLValue()
|
|||
{
|
||||
if (readPointer < 0)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode int before a search.\n");
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode int before a search.\n");
|
||||
readPointer = -1;
|
||||
return 0;
|
||||
}
|
||||
|
|
19
Heat.cpp
19
Heat.cpp
|
@ -73,8 +73,7 @@ void Heat::Diagnostics()
|
|||
{
|
||||
if (pids[heater]->active)
|
||||
{
|
||||
scratchString.printf("Heater %d: I-accumulator = %.1f\n", heater, pids[heater]->temp_iState);
|
||||
platform->AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
platform->AppendMessage(BOTH_MESSAGE, "Heater %d: I-accumulator = %.1f\n", heater, pids[heater]->temp_iState);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -163,8 +162,7 @@ void PID::Spin()
|
|||
platform->SetHeater(heater, 0.0);
|
||||
temperatureFault = true;
|
||||
switchedOff = true;
|
||||
scratchString.printf("Temperature fault on heater %d, T = %.1f\n", heater, temperature);
|
||||
platform->Message(BOTH_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_MESSAGE, "Temperature fault on heater %d, T = %.1f\n", heater, temperature);
|
||||
reprap.FlagTemperatureFault(heater);
|
||||
}
|
||||
}
|
||||
|
@ -191,8 +189,7 @@ void PID::Spin()
|
|||
platform->SetHeater(heater, 0.0);
|
||||
temperatureFault = true;
|
||||
switchedOff = true;
|
||||
scratchString.printf("Heating fault on heater %d, T = %.1f C; still not at temperature after %f seconds.\n", heater, temperature, tim);
|
||||
platform->Message(BOTH_MESSAGE, scratchString);
|
||||
platform->Message(BOTH_MESSAGE, "Heating fault on heater %d, T = %.1f C; still not at temperature after %f seconds.\n", heater, temperature, tim);
|
||||
reprap.FlagTemperatureFault(heater);
|
||||
}
|
||||
}
|
||||
|
@ -232,8 +229,14 @@ void PID::Spin()
|
|||
float sampleInterval = platform->HeatSampleTime();
|
||||
temp_iState += error * pp.kI * sampleInterval;
|
||||
|
||||
if (temp_iState < pp.pidMin) temp_iState = pp.pidMin;
|
||||
else if (temp_iState > pp.pidMax) temp_iState = pp.pidMax;
|
||||
if (temp_iState < pp.pidMin)
|
||||
{
|
||||
temp_iState = pp.pidMin;
|
||||
}
|
||||
else if (temp_iState > pp.pidMax)
|
||||
{
|
||||
temp_iState = pp.pidMax;
|
||||
}
|
||||
|
||||
float temp_dState = pp.kD * (temperature - lastTemperature) / sampleInterval;
|
||||
float result = pp.kP * error + temp_iState - temp_dState;
|
||||
|
|
9
Heat.h
9
Heat.h
|
@ -72,7 +72,7 @@ class Heat
|
|||
{
|
||||
public:
|
||||
// Enumeration to describe the status of a heater. Note that the web interface returns the numerical values, so don't change them.
|
||||
enum HeaterStatus { HS_off = 0, HS_standby = 1, HS_active = 2 };
|
||||
enum HeaterStatus { HS_off = 0, HS_standby = 1, HS_active = 2, HS_fault = 3 };
|
||||
|
||||
Heat(Platform* p, GCodes* g);
|
||||
void Spin(); // Called in a tight loop to keep everything going
|
||||
|
@ -187,9 +187,10 @@ inline Heat::HeaterStatus Heat::GetStatus(int8_t heater) const
|
|||
{
|
||||
if (heater < 0 || heater >= HEATERS)
|
||||
return HS_off;
|
||||
return (pids[heater]->SwitchedOff()) ? HS_off
|
||||
: (pids[heater]->Active()) ? HS_active
|
||||
: HS_standby;
|
||||
return (pids[heater]->temperatureFault ? HS_fault
|
||||
: pids[heater]->SwitchedOff()) ? HS_off
|
||||
: (pids[heater]->Active()) ? HS_active
|
||||
: HS_standby;
|
||||
}
|
||||
|
||||
inline void Heat::SetActiveTemperature(int8_t heater, float t)
|
||||
|
|
|
@ -83,44 +83,51 @@ Allows a non "Arduino Due" PIO pin to be setup.
|
|||
*/
|
||||
extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode )
|
||||
{
|
||||
if ( nonDuePinDescription[ulPin].ulPinType == PIO_NOT_A_PIN )
|
||||
if (ulPin < X0)
|
||||
{
|
||||
pinMode(ulPin, ulMode); // pass on to Arduino core
|
||||
return;
|
||||
}
|
||||
|
||||
const PinDescription& pinDesc = nonDuePinDescription[ulPin - X0];
|
||||
if ( pinDesc.ulPinType == PIO_NOT_A_PIN )
|
||||
{
|
||||
return ;
|
||||
return;
|
||||
}
|
||||
|
||||
switch ( ulMode )
|
||||
{
|
||||
case INPUT:
|
||||
/* Enable peripheral for clocking input */
|
||||
pmc_enable_periph_clk( nonDuePinDescription[ulPin].ulPeripheralId ) ;
|
||||
pmc_enable_periph_clk( pinDesc.ulPeripheralId ) ;
|
||||
PIO_Configure(
|
||||
nonDuePinDescription[ulPin].pPort,
|
||||
pinDesc.pPort,
|
||||
PIO_INPUT,
|
||||
nonDuePinDescription[ulPin].ulPin,
|
||||
pinDesc.ulPin,
|
||||
0 ) ;
|
||||
break ;
|
||||
|
||||
case INPUT_PULLUP:
|
||||
/* Enable peripheral for clocking input */
|
||||
pmc_enable_periph_clk( nonDuePinDescription[ulPin].ulPeripheralId ) ;
|
||||
pmc_enable_periph_clk( pinDesc.ulPeripheralId ) ;
|
||||
PIO_Configure(
|
||||
nonDuePinDescription[ulPin].pPort,
|
||||
pinDesc.pPort,
|
||||
PIO_INPUT,
|
||||
nonDuePinDescription[ulPin].ulPin,
|
||||
pinDesc.ulPin,
|
||||
PIO_PULLUP ) ;
|
||||
break ;
|
||||
|
||||
case OUTPUT:
|
||||
PIO_Configure(
|
||||
nonDuePinDescription[ulPin].pPort,
|
||||
pinDesc.pPort,
|
||||
PIO_OUTPUT_1,
|
||||
nonDuePinDescription[ulPin].ulPin,
|
||||
nonDuePinDescription[ulPin].ulPinConfiguration ) ;
|
||||
pinDesc.ulPin,
|
||||
pinDesc.ulPinConfiguration ) ;
|
||||
|
||||
/* if all pins are output, disable PIO Controller clocking, reduce power consumption */
|
||||
if ( nonDuePinDescription[ulPin].pPort->PIO_OSR == 0xffffffff )
|
||||
if ( pinDesc.pPort->PIO_OSR == 0xffffffff )
|
||||
{
|
||||
pmc_disable_periph_clk( g_APinDescription[ulPin].ulPeripheralId ) ;
|
||||
pmc_disable_periph_clk( pinDesc.ulPeripheralId ) ;
|
||||
}
|
||||
break ;
|
||||
|
||||
|
@ -137,19 +144,27 @@ Allows digital write to a non "Arduino Due" PIO pin that has been setup as outpu
|
|||
|
||||
extern void digitalWriteNonDue( uint32_t ulPin, uint32_t ulVal )
|
||||
{
|
||||
if (ulPin < X0)
|
||||
{
|
||||
digitalWrite(ulPin, ulVal); // pass on to Arduino core
|
||||
return;
|
||||
}
|
||||
|
||||
const PinDescription& pinDesc = nonDuePinDescription[ulPin - X0];
|
||||
|
||||
/* Handle */
|
||||
if ( nonDuePinDescription[ulPin].ulPinType == PIO_NOT_A_PIN )
|
||||
{
|
||||
if ( pinDesc.ulPinType == PIO_NOT_A_PIN )
|
||||
{
|
||||
return ;
|
||||
}
|
||||
|
||||
if ( PIO_GetOutputDataStatus( nonDuePinDescription[ulPin].pPort, nonDuePinDescription[ulPin].ulPin ) == 0 )
|
||||
if ( PIO_GetOutputDataStatus( pinDesc.pPort, pinDesc.ulPin ) == 0 )
|
||||
{
|
||||
PIO_PullUp( nonDuePinDescription[ulPin].pPort, nonDuePinDescription[ulPin].ulPin, ulVal ) ;
|
||||
PIO_PullUp( pinDesc.pPort, pinDesc.ulPin, ulVal ) ;
|
||||
}
|
||||
else
|
||||
{
|
||||
PIO_SetOutput( nonDuePinDescription[ulPin].pPort, nonDuePinDescription[ulPin].ulPin, ulVal, 0, PIO_PULLUP ) ;
|
||||
PIO_SetOutput( pinDesc.pPort, pinDesc.ulPin, ulVal, 0, PIO_PULLUP ) ;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -160,12 +175,18 @@ Allows digital read of a non "Arduino Due" PIO pin that has been setup as input
|
|||
*/
|
||||
extern int digitalReadNonDue( uint32_t ulPin )
|
||||
{
|
||||
if ( nonDuePinDescription[ulPin].ulPinType == PIO_NOT_A_PIN )
|
||||
if (ulPin < X0)
|
||||
{
|
||||
return digitalRead(ulPin); // pass on to Arduino core
|
||||
}
|
||||
|
||||
const PinDescription& pinDesc = nonDuePinDescription[ulPin - X0];
|
||||
if ( pinDesc.ulPinType == PIO_NOT_A_PIN )
|
||||
{
|
||||
return LOW ;
|
||||
}
|
||||
|
||||
if ( PIO_Get( nonDuePinDescription[ulPin].pPort, PIO_INPUT, nonDuePinDescription[ulPin].ulPin ) == 1 )
|
||||
if ( PIO_Get( pinDesc.pPort, PIO_INPUT, pinDesc.ulPin ) == 1 )
|
||||
{
|
||||
return HIGH ;
|
||||
}
|
||||
|
@ -173,59 +194,80 @@ extern int digitalReadNonDue( uint32_t ulPin )
|
|||
return LOW ;
|
||||
}
|
||||
|
||||
static uint8_t PWMEnabled = 0;
|
||||
static uint8_t pinEnabled[PINS_C];
|
||||
static bool nonDuePWMEnabled = 0;
|
||||
static bool PWMChanEnabled[8] = {false,false,false,false, false,false,false,false}; // there are only 8 PWM channels
|
||||
|
||||
/*
|
||||
analog write helper functions
|
||||
*/
|
||||
void analogOutputNonDueInit(void) {
|
||||
uint8_t i;
|
||||
for (i=0; i<PINS_C; i++)
|
||||
pinEnabled[i] = 0;
|
||||
// Version of PWMC_ConfigureChannel from Arduino core, fixed to not mess up PWM channel 0 when another channel is programmed
|
||||
static void PWMC_ConfigureChannel_fixed( Pwm* pPwm, uint32_t ul_channel, uint32_t prescaler, uint32_t alignment, uint32_t polarity )
|
||||
{
|
||||
/* Disable ul_channel (effective at the end of the current period) */
|
||||
if ((pPwm->PWM_SR & (1 << ul_channel)) != 0) {
|
||||
pPwm->PWM_DIS = 1 << ul_channel;
|
||||
while ((pPwm->PWM_SR & (1 << ul_channel)) != 0);
|
||||
}
|
||||
|
||||
/* Configure ul_channel */
|
||||
pPwm->PWM_CH_NUM[ul_channel].PWM_CMR = prescaler | alignment | polarity;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
analogWriteNonDue
|
||||
copied from the analogWrite function within wiring-analog.c file, part of the arduino core.
|
||||
Allows analog write to a non "Arduino Due" PWM pin. Note this does not support the other functions of
|
||||
the arduino analog write function such as timer counters and the DAC. Any hardware PWM pin that is defined as such
|
||||
within the unDefPinDescription[] struct should work, and non hardware PWM pin will default to digitalWriteUndefined
|
||||
NOTE:
|
||||
1. We must not pass on any PWM calls to the Arduino core analogWrite here, because it calls the buggy version of PWMC_ConfigureChannel
|
||||
which messes up channel 0..
|
||||
2. The optional fastPwm parameter only takes effect on the first call to analogWriteNonDuet for each PWM pin.
|
||||
If true on the first call then the PWM frequency will be set to 25kHz instead of 1kHz.
|
||||
*/
|
||||
|
||||
void analogWriteNonDue(uint32_t ulPin, uint32_t ulValue) {
|
||||
uint32_t attr = nonDuePinDescription[ulPin].ulPinAttribute;
|
||||
if ((attr & PIN_ATTR_PWM) == PIN_ATTR_PWM) {
|
||||
if (!PWMEnabled) {
|
||||
// PWM Startup code
|
||||
pmc_enable_periph_clk(PWM_INTERFACE_ID);
|
||||
PWMC_ConfigureClocks(PWM_FREQUENCY * PWM_MAX_DUTY_CYCLE, 0, VARIANT_MCK);
|
||||
analogOutputNonDueInit();
|
||||
PWMEnabled = 1;
|
||||
}
|
||||
uint32_t chan = nonDuePinDescription[ulPin].ulPWMChannel;
|
||||
if (!pinEnabled[ulPin]) {
|
||||
// Setup PWM for this pin
|
||||
PIO_Configure(nonDuePinDescription[ulPin].pPort,
|
||||
nonDuePinDescription[ulPin].ulPinType,
|
||||
nonDuePinDescription[ulPin].ulPin,
|
||||
nonDuePinDescription[ulPin].ulPinConfiguration);
|
||||
PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, 0, 0);
|
||||
PWMC_SetPeriod(PWM_INTERFACE, chan, PWM_MAX_DUTY_CYCLE);
|
||||
PWMC_SetDutyCycle(PWM_INTERFACE, chan, ulValue);
|
||||
PWMC_EnableChannel(PWM_INTERFACE, chan);
|
||||
pinEnabled[ulPin] = 1;
|
||||
}
|
||||
void analogWriteNonDue(uint32_t ulPin, uint32_t ulValue, bool fastPwm)
|
||||
{
|
||||
const PinDescription& pinDesc = (ulPin >= X0) ? nonDuePinDescription[ulPin - X0] : g_APinDescription[ulPin];
|
||||
uint32_t attr = pinDesc.ulPinAttribute;
|
||||
if ((attr & PIN_ATTR_ANALOG) == PIN_ATTR_ANALOG)
|
||||
{
|
||||
// It's a DAC pin, so we can pass it on (and it can't be an extended pin because none of our extended pins support DAC)
|
||||
analogWrite(ulPin, ulValue);
|
||||
return;
|
||||
}
|
||||
|
||||
if ((attr & PIN_ATTR_PWM) == PIN_ATTR_PWM)
|
||||
{
|
||||
if (!nonDuePWMEnabled)
|
||||
{
|
||||
// PWM Startup code
|
||||
pmc_enable_periph_clk(PWM_INTERFACE_ID);
|
||||
// Set clock A to give 1kHz PWM (the standard value for Arduino Due) and clock B to give 25kHz PWM
|
||||
PWMC_ConfigureClocks(PWM_FREQUENCY * PWM_MAX_DUTY_CYCLE, pwmFastFrequency * PWM_MAX_DUTY_CYCLE, VARIANT_MCK);
|
||||
nonDuePWMEnabled = true;
|
||||
}
|
||||
|
||||
uint32_t chan = pinDesc.ulPWMChannel;
|
||||
if (!PWMChanEnabled[chan])
|
||||
{
|
||||
// Setup PWM for this PWM channel
|
||||
PIO_Configure(pinDesc.pPort,
|
||||
pinDesc.ulPinType,
|
||||
pinDesc.ulPin,
|
||||
pinDesc.ulPinConfiguration);
|
||||
PWMC_ConfigureChannel_fixed(PWM_INTERFACE, chan, (fastPwm) ? PWM_CMR_CPRE_CLKB : PWM_CMR_CPRE_CLKA, 0, 0);
|
||||
PWMC_SetPeriod(PWM_INTERFACE, chan, PWM_MAX_DUTY_CYCLE);
|
||||
PWMC_SetDutyCycle(PWM_INTERFACE, chan, ulValue);
|
||||
PWMC_EnableChannel(PWM_INTERFACE, chan);
|
||||
PWMChanEnabled[chan] = true;
|
||||
}
|
||||
|
||||
PWMC_SetDutyCycle(PWM_INTERFACE, chan, ulValue);
|
||||
return;
|
||||
}
|
||||
|
||||
PWMC_SetDutyCycle(PWM_INTERFACE, chan, ulValue);
|
||||
return;
|
||||
}
|
||||
// Defaults to digital write
|
||||
pinModeNonDue(ulPin, OUTPUT);
|
||||
if (ulValue < 128)
|
||||
digitalWriteNonDue(ulPin, LOW);
|
||||
else
|
||||
digitalWriteNonDue(ulPin, HIGH);
|
||||
digitalWriteNonDue(ulPin, (ulValue < 128) ? LOW : HIGH);
|
||||
}
|
||||
|
||||
|
||||
|
@ -239,11 +281,11 @@ void hsmciPinsinit()
|
|||
PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].ulPinConfiguration);
|
||||
PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].ulPinConfiguration);
|
||||
//set pullups (not on clock!)
|
||||
digitalWriteNonDue(PIN_HSMCI_MCCDA_GPIO, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA0_GPIO, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA1_GPIO, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA2_GPIO, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA3_GPIO, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCCDA_GPIO+X0, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA0_GPIO+X0, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA1_GPIO+X0, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA2_GPIO+X0, HIGH);
|
||||
digitalWriteNonDue(PIN_HSMCI_MCDA3_GPIO+X0, HIGH);
|
||||
}
|
||||
|
||||
//initialise ethernet pins
|
||||
|
|
|
@ -29,17 +29,21 @@ See undefined.cpp file for more info
|
|||
// Number of pins defined in PinDescription array
|
||||
#define PINS_C 25
|
||||
|
||||
//undefined pins constants so the undef pins can
|
||||
//be refered to a Xn rather than n
|
||||
static const uint8_t X0 = 0;
|
||||
static const uint8_t X1 = 1;
|
||||
static const uint8_t X2 = 2;
|
||||
static const uint8_t X3 = 3;
|
||||
static const uint8_t X4 = 4;
|
||||
static const uint8_t X5 = 5;
|
||||
static const uint8_t X6 = 6;
|
||||
static const uint8_t X7 = 7;
|
||||
static const uint8_t X8 = 8;
|
||||
static const unsigned int pwmFastFrequency = 25000; // fast PWM frequency for Intel spec PWM fans
|
||||
|
||||
// Undefined pins constants so the undef pins can be referred to a Xn rather than n
|
||||
// Any pin numbers below X0 we assume are ordinary Due pin numbers
|
||||
// Note: these must all be <=127 because pin numbers are held in int8_t in some places.
|
||||
// There are 92 pins defined in the Arduino Due core as at version 1.5.4, so these must all be >=92
|
||||
static const uint8_t X0 = 100;
|
||||
static const uint8_t X1 = 101;
|
||||
static const uint8_t X2 = 102;
|
||||
static const uint8_t X3 = 103;
|
||||
static const uint8_t X4 = 104;
|
||||
static const uint8_t X5 = 105;
|
||||
static const uint8_t X6 = 106;
|
||||
static const uint8_t X7 = 107;
|
||||
static const uint8_t X8 = 108;
|
||||
//HSMCI
|
||||
static const uint8_t PIN_HSMCI_MCCDA_GPIO = 9;
|
||||
static const uint8_t PIN_HSMCI_MCCK_GPIO = 10;
|
||||
|
@ -66,7 +70,7 @@ extern const PinDescription nonDuePinDescription[] ;
|
|||
extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode );
|
||||
extern void digitalWriteNonDue( uint32_t ulPin, uint32_t ulVal );
|
||||
extern int digitalReadNonDue( uint32_t ulPin);
|
||||
extern void analogWriteNonDue(uint32_t ulPin, uint32_t ulValue);
|
||||
extern void analogWriteNonDue(uint32_t ulPin, uint32_t ulValue, bool fastPwm = false);
|
||||
extern void analogOutputNonDue();
|
||||
extern void hsmciPinsinit();
|
||||
extern void ethPinsInit();
|
||||
|
|
3
Move.cpp
3
Move.cpp
|
@ -1310,10 +1310,9 @@ long LookAhead::EndPointToMachine(int8_t drive, float coord)
|
|||
|
||||
void LookAhead::PrintMove()
|
||||
{
|
||||
scratchString.printf("X,Y,Z: %.1f %.1f %.1f, min v: %.2f, max v: %.1f, acc: %.1f, feed: %.1f, u: %.3f, v: %.3f\n",
|
||||
platform->Message(HOST_MESSAGE, "X,Y,Z: %.1f %.1f %.1f, min v: %.2f, max v: %.1f, acc: %.1f, feed: %.1f, u: %.3f, v: %.3f\n",
|
||||
MachineToEndPoint(X_AXIS), MachineToEndPoint(Y_AXIS), MachineToEndPoint(Z_AXIS),
|
||||
MinSpeed(), MaxSpeed(), Acceleration(), FeedRate(), Previous()->V(), V());
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
}
|
||||
|
||||
|
||||
|
|
30
Move.h
30
Move.h
|
@ -69,17 +69,17 @@ protected:
|
|||
LookAhead(Move* m, Platform* p, LookAhead* n);
|
||||
void Init(long ep[], float requsestedFeedRate, float minSpeed, // Set up this move
|
||||
float maxSpeed, float acceleration, EndstopChecks ce);
|
||||
LookAhead* Next(); // Next one in the ring
|
||||
LookAhead* Previous(); // Previous one in the ring
|
||||
LookAhead* Next() const; // Next one in the ring
|
||||
LookAhead* Previous() const; // Previous one in the ring
|
||||
const long* MachineCoordinates() const; // Endpoints of a move in machine coordinates
|
||||
float MachineToEndPoint(int8_t drive) const; // Convert a move endpoint to real mm coordinates
|
||||
static float MachineToEndPoint(int8_t drive, long coord); // Convert any number to a real coordinate
|
||||
static long EndPointToMachine(int8_t drive, float coord); // Convert real mm to a machine coordinate
|
||||
float FeedRate(); // How fast is the set speed for this move
|
||||
float MinSpeed(); // What is the slowest that this move can be
|
||||
float MaxSpeed(); // What is the fastest this move can be
|
||||
float Acceleration(); // What is the acceleration available for this move
|
||||
float V(); // The speed at the end of the move
|
||||
float FeedRate() const; // How fast is the set speed for this move
|
||||
float MinSpeed() const; // What is the slowest that this move can be
|
||||
float MaxSpeed() const; // What is the fastest this move can be
|
||||
float Acceleration() const; // What is the acceleration available for this move
|
||||
float V() const; // The speed at the end of the move
|
||||
void SetV(float vv); // Set the end speed
|
||||
void SetFeedRate(float f); // Set the desired feedrate
|
||||
int8_t Processed() const; // Where we are in the look-ahead prediction sequence
|
||||
|
@ -258,7 +258,7 @@ class Move
|
|||
bool addNoMoreMoves; // If true, allow no more moves to be added to the look-ahead
|
||||
bool active; // Are we live and running?
|
||||
float currentFeedrate; // Err... the current feed rate...
|
||||
float liveCoordinates[DRIVES + 1]; // The last endpoint that the machine moved to
|
||||
volatile float liveCoordinates[DRIVES + 1]; // The last endpoint that the machine moved to
|
||||
float nextMove[DRIVES + 1]; // The endpoint of the next move to processExtra entry is for feedrate
|
||||
float normalisedDirectionVector[DRIVES]; // Used to hold a unit-length vector in the direction of motion
|
||||
long nextMachineEndPoints[DRIVES+1]; // The next endpoint in machine coordinates (i.e. steps)
|
||||
|
@ -280,12 +280,12 @@ class Move
|
|||
|
||||
//********************************************************************************************************
|
||||
|
||||
inline LookAhead* LookAhead::Next()
|
||||
inline LookAhead* LookAhead::Next() const
|
||||
{
|
||||
return next;
|
||||
}
|
||||
|
||||
inline LookAhead* LookAhead::Previous()
|
||||
inline LookAhead* LookAhead::Previous() const
|
||||
{
|
||||
return previous;
|
||||
}
|
||||
|
@ -301,22 +301,22 @@ inline float LookAhead::MachineToEndPoint(int8_t drive) const
|
|||
return ((float)(endPoint[drive]))/platform->DriveStepsPerUnit(drive);
|
||||
}
|
||||
|
||||
inline float LookAhead::FeedRate()
|
||||
inline float LookAhead::FeedRate() const
|
||||
{
|
||||
return requestedFeedrate;
|
||||
}
|
||||
|
||||
inline float LookAhead::MinSpeed()
|
||||
inline float LookAhead::MinSpeed() const
|
||||
{
|
||||
return minSpeed;
|
||||
}
|
||||
|
||||
inline float LookAhead::MaxSpeed()
|
||||
inline float LookAhead::MaxSpeed() const
|
||||
{
|
||||
return maxSpeed;
|
||||
}
|
||||
|
||||
inline float LookAhead::Acceleration()
|
||||
inline float LookAhead::Acceleration() const
|
||||
{
|
||||
return acceleration;
|
||||
}
|
||||
|
@ -326,7 +326,7 @@ inline void LookAhead::SetV(float vv)
|
|||
v = vv;
|
||||
}
|
||||
|
||||
inline float LookAhead::V()
|
||||
inline float LookAhead::V() const
|
||||
{
|
||||
return v;
|
||||
}
|
||||
|
|
52
Network.cpp
52
Network.cpp
|
@ -123,6 +123,28 @@ static void SendData(tcp_pcb *pcb, ConnectionState *cs)
|
|||
extern "C"
|
||||
{
|
||||
|
||||
// Callback functions for the EMAC driver
|
||||
|
||||
static void emac_read_packet(uint32_t ul_status)
|
||||
{
|
||||
// Because the LWIP stack can become corrupted if we work with it in parallel,
|
||||
// we may have to wait for the next Spin() call to read the next packet.
|
||||
// On this occasion, we can set the RX callback again.
|
||||
if (inLwip)
|
||||
{
|
||||
reprap.GetNetwork()->ReadPacket();
|
||||
ethernet_set_rx_callback(NULL);
|
||||
}
|
||||
else
|
||||
{
|
||||
++inLwip;
|
||||
do {
|
||||
// read all queued packets from the RX buffer
|
||||
} while (ethernet_read());
|
||||
--inLwip;
|
||||
}
|
||||
}
|
||||
|
||||
// Callback functions called by LWIP
|
||||
|
||||
static void conn_err(void *arg, err_t err)
|
||||
|
@ -414,12 +436,19 @@ void Network::Spin()
|
|||
{
|
||||
if (state == NetworkActive)
|
||||
{
|
||||
// Fetch incoming data
|
||||
// ethernet_task() is called twice because the EMAC RX buffers have been increased by dc42's Arduino patch.
|
||||
++inLwip;
|
||||
ethernet_task();
|
||||
ethernet_task();
|
||||
--inLwip;
|
||||
// See if we can read any packets
|
||||
if (readingData)
|
||||
{
|
||||
readingData = false;
|
||||
|
||||
++inLwip;
|
||||
do {
|
||||
// read all queued packets from the RX buffer
|
||||
} while (ethernet_read());
|
||||
--inLwip;
|
||||
|
||||
ethernet_set_rx_callback(&emac_read_packet);
|
||||
}
|
||||
|
||||
// See if we can send anything
|
||||
++inLwip;
|
||||
|
@ -463,11 +492,22 @@ void Network::Spin()
|
|||
httpd_init();
|
||||
ftpd_init();
|
||||
telnetd_init();
|
||||
ethernet_set_rx_callback(&emac_read_packet);
|
||||
state = NetworkActive;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Network::Interrupt()
|
||||
{
|
||||
if (!inLwip)
|
||||
{
|
||||
++inLwip;
|
||||
ethernet_timers_update();
|
||||
--inLwip;
|
||||
}
|
||||
}
|
||||
|
||||
bool Network::InLwip() const
|
||||
{
|
||||
return (inLwip);
|
||||
|
|
|
@ -160,6 +160,7 @@ public:
|
|||
Network();
|
||||
void Init();
|
||||
void Spin();
|
||||
void Interrupt();
|
||||
|
||||
bool InLwip() const;
|
||||
void ReadPacket();
|
||||
|
|
311
Platform.cpp
311
Platform.cpp
|
@ -28,6 +28,8 @@ extern "C" char *sbrk(int i);
|
|||
|
||||
const uint8_t memPattern = 0xA5;
|
||||
|
||||
static volatile uint32_t fanRpmCounter = 0;
|
||||
|
||||
// Arduino initialise and loop functions
|
||||
// Put nothing in these other than calls to the RepRap equivalents
|
||||
|
||||
|
@ -91,7 +93,8 @@ bool PidParameters::operator==(const PidParameters& other) const
|
|||
// Platform class
|
||||
|
||||
Platform::Platform() :
|
||||
tickState(0), fileStructureInitialised(false), active(false), errorCodeBits(0), debugCode(0)
|
||||
tickState(0), fileStructureInitialised(false), active(false), errorCodeBits(0), debugCode(0),
|
||||
messageString(messageStringBuffer, ARRAY_SIZE(messageStringBuffer))
|
||||
{
|
||||
line = new Line();
|
||||
|
||||
|
@ -109,8 +112,8 @@ Platform::Platform() :
|
|||
|
||||
void Platform::Init()
|
||||
{
|
||||
digitalWrite(atxPowerPin, LOW); // ensure ATX power is off by default
|
||||
pinMode(atxPowerPin, OUTPUT);
|
||||
digitalWriteNonDue(atxPowerPin, LOW); // ensure ATX power is off by default
|
||||
pinModeNonDue(atxPowerPin, OUTPUT);
|
||||
|
||||
DueFlashStorage::init();
|
||||
// We really want to use static_assert here, but the ancient version of gcc used by Arduino doesn't support it
|
||||
|
@ -220,6 +223,8 @@ void Platform::Init()
|
|||
standbyTemperatures = STANDBY_TEMPERATURES;
|
||||
activeTemperatures = ACTIVE_TEMPERATURES;
|
||||
coolingFanPin = COOLING_FAN_PIN;
|
||||
coolingFanRpmPin = COOLING_FAN_RPM_PIN;
|
||||
lastRpmResetTime = 0.0;
|
||||
|
||||
webDir = WEB_DIR;
|
||||
gcodeDir = GCODE_DIR;
|
||||
|
@ -234,24 +239,15 @@ void Platform::Init()
|
|||
{
|
||||
if (stepPins[i] >= 0)
|
||||
{
|
||||
if(i == E0_DRIVE || i == E3_DRIVE) // STEP_PINS {14, 25, 5, X2, 41, 39, X4, 49}
|
||||
pinModeNonDue(stepPins[i], OUTPUT);
|
||||
else
|
||||
pinMode(stepPins[i], OUTPUT);
|
||||
pinModeNonDue(stepPins[i], OUTPUT);
|
||||
}
|
||||
if (directionPins[i] >= 0)
|
||||
{
|
||||
if(i == E0_DRIVE) // DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48}
|
||||
pinModeNonDue(directionPins[i], OUTPUT);
|
||||
else
|
||||
pinMode(directionPins[i], OUTPUT);
|
||||
pinModeNonDue(directionPins[i], OUTPUT);
|
||||
}
|
||||
if (enablePins[i] >= 0)
|
||||
{
|
||||
if(i == Z_AXIS || i == E0_DRIVE || i == E2_DRIVE) // ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47}
|
||||
pinModeNonDue(enablePins[i], OUTPUT);
|
||||
else
|
||||
pinMode(enablePins[i], OUTPUT);
|
||||
pinModeNonDue(enablePins[i], OUTPUT);
|
||||
}
|
||||
Disable(i);
|
||||
driveEnabled[i] = false;
|
||||
|
@ -260,13 +256,11 @@ void Platform::Init()
|
|||
{
|
||||
if (lowStopPins[i] >= 0)
|
||||
{
|
||||
pinMode(lowStopPins[i], INPUT);
|
||||
digitalWrite(lowStopPins[i], HIGH); // Turn on pullup
|
||||
pinModeNonDue(lowStopPins[i], INPUT_PULLUP);
|
||||
}
|
||||
if (highStopPins[i] >= 0)
|
||||
{
|
||||
pinMode(highStopPins[i], INPUT);
|
||||
digitalWrite(highStopPins[i], HIGH); // Turn on pullup
|
||||
pinModeNonDue(highStopPins[i], INPUT_PULLUP);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -274,16 +268,8 @@ void Platform::Init()
|
|||
{
|
||||
if (heatOnPins[i] >= 0)
|
||||
{
|
||||
if(i == E0_HEATER || i == E1_HEATER) // HEAT_ON_PINS {6, X5, X7, 7, 8, 9}
|
||||
{
|
||||
digitalWriteNonDue(heatOnPins[i], HIGH); // turn the heater off
|
||||
pinModeNonDue(heatOnPins[i], OUTPUT);
|
||||
}
|
||||
else
|
||||
{
|
||||
digitalWrite(heatOnPins[i], HIGH); // turn the heater off
|
||||
pinMode(heatOnPins[i], OUTPUT);
|
||||
}
|
||||
digitalWriteNonDue(heatOnPins[i], HIGH); // turn the heater off
|
||||
pinModeNonDue(heatOnPins[i], OUTPUT);
|
||||
}
|
||||
analogReadResolution(12);
|
||||
thermistorFilters[i].Init(analogRead(tempSensePins[i]));
|
||||
|
@ -299,8 +285,12 @@ void Platform::Init()
|
|||
|
||||
if (coolingFanPin >= 0)
|
||||
{
|
||||
//pinModeNonDue(coolingFanPin, OUTPUT); //not required as analogwrite does this automatically
|
||||
analogWriteNonDue(coolingFanPin, 255); //inverse logic for Duet v0.6 this turns it off
|
||||
analogWriteNonDue(coolingFanPin, (HEAT_ON == 0) ? 255 : 0, true);
|
||||
}
|
||||
|
||||
if (coolingFanRpmPin >= 0)
|
||||
{
|
||||
pinModeNonDue(coolingFanRpmPin, INPUT_PULLUP);
|
||||
}
|
||||
|
||||
InitialiseInterrupts();
|
||||
|
@ -328,14 +318,14 @@ void Platform::InitZProbe()
|
|||
|
||||
if (nvData.zProbeType == 1 || nvData.zProbeType == 2)
|
||||
{
|
||||
pinMode(zProbeModulationPin, OUTPUT);
|
||||
digitalWrite(zProbeModulationPin, HIGH); // enable the IR LED
|
||||
pinModeNonDue(zProbeModulationPin, OUTPUT);
|
||||
digitalWriteNonDue(zProbeModulationPin, HIGH); // enable the IR LED
|
||||
SetZProbing(false);
|
||||
}
|
||||
else if (nvData.zProbeType == 3)
|
||||
{
|
||||
pinMode(zProbeModulationPin, OUTPUT);
|
||||
digitalWrite(zProbeModulationPin, LOW); // enable the alternate sensor
|
||||
pinModeNonDue(zProbeModulationPin, OUTPUT);
|
||||
digitalWriteNonDue(zProbeModulationPin, LOW); // enable the alternate sensor
|
||||
SetZProbing(false);
|
||||
}
|
||||
}
|
||||
|
@ -629,6 +619,17 @@ void TC3_Handler()
|
|||
reprap.Interrupt();
|
||||
}
|
||||
|
||||
void TC4_Handler()
|
||||
{
|
||||
TC_GetStatus(TC1, 1);
|
||||
reprap.GetNetwork()->Interrupt();
|
||||
}
|
||||
|
||||
void FanInterrupt()
|
||||
{
|
||||
fanRpmCounter++;
|
||||
}
|
||||
|
||||
void Platform::InitialiseInterrupts()
|
||||
{
|
||||
// Timer interrupt for stepper motors
|
||||
|
@ -639,6 +640,20 @@ void Platform::InitialiseInterrupts()
|
|||
TC1 ->TC_CHANNEL[0].TC_IDR = ~TC_IER_CPCS;
|
||||
SetInterrupt(STANDBY_INTERRUPT_RATE);
|
||||
|
||||
// Timer interrupt to keep the networking timers running (called at 8Hz)
|
||||
pmc_enable_periph_clk((uint32_t) TC4_IRQn);
|
||||
TC_Configure(TC1, 1, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK2);
|
||||
uint32_t rc = VARIANT_MCK/8/16; // 8 because we selected TIMER_CLOCK2 above
|
||||
TC_SetRA(TC1, 1, rc/2); // 50% high, 50% low
|
||||
TC_SetRC(TC1, 1, rc);
|
||||
TC_Start(TC1, 1);
|
||||
TC1 ->TC_CHANNEL[1].TC_IER = TC_IER_CPCS;
|
||||
TC1 ->TC_CHANNEL[1].TC_IDR = ~TC_IER_CPCS;
|
||||
NVIC_EnableIRQ(TC4_IRQn);
|
||||
|
||||
// Interrupt for 4-pin PWM fan sense line
|
||||
attachInterrupt(coolingFanRpmPin, FanInterrupt, FALLING);
|
||||
|
||||
// Tick interrupt for ADC conversions
|
||||
tickState = 0;
|
||||
currentHeater = 0;
|
||||
|
@ -649,6 +664,7 @@ void Platform::InitialiseInterrupts()
|
|||
//void Platform::DisableInterrupts()
|
||||
//{
|
||||
// NVIC_DisableIRQ(TC3_IRQn);
|
||||
// NVIC_DisableIRQ(TC4_IRQn);
|
||||
//}
|
||||
|
||||
// Process a 1ms tick interrupt
|
||||
|
@ -701,7 +717,7 @@ void Platform::Tick()
|
|||
StartAdcConversion(heaterAdcChannels[currentHeater]); // read a thermistor
|
||||
if (nvData.zProbeType == 2) // if using a modulated IR sensor
|
||||
{
|
||||
digitalWrite(Z_PROBE_MOD_PIN, LOW); // turn off the IR emitter
|
||||
digitalWriteNonDue(Z_PROBE_MOD_PIN, LOW); // turn off the IR emitter
|
||||
}
|
||||
++tickState;
|
||||
break;
|
||||
|
@ -714,7 +730,7 @@ void Platform::Tick()
|
|||
StartAdcConversion(heaterAdcChannels[currentHeater]); // read a thermistor
|
||||
if (nvData.zProbeType == 2) // if using a modulated IR sensor
|
||||
{
|
||||
digitalWrite(Z_PROBE_MOD_PIN, HIGH); // turn on the IR emitter
|
||||
digitalWriteNonDue(Z_PROBE_MOD_PIN, HIGH); // turn on the IR emitter
|
||||
}
|
||||
tickState = 1;
|
||||
break;
|
||||
|
@ -763,36 +779,27 @@ void Platform::Diagnostics()
|
|||
const char *ramstart = (char *) 0x20070000;
|
||||
const struct mallinfo mi = mallinfo();
|
||||
AppendMessage(BOTH_MESSAGE, "Memory usage:\n\n");
|
||||
scratchString.printf("Program static ram used: %d\n", &_end - ramstart);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
scratchString.printf("Dynamic ram used: %d\n", mi.uordblks);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
scratchString.printf("Recycled dynamic ram: %d\n", mi.fordblks);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
AppendMessage(BOTH_MESSAGE, "Program static ram used: %d\n", &_end - ramstart);
|
||||
AppendMessage(BOTH_MESSAGE, "Dynamic ram used: %d\n", mi.uordblks);
|
||||
AppendMessage(BOTH_MESSAGE, "Recycled dynamic ram: %d\n", mi.fordblks);
|
||||
size_t currentStack, maxStack, neverUsed;
|
||||
GetStackUsage(¤tStack, &maxStack, &neverUsed);
|
||||
scratchString.printf("Current stack ram used: %d\n", currentStack);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
scratchString.printf("Maximum stack ram used: %d\n", maxStack);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
scratchString.printf("Never used ram: %d\n", neverUsed);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
AppendMessage(BOTH_MESSAGE, "Current stack ram used: %d\n", currentStack);
|
||||
AppendMessage(BOTH_MESSAGE, "Maximum stack ram used: %d\n", maxStack);
|
||||
AppendMessage(BOTH_MESSAGE, "Never used ram: %d\n", neverUsed);
|
||||
|
||||
// Show the up time and reason for the last reset
|
||||
const uint32_t now = (uint32_t)Time(); // get up time in seconds
|
||||
const char* resetReasons[8] = { "power up", "backup", "watchdog", "software", "external", "?", "?", "?" };
|
||||
scratchString.printf("Last reset %02d:%02d:%02d ago, cause: %s\n",
|
||||
AppendMessage(BOTH_MESSAGE, "Last reset %02d:%02d:%02d ago, cause: %s\n",
|
||||
(unsigned int)(now/3600), (unsigned int)((now % 3600)/60), (unsigned int)(now % 60),
|
||||
resetReasons[(REG_RSTC_SR & RSTC_SR_RSTTYP_Msk) >> RSTC_SR_RSTTYP_Pos]);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
|
||||
// Show the error code stored at the last software reset
|
||||
scratchString.printf("Last software reset code & available RAM: 0x%04x, %u\n", nvData.resetReason, nvData.neverUsedRam);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
AppendMessage(BOTH_MESSAGE, "Last software reset code & available RAM: 0x%04x, %u\n", nvData.resetReason, nvData.neverUsedRam);
|
||||
|
||||
// Show the current error codes
|
||||
scratchString.printf("Error status: %u\n", errorCodeBits);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
AppendMessage(BOTH_MESSAGE, "Error status: %u\n", errorCodeBits);
|
||||
|
||||
// Show the current probe position heights
|
||||
scratchString.copy("Bed probe heights:");
|
||||
|
@ -812,12 +819,10 @@ void Platform::Diagnostics()
|
|||
++numFreeFiles;
|
||||
}
|
||||
}
|
||||
scratchString.printf("Free file entries: %u\n", numFreeFiles);
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
AppendMessage(BOTH_MESSAGE, "Free file entries: %u\n", numFreeFiles);
|
||||
|
||||
// Show the longest write time
|
||||
scratchString.printf("Longest block write time: %.1fms\n", FileStore::GetAndClearLongestWriteTime());
|
||||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
AppendMessage(BOTH_MESSAGE, "Longest block write time: %.1fms\n", FileStore::GetAndClearLongestWriteTime());
|
||||
|
||||
reprap.Timing();
|
||||
|
||||
|
@ -862,15 +867,14 @@ void Platform::GetStackUsage(size_t* currentStack, size_t* maxStack, size_t* nev
|
|||
if (neverUsed) { *neverUsed = stack_lwm - heapend; }
|
||||
}
|
||||
|
||||
void Platform::ClassReport(char* className, float &lastTime)
|
||||
void Platform::ClassReport(const char* className, float &lastTime)
|
||||
{
|
||||
if (!reprap.Debug())
|
||||
return;
|
||||
if (Time() - lastTime < LONG_TIME)
|
||||
return;
|
||||
lastTime = Time();
|
||||
scratchString.printf("Class %s spinning.\n", className);
|
||||
Message(HOST_MESSAGE, scratchString);
|
||||
Message(HOST_MESSAGE, "Class %s spinning.\n", className);
|
||||
}
|
||||
|
||||
//===========================================================================
|
||||
|
@ -938,24 +942,13 @@ const PidParameters& Platform::GetPidParameters(size_t heater)
|
|||
|
||||
// power is a fraction in [0,1]
|
||||
|
||||
void Platform::SetHeater(size_t heater, const float& power)
|
||||
void Platform::SetHeater(size_t heater, float power)
|
||||
{
|
||||
if (heatOnPins[heater] < 0)
|
||||
return;
|
||||
|
||||
byte p = (byte) (255.0 * min<float>(1.0, max<float>(0.0, power)));
|
||||
if (HEAT_ON == 0)
|
||||
{
|
||||
p = 255 - p;
|
||||
if(heater == E0_HEATER || heater == E1_HEATER) //HEAT_ON_PINS {6, X5, X7, 7, 8, 9}
|
||||
{
|
||||
analogWriteNonDue(heatOnPins[heater], p);
|
||||
}
|
||||
else
|
||||
{
|
||||
analogWrite(heatOnPins[heater], p);
|
||||
}
|
||||
}
|
||||
analogWriteNonDue(heatOnPins[heater], (HEAT_ON == 0) ? 255 - p : p);
|
||||
}
|
||||
|
||||
EndStopHit Platform::Stopped(int8_t drive)
|
||||
|
@ -976,12 +969,12 @@ EndStopHit Platform::Stopped(int8_t drive)
|
|||
|
||||
if (lowStopPins[drive] >= 0)
|
||||
{
|
||||
if (digitalRead(lowStopPins[drive]) == ENDSTOP_HIT)
|
||||
if (digitalReadNonDue(lowStopPins[drive]) == ENDSTOP_HIT)
|
||||
return lowHit;
|
||||
}
|
||||
if (highStopPins[drive] >= 0)
|
||||
{
|
||||
if (digitalRead(highStopPins[drive]) == ENDSTOP_HIT)
|
||||
if (digitalReadNonDue(highStopPins[drive]) == ENDSTOP_HIT)
|
||||
return highHit;
|
||||
}
|
||||
return noStop;
|
||||
|
@ -993,24 +986,14 @@ void Platform::SetDirection(byte drive, bool direction)
|
|||
return;
|
||||
|
||||
bool d = (direction == FORWARDS) ? directions[drive] : !directions[drive];
|
||||
if(drive == E0_DRIVE) //DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48}
|
||||
{
|
||||
digitalWriteNonDue(directionPins[drive], d);
|
||||
}
|
||||
else
|
||||
{
|
||||
digitalWrite(directionPins[drive], d);
|
||||
}
|
||||
digitalWriteNonDue(directionPins[drive], d);
|
||||
}
|
||||
|
||||
void Platform::Disable(byte drive)
|
||||
{
|
||||
if(enablePins[drive] < 0)
|
||||
return;
|
||||
if(drive == Z_AXIS || drive==E0_DRIVE || drive==E2_DRIVE) //ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47}
|
||||
digitalWriteNonDue(enablePins[drive], DISABLE);
|
||||
else
|
||||
digitalWrite(enablePins[drive], DISABLE);
|
||||
digitalWriteNonDue(enablePins[drive], DISABLE);
|
||||
driveEnabled[drive] = false;
|
||||
}
|
||||
|
||||
|
@ -1020,25 +1003,11 @@ void Platform::Step(byte drive)
|
|||
return;
|
||||
if(!driveEnabled[drive] && enablePins[drive] >= 0)
|
||||
{
|
||||
if(drive == Z_AXIS || drive==E0_DRIVE || drive==E2_DRIVE) //ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47}
|
||||
{
|
||||
digitalWriteNonDue(enablePins[drive], ENABLE);
|
||||
}
|
||||
else
|
||||
{
|
||||
digitalWrite(enablePins[drive], ENABLE);
|
||||
}
|
||||
digitalWriteNonDue(enablePins[drive], ENABLE);
|
||||
driveEnabled[drive] = true;
|
||||
}
|
||||
if(drive == E0_DRIVE || drive == E3_DRIVE) //STEP_PINS {14, 25, 5, X2, 41, 39, X4, 49}
|
||||
{
|
||||
digitalWriteNonDue(stepPins[drive], 0);
|
||||
digitalWriteNonDue(stepPins[drive], 1);
|
||||
} else
|
||||
{
|
||||
digitalWrite(stepPins[drive], 0);
|
||||
digitalWrite(stepPins[drive], 1);
|
||||
}
|
||||
digitalWriteNonDue(stepPins[drive], 0);
|
||||
digitalWriteNonDue(stepPins[drive], 1);
|
||||
}
|
||||
|
||||
// current is in mA
|
||||
|
@ -1101,10 +1070,31 @@ void Platform::CoolingFan(float speed)
|
|||
}
|
||||
|
||||
// The cooling fan output pin gets inverted if HEAT_ON == 0
|
||||
analogWriteNonDue(coolingFanPin, (HEAT_ON == 0) ? (255 - p) : p);
|
||||
analogWriteNonDue(coolingFanPin, (HEAT_ON == 0) ? (255 - p) : p, true);
|
||||
}
|
||||
}
|
||||
|
||||
// Get current fan RPM
|
||||
|
||||
float Platform::GetFanRPM()
|
||||
{
|
||||
float now = Time();
|
||||
float diff = now - lastRpmResetTime;
|
||||
|
||||
// Intel's 4-pin PWM fan specifications say we get two pulses per revolution.
|
||||
// That means we get 2 ISR calls per pulse and 4 increments per revolution.
|
||||
float result = (float)fanRpmCounter / (4.0 * diff) * 60.0;
|
||||
|
||||
// Collect some values and reset the counters after a few seconds
|
||||
if (diff > COOLING_FAN_RPM_SAMPLE_TIME)
|
||||
{
|
||||
fanRpmCounter = 0;
|
||||
lastRpmResetTime = now;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
// Interrupts
|
||||
|
||||
void Platform::SetInterrupt(float s) // Seconds
|
||||
|
@ -1154,7 +1144,16 @@ MassStorage* Platform::GetMassStorage()
|
|||
return massStorage;
|
||||
}
|
||||
|
||||
void Platform::Message(char type, const char* message)
|
||||
void Platform::Message(char type, const char* message, ...)
|
||||
{
|
||||
va_list vargs;
|
||||
va_start(vargs, message);
|
||||
messageString.vprintf(message, vargs);
|
||||
va_end(vargs);
|
||||
Message(type, messageString);
|
||||
}
|
||||
|
||||
void Platform::Message(char type, const StringRef& message)
|
||||
{
|
||||
switch(type)
|
||||
{
|
||||
|
@ -1178,17 +1177,17 @@ void Platform::Message(char type, const char* message)
|
|||
line->Write(' ', type == DEBUG_MESSAGE);
|
||||
}
|
||||
}
|
||||
line->Write(message, type == DEBUG_MESSAGE);
|
||||
line->Write(message.Pointer(), type == DEBUG_MESSAGE);
|
||||
break;
|
||||
|
||||
case WEB_MESSAGE:
|
||||
// Message that is to be sent to the web
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message, false);
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), false);
|
||||
break;
|
||||
|
||||
case WEB_ERROR_MESSAGE:
|
||||
// Message that is to be sent to the web - flags an error
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message, true);
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), true);
|
||||
break;
|
||||
|
||||
case BOTH_MESSAGE:
|
||||
|
@ -1200,8 +1199,8 @@ void Platform::Message(char type, const char* message)
|
|||
line->Write(' ');
|
||||
}
|
||||
}
|
||||
line->Write(message);
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message, false);
|
||||
line->Write(message.Pointer());
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), false);
|
||||
break;
|
||||
|
||||
case BOTH_ERROR_MESSAGE:
|
||||
|
@ -1216,13 +1215,22 @@ void Platform::Message(char type, const char* message)
|
|||
line->Write(' ');
|
||||
}
|
||||
}
|
||||
line->Write(message);
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message, true);
|
||||
line->Write(message.Pointer());
|
||||
reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), true);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void Platform::AppendMessage(char type, const char* message)
|
||||
void Platform::AppendMessage(char type, const char* message, ...)
|
||||
{
|
||||
va_list vargs;
|
||||
va_start(vargs, message);
|
||||
messageString.vprintf(message, vargs);
|
||||
va_end(vargs);
|
||||
AppendMessage(type, messageString);
|
||||
}
|
||||
|
||||
void Platform::AppendMessage(char type, const StringRef& message)
|
||||
{
|
||||
switch(type)
|
||||
{
|
||||
|
@ -1247,17 +1255,17 @@ void Platform::AppendMessage(char type, const char* message)
|
|||
line->Write(' ', type == DEBUG_MESSAGE);
|
||||
}
|
||||
}
|
||||
line->Write(message, type == DEBUG_MESSAGE);
|
||||
line->Write(message.Pointer(), type == DEBUG_MESSAGE);
|
||||
break;
|
||||
|
||||
case WEB_MESSAGE:
|
||||
// Message that is to be sent to the web
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message, false);
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), false);
|
||||
break;
|
||||
|
||||
case WEB_ERROR_MESSAGE:
|
||||
// Message that is to be sent to the web - flags an error
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message, true);
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), true);
|
||||
break;
|
||||
|
||||
case BOTH_MESSAGE:
|
||||
|
@ -1269,8 +1277,8 @@ void Platform::AppendMessage(char type, const char* message)
|
|||
line->Write(' ');
|
||||
}
|
||||
}
|
||||
line->Write(message);
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message, false);
|
||||
line->Write(message.Pointer());
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), false);
|
||||
break;
|
||||
|
||||
case BOTH_ERROR_MESSAGE:
|
||||
|
@ -1285,8 +1293,8 @@ void Platform::AppendMessage(char type, const char* message)
|
|||
line->Write(' ');
|
||||
}
|
||||
}
|
||||
line->Write(message);
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message, true);
|
||||
line->Write(message.Pointer());
|
||||
reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), true);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -1294,7 +1302,7 @@ void Platform::AppendMessage(char type, const char* message)
|
|||
|
||||
void Platform::SetAtxPower(bool on)
|
||||
{
|
||||
digitalWrite(atxPowerPin, (on) ? HIGH : LOW);
|
||||
digitalWriteNonDue(atxPowerPin, (on) ? HIGH : LOW);
|
||||
}
|
||||
|
||||
|
||||
|
@ -1503,9 +1511,7 @@ bool MassStorage::Delete(const char* directory, const char* fileName)
|
|||
: fileName;
|
||||
if (f_unlink(location) != FR_OK)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Can't delete file ");
|
||||
platform->Message(HOST_MESSAGE, location);
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_MESSAGE, "Can't delete file %s\n, location");
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -1517,9 +1523,7 @@ bool MassStorage::MakeDirectory(const char *parentDir, const char *dirName)
|
|||
const char* location = platform->GetMassStorage()->CombineName(parentDir, dirName);
|
||||
if (f_mkdir(location) != FR_OK)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Can't create directory ");
|
||||
platform->Message(HOST_MESSAGE, location);
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_MESSAGE, "Can't create directory %s\n", location);
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -1529,9 +1533,7 @@ bool MassStorage::MakeDirectory(const char *directory)
|
|||
{
|
||||
if (f_mkdir(directory) != FR_OK)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Can't create directory ");
|
||||
platform->Message(HOST_MESSAGE, directory);
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_MESSAGE, "Can't create directory %s\n", directory);
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -1542,11 +1544,7 @@ bool MassStorage::Rename(const char *oldFilename, const char *newFilename)
|
|||
{
|
||||
if (f_rename(oldFilename, newFilename) != FR_OK)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Can't rename file or directory ");
|
||||
platform->Message(HOST_MESSAGE, oldFilename);
|
||||
platform->Message(HOST_MESSAGE, " to ");
|
||||
platform->Message(HOST_MESSAGE, newFilename);
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
platform->Message(BOTH_MESSAGE, "Can't rename file or directory %s to %s\n", oldFilename, newFilename);
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -1587,12 +1585,7 @@ bool FileStore::Open(const char* directory, const char* fileName, bool write)
|
|||
FRESULT openReturn = f_open(&file, location, (writing) ? FA_CREATE_ALWAYS | FA_WRITE : FA_OPEN_EXISTING | FA_READ);
|
||||
if (openReturn != FR_OK)
|
||||
{
|
||||
char errString[12]; // don't use scratch_string for this because that may be holding the original filename
|
||||
platform->Message(BOTH_MESSAGE, "Can't open ");
|
||||
platform->AppendMessage(BOTH_MESSAGE, location);
|
||||
platform->AppendMessage(BOTH_MESSAGE, (writing) ? " to write to, error code " : " to read from, error code ");
|
||||
snprintf(errString, ARRAY_SIZE(errString), "%d\n", openReturn);
|
||||
platform->AppendMessage(BOTH_MESSAGE, errString);
|
||||
platform->Message(BOTH_MESSAGE, "Can't open %s to %s, error code %d\n", location, (writing) ? "write" : "read", openReturn);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -1606,7 +1599,7 @@ void FileStore::Duplicate()
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to dup a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to dup a non-open file.\n");
|
||||
return;
|
||||
}
|
||||
++openCount;
|
||||
|
@ -1616,7 +1609,7 @@ bool FileStore::Close()
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to close a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to close a non-open file.\n");
|
||||
return false;
|
||||
}
|
||||
--openCount;
|
||||
|
@ -1640,7 +1633,7 @@ bool FileStore::Seek(unsigned long pos)
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to seek on a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to seek on a non-open file.\n");
|
||||
return false;
|
||||
}
|
||||
if (writing)
|
||||
|
@ -1661,7 +1654,7 @@ unsigned long FileStore::Length()
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to size non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to size non-open file.\n");
|
||||
return 0;
|
||||
}
|
||||
return file.fsize;
|
||||
|
@ -1686,7 +1679,7 @@ bool FileStore::ReadBuffer()
|
|||
FRESULT readStatus = f_read(&file, buf, FILE_BUF_LEN, &lastBufferEntry); // Read a chunk of file
|
||||
if (readStatus)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Error reading file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Error reading file.\n");
|
||||
return false;
|
||||
}
|
||||
bufferPointer = 0;
|
||||
|
@ -1698,7 +1691,7 @@ bool FileStore::Read(char& b)
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to read from a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to read from a non-open file.\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -1728,7 +1721,7 @@ int FileStore::Read(char* extBuf, unsigned int nBytes)
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to read from a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to read from a non-open file.\n");
|
||||
return -1;
|
||||
}
|
||||
bufferPointer = FILE_BUF_LEN; // invalidate the buffer
|
||||
|
@ -1736,7 +1729,7 @@ int FileStore::Read(char* extBuf, unsigned int nBytes)
|
|||
FRESULT readStatus = f_read(&file, extBuf, nBytes, &bytesRead);
|
||||
if (readStatus)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Error reading file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Error reading file.\n");
|
||||
return -1;
|
||||
}
|
||||
return (int)bytesRead;
|
||||
|
@ -1749,7 +1742,7 @@ bool FileStore::WriteBuffer()
|
|||
bool ok = InternalWriteBlock((const char*)buf, bufferPointer);
|
||||
if (!ok)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Error writing file. Disc may be full.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Error writing file. Disc may be full.\n");
|
||||
return false;
|
||||
}
|
||||
bufferPointer = 0;
|
||||
|
@ -1761,7 +1754,7 @@ bool FileStore::Write(char b)
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to write byte to a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to write byte to a non-open file.\n");
|
||||
return false;
|
||||
}
|
||||
buf[bufferPointer] = b;
|
||||
|
@ -1777,7 +1770,7 @@ bool FileStore::Write(const char* b)
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to write string to a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to write string to a non-open file.\n");
|
||||
return false;
|
||||
}
|
||||
int i = 0;
|
||||
|
@ -1796,14 +1789,14 @@ bool FileStore::Write(const char *s, unsigned int len)
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to write block to a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to write block to a non-open file.\n");
|
||||
return false;
|
||||
}
|
||||
if (!WriteBuffer())
|
||||
{
|
||||
return false;
|
||||
}
|
||||
InternalWriteBlock(s, len);
|
||||
return InternalWriteBlock(s, len);
|
||||
}
|
||||
|
||||
bool FileStore::InternalWriteBlock(const char *s, unsigned int len)
|
||||
|
@ -1818,7 +1811,7 @@ bool FileStore::InternalWriteBlock(const char *s, unsigned int len)
|
|||
}
|
||||
if ((writeStatus != FR_OK) || (bytesWritten != len))
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Error writing file. Disc may be full.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Error writing file. Disc may be full.\n");
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -1828,7 +1821,7 @@ bool FileStore::Flush()
|
|||
{
|
||||
if (!inUse)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "Attempt to flush a non-open file.\n");
|
||||
platform->Message(BOTH_MESSAGE, "Attempt to flush a non-open file.\n");
|
||||
return false;
|
||||
}
|
||||
if (!WriteBuffer())
|
||||
|
|
42
Platform.h
42
Platform.h
|
@ -128,7 +128,7 @@ const unsigned int numZProbeReadingsAveraged = 8; // we average this number of r
|
|||
// HEATERS - The bed is assumed to be the at index 0
|
||||
|
||||
#define TEMP_SENSE_PINS {5, 4, 0, 7, 8, 9} // Analogue pin numbers
|
||||
#define HEAT_ON_PINS {6, X5, X7, 7, 8, 9} //pin D38 is PWM capable but not an Arduino PWM pin - //FIXME TEST if E1 PWM works as D38
|
||||
#define HEAT_ON_PINS {6, X5, X7, 7, 8, 9} //pin D38 is PWM capable but not an Arduino PWM pin
|
||||
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
|
||||
// Hot end thermistor: http://www.digikey.co.uk/product-search/en?x=20&y=11&KeyWords=480-3137-ND
|
||||
const float defaultThermistorBetas[HEATERS] = {3988.0, 4138.0, 4138.0, 4138.0, 4138.0, 4138.0}; // Bed thermistor: B57861S104F40; Extruder thermistor: RS 198-961
|
||||
|
@ -171,7 +171,9 @@ const float defaultPidMax[HEATERS] = {255, 180, 180, 180, 180, 180}; // maximu
|
|||
|
||||
#define STANDBY_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO} // We specify one for the bed, though it's not needed
|
||||
#define ACTIVE_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO}
|
||||
#define COOLING_FAN_PIN X6 //pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
|
||||
#define COOLING_FAN_PIN X6 // pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
|
||||
#define COOLING_FAN_RPM_PIN 36 // pin PC4
|
||||
#define COOLING_FAN_RPM_SAMPLE_TIME 2.0 // Time to wait before resetting the internal fan RPM stats
|
||||
#define HEAT_ON 0 // 0 for inverted heater (e.g. Duet v0.6) 1 for not (e.g. Duet v0.4)
|
||||
|
||||
// For the theory behind ADC oversampling, see http://www.atmel.com/Images/doc8003.pdf
|
||||
|
@ -218,6 +220,8 @@ const int atxPowerPin = 12; // Arduino Due pin number that controls the ATX
|
|||
const uint16_t lineInBufsize = 256; // use a power of 2 for good performance
|
||||
const uint16_t lineOutBufSize = 2048; // ideally this should be large enough to hold the results of an M503 command,
|
||||
// but could be reduced if we ever need the memory
|
||||
const size_t messageStringLength = 1024; // max length of a message chunk sent via Message or AppendMessage
|
||||
|
||||
/****************************************************************************************************/
|
||||
|
||||
enum EndStopHit
|
||||
|
@ -541,12 +545,12 @@ public:
|
|||
// it has just been restarted; it can do this by executing an actual restart if you like, but beware the
|
||||
// loop of death...
|
||||
void Spin(); // This gets called in the main loop and should do any housekeeping needed
|
||||
void Exit(); // Shut down tidily. Calling Init after calling this should reset to the beginning
|
||||
void Exit(); // Shut down tidily. Calling Init after calling this should reset to the beginning
|
||||
Compatibility Emulating() const;
|
||||
void SetEmulating(Compatibility c);
|
||||
void Diagnostics();
|
||||
void DiagnosticTest(int d);
|
||||
void ClassReport(char* className, float &lastTime); // Called on return to check everything's live.
|
||||
void ClassReport(const char* className, float &lastTime); // Called on return to check everything's live.
|
||||
void RecordError(ErrorCode ec) { errorCodeBits |= ec; }
|
||||
void SoftwareReset(uint16_t reason);
|
||||
void SetAtxPower(bool on);
|
||||
|
@ -574,18 +578,18 @@ public:
|
|||
|
||||
MassStorage* GetMassStorage();
|
||||
FileStore* GetFileStore(const char* directory, const char* fileName, bool write);
|
||||
const char* GetWebDir() const; // Where the htm etc files are
|
||||
const char* GetGCodeDir() const; // Where the gcodes are
|
||||
const char* GetSysDir() const; // Where the system files are
|
||||
const char* GetTempDir() const; // Where temporary files are
|
||||
const char* GetWebDir() const; // Where the htm etc files are
|
||||
const char* GetGCodeDir() const; // Where the gcodes are
|
||||
const char* GetSysDir() const; // Where the system files are
|
||||
const char* GetTempDir() const; // Where temporary files are
|
||||
const char* GetConfigFile() const; // Where the configuration is stored (in the system dir).
|
||||
|
||||
void Message(char type, const 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.
|
||||
void Message(char type, const StringRef& message) { return Message(type, message.Pointer()); }
|
||||
void AppendMessage(char type, const 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.
|
||||
void AppendMessage(char type, const StringRef& message) { return AppendMessage(type, message.Pointer()); }
|
||||
void Message(char type, const 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.
|
||||
void Message(char type, const StringRef& message);
|
||||
void AppendMessage(char type, const 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.
|
||||
void AppendMessage(char type, const StringRef& message);
|
||||
void PushMessageIndent();
|
||||
void PopMessageIndent();
|
||||
|
||||
|
@ -643,10 +647,11 @@ public:
|
|||
// Heat and temperature
|
||||
|
||||
float GetTemperature(size_t heater) const; // Result is in degrees Celsius
|
||||
void SetHeater(size_t heater, const float& power); // power is a fraction in [0,1]
|
||||
void SetHeater(size_t heater, float power); // power is a fraction in [0,1]
|
||||
float HeatSampleTime() const;
|
||||
void SetHeatSampleTime(float st);
|
||||
void CoolingFan(float speed);
|
||||
float GetFanRPM();
|
||||
void SetPidParameters(size_t heater, const PidParameters& params);
|
||||
const PidParameters& GetPidParameters(size_t heater);
|
||||
|
||||
|
@ -705,7 +710,7 @@ private:
|
|||
int8_t directionPins[DRIVES];
|
||||
int8_t enablePins[DRIVES];
|
||||
bool disableDrives[DRIVES];
|
||||
bool driveEnabled[DRIVES];
|
||||
volatile bool driveEnabled[DRIVES];
|
||||
bool directions[DRIVES];
|
||||
int8_t lowStopPins[DRIVES];
|
||||
int8_t highStopPins[DRIVES];
|
||||
|
@ -750,6 +755,8 @@ private:
|
|||
float standbyTemperatures[HEATERS];
|
||||
float activeTemperatures[HEATERS];
|
||||
int8_t coolingFanPin;
|
||||
int8_t coolingFanRpmPin;
|
||||
float lastRpmResetTime;
|
||||
|
||||
// Serial/USB
|
||||
|
||||
|
@ -779,6 +786,9 @@ private:
|
|||
static uint16_t GetAdcReading(adc_channel_num_t chan);
|
||||
static void StartAdcConversion(adc_channel_num_t chan);
|
||||
static adc_channel_num_t PinToAdcChannel(int pin);
|
||||
|
||||
char messageStringBuffer[messageStringLength];
|
||||
StringRef messageString;
|
||||
};
|
||||
|
||||
// Small class to hold an open file and data relating to it.
|
||||
|
|
BIN
Release/RepRapFirmware-078p-dc42.bin
Normal file
BIN
Release/RepRapFirmware-078p-dc42.bin
Normal file
Binary file not shown.
|
@ -189,11 +189,10 @@ void RepRap::Init()
|
|||
currentTool = NULL;
|
||||
const uint32_t wdtTicks = 256; // number of watchdog ticks @ 32768Hz/128 before the watchdog times out (max 4095)
|
||||
WDT_Enable(WDT, (wdtTicks << WDT_MR_WDV_Pos) | (wdtTicks << WDT_MR_WDD_Pos) | WDT_MR_WDRSTEN); // enable watchdog, reset the mcu if it times out
|
||||
coldExtrude = true; // DC42 changed default to true for compatibility because for now we are aiming for copatibility with RRP 0.78
|
||||
coldExtrude = true; // DC42 changed default to true for compatibility because for now we are aiming for compatibility with RRP 0.78
|
||||
active = true; // must do this before we start the network, else the watchdog may time out
|
||||
|
||||
scratchString.printf("%s Version %s dated %s\n", NAME, VERSION, DATE);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(HOST_MESSAGE, "%s Version %s dated %s\n", NAME, VERSION, DATE);
|
||||
|
||||
platform->Message(HOST_MESSAGE, ".\n\nExecuting ");
|
||||
platform->Message(HOST_MESSAGE, platform->GetConfigFile());
|
||||
|
@ -222,14 +221,10 @@ void RepRap::Init()
|
|||
}
|
||||
}
|
||||
|
||||
//while(gCodes->RunConfigurationGCodes()); // Wait till the file is finished
|
||||
|
||||
platform->Message(HOST_MESSAGE, "\nStarting network...\n");
|
||||
network->Init(); // Need to do this here, as the configuration GCodes may set IP address etc.
|
||||
|
||||
platform->Message(HOST_MESSAGE, "\n");
|
||||
scratchString.printf("%s is up and running.\n", NAME);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(HOST_MESSAGE, "\n%s is up and running.\n", NAME);
|
||||
fastLoop = FLT_MAX;
|
||||
slowLoop = 0.0;
|
||||
lastTime = platform->Time();
|
||||
|
@ -295,8 +290,7 @@ void RepRap::Spin()
|
|||
|
||||
void RepRap::Timing()
|
||||
{
|
||||
scratchString.printf("Slowest main loop (seconds): %f; fastest: %f\n", slowLoop, fastLoop);
|
||||
platform->AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
platform->AppendMessage(BOTH_MESSAGE, "Slowest main loop (seconds): %f; fastest: %f\n", slowLoop, fastLoop);
|
||||
fastLoop = FLT_MAX;
|
||||
slowLoop = 0.0;
|
||||
}
|
||||
|
@ -425,8 +419,7 @@ void RepRap::StandbyTool(int toolNumber)
|
|||
tool = tool->Next();
|
||||
}
|
||||
|
||||
scratchString.printf("Attempt to standby a non-existent tool: %d.\n", toolNumber);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(HOST_MESSAGE, "Attempt to standby a non-existent tool: %d.\n", toolNumber);
|
||||
}
|
||||
|
||||
Tool* RepRap::GetTool(int toolNumber)
|
||||
|
@ -456,8 +449,7 @@ void RepRap::SetToolVariables(int toolNumber, float* standbyTemperatures, float*
|
|||
tool = tool->Next();
|
||||
}
|
||||
|
||||
scratchString.printf("Attempt to set variables for a non-existent tool: %d.\n", toolNumber);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
platform->Message(HOST_MESSAGE, "Attempt to set variables for a non-existent tool: %d.\n", toolNumber);
|
||||
}
|
||||
|
||||
|
||||
|
@ -550,7 +542,7 @@ size_t StringRef::cat(const char* src)
|
|||
|
||||
// Utilities and storage not part of any class
|
||||
|
||||
static char scratchStringBuffer[STRING_LENGTH];
|
||||
static char scratchStringBuffer[200]; // this is now used only for short messages
|
||||
StringRef scratchString(scratchStringBuffer, ARRAY_SIZE(scratchStringBuffer));
|
||||
|
||||
// For debug use
|
||||
|
|
|
@ -324,7 +324,7 @@ void Webserver::ProcessGcode(const char* gc)
|
|||
printStartTime = platform->Time();
|
||||
strncpy(fileBeingPrinted, &gc[4], ARRAY_SIZE(fileBeingPrinted));
|
||||
fileBeingPrinted[ARRAY_UPB(fileBeingPrinted)] = 0;
|
||||
reprap.GetGCodes()->QueueFileToPrint(&gc[4]);
|
||||
reprap.GetGCodes()->QueueFileToPrint(fileBeingPrinted);
|
||||
}
|
||||
else if (StringStartsWith(gc, "M112") && !isdigit(gc[4])) // emergency stop
|
||||
{
|
||||
|
@ -523,7 +523,7 @@ void Webserver::MessageStringToWebInterface(const char *s, bool error)
|
|||
}
|
||||
else
|
||||
{
|
||||
gcodeReply.printf("%s", s);
|
||||
gcodeReply.copy(s);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -794,17 +794,13 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
|
|||
jsonResponseBuffer[ARRAY_UPB(jsonResponseBuffer)] = 0;
|
||||
if (webDebug)
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "JSON response: ");
|
||||
platform->Message(HOST_MESSAGE, jsonResponseBuffer);
|
||||
platform->Message(HOST_MESSAGE, " queued\n");
|
||||
platform->Message(HOST_MESSAGE, "JSON response: %s queued\n", jsonResponseBuffer);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
jsonResponseBuffer[0] = 0;
|
||||
platform->Message(HOST_MESSAGE, "KnockOut request: ");
|
||||
platform->Message(HOST_MESSAGE, command);
|
||||
platform->Message(HOST_MESSAGE, " not recognised\n");
|
||||
platform->Message(HOST_MESSAGE, "KnockOut request: %s not recognised\n", command);
|
||||
}
|
||||
|
||||
if (mayKeepOpen)
|
||||
|
@ -875,7 +871,7 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, StringRef&
|
|||
else if (StringEquals(request, "upload_cancel"))
|
||||
{
|
||||
CancelUpload();
|
||||
response.printf("{\"err\":%d}", 0);
|
||||
response.copy("{\"err\":0}");
|
||||
}
|
||||
else if (StringEquals(request, "delete") && StringEquals(key, "name"))
|
||||
{
|
||||
|
@ -933,7 +929,7 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, StringRef&
|
|||
}
|
||||
else
|
||||
{
|
||||
response.printf("{\"err\":1}");
|
||||
response.copy("{\"err\":1}");
|
||||
}
|
||||
}
|
||||
else if (reprap.GetGCodes()->PrintingAFile() && webserver->fileInfoDetected)
|
||||
|
@ -964,7 +960,7 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, StringRef&
|
|||
}
|
||||
else if (StringEquals(request, "name"))
|
||||
{
|
||||
response.printf("{\"myName\":\"");
|
||||
response.copy("{\"myName\":\"");
|
||||
size_t j = response.strlen();
|
||||
const char *myName = webserver->GetName();
|
||||
for (size_t i = 0; i < SHORT_STRING_LENGTH; ++i)
|
||||
|
@ -1136,6 +1132,9 @@ void Webserver::HttpInterpreter::GetStatusResponse(StringRef& response, uint8_t
|
|||
break;
|
||||
}
|
||||
|
||||
// Send fan RPM value
|
||||
response.catf(",\"fanRPM\":%u", (unsigned int)platform->GetFanRPM());
|
||||
|
||||
// Send the amount of buffer space available for gcodes
|
||||
response.catf(",\"buff\":%u", webserver->GetGcodeBufferSpace());
|
||||
|
||||
|
@ -1723,8 +1722,7 @@ bool Webserver::FtpInterpreter::CharFromClient(char c)
|
|||
|
||||
if (DebugEnabled())
|
||||
{
|
||||
scratchString.printf("FtpInterpreter::ProcessLine called with state %d:\n%s\n", state, clientMessage);
|
||||
platform->Message(DEBUG_MESSAGE, scratchString);
|
||||
platform->Message(DEBUG_MESSAGE, "FtpInterpreter::ProcessLine called with state %d:\n%s\n", state, clientMessage);
|
||||
}
|
||||
|
||||
if (clientPointer > 1) // only process a new line if we actually received data
|
||||
|
@ -2482,6 +2480,8 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi
|
|||
const size_t overlap = 100;
|
||||
char buf[readSize + overlap + 1]; // need the +1 so we can add a null terminator
|
||||
bool foundLayerHeight = false;
|
||||
unsigned int filamentsFound = 0, nFilaments;
|
||||
float filaments[DRIVES - AXES];
|
||||
|
||||
// Get slic3r settings by reading from the start of the file. We only read the first 1K or so, everything we are looking for should be there.
|
||||
{
|
||||
|
@ -2491,6 +2491,17 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi
|
|||
{
|
||||
buf[sizeToRead] = 0;
|
||||
|
||||
// Search for filament usage (Cura puts it at the beginning of a G-code file)
|
||||
nFilaments = FindFilamentUsed(buf, sizeToRead, filaments, DRIVES - AXES);
|
||||
if (nFilaments != 0 && nFilaments >= filamentsFound)
|
||||
{
|
||||
filamentsFound = min<unsigned int>(nFilaments, info.numFilaments);
|
||||
for (unsigned int i = 0; i < filamentsFound; ++i)
|
||||
{
|
||||
info.filamentNeeded[i] = filaments[i];
|
||||
}
|
||||
}
|
||||
|
||||
// Look for layer height
|
||||
foundLayerHeight = FindLayerHeight(buf, sizeToRead, info.layerHeight);
|
||||
|
||||
|
@ -2524,6 +2535,7 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi
|
|||
|
||||
// Now get the object height and filament used by reading the end of the file
|
||||
{
|
||||
bool searchForFilaments = (filamentsFound == 0);
|
||||
size_t sizeToRead;
|
||||
if (info.fileSize <= readSize + overlap)
|
||||
{
|
||||
|
@ -2539,7 +2551,6 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi
|
|||
}
|
||||
unsigned long seekPos = info.fileSize - sizeToRead; // read on a 512b boundary
|
||||
size_t sizeToScan = sizeToRead;
|
||||
unsigned int filamentsFound = 0;
|
||||
for (;;)
|
||||
{
|
||||
if (!f->Seek(seekPos))
|
||||
|
@ -2554,14 +2565,16 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi
|
|||
buf[sizeToScan] = 0; // add a null terminator
|
||||
|
||||
// Search for filament used
|
||||
float filaments[DRIVES - AXES];
|
||||
unsigned int nFilaments = FindFilamentUsed(buf, sizeToScan, filaments, DRIVES - AXES);
|
||||
if (nFilaments != 0 && nFilaments >= filamentsFound)
|
||||
if (searchForFilaments)
|
||||
{
|
||||
filamentsFound = min<unsigned int>(nFilaments, info.numFilaments);
|
||||
for (unsigned int i = 0; i < filamentsFound; ++i)
|
||||
nFilaments = FindFilamentUsed(buf, sizeToScan, filaments, DRIVES - AXES);
|
||||
if (nFilaments != 0 && nFilaments >= filamentsFound)
|
||||
{
|
||||
info.filamentNeeded[i] = filaments[i];
|
||||
filamentsFound = min<unsigned int>(nFilaments, info.numFilaments);
|
||||
for (unsigned int i = 0; i < filamentsFound; ++i)
|
||||
{
|
||||
info.filamentNeeded[i] = filaments[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -47,7 +47,6 @@
|
|||
#include "ethernet_sam.h"
|
||||
//#include "emac.h"
|
||||
#include "ethernet_phy.h"
|
||||
#include "timer_mgt_sam.h"
|
||||
//#include "sysclk.h"
|
||||
/* lwIP includes */
|
||||
#include "lwip/src/include/lwip/sys.h"
|
||||
|
@ -69,7 +68,7 @@
|
|||
#include "lwip/src/include/netif/etharp.h"
|
||||
#include "lwip/src/sam/include/netif/ethernetif.h"
|
||||
|
||||
#include "lwip_test.h"
|
||||
#include "emac.h"
|
||||
|
||||
extern void RepRapNetworkMessage(const char*);
|
||||
|
||||
|
@ -86,7 +85,7 @@ bool status_link_up()
|
|||
//*****************************AB
|
||||
|
||||
|
||||
struct netif* GetConfiguration()
|
||||
struct netif* ethernet_get_configuration()
|
||||
{
|
||||
return &gs_net_if;
|
||||
}
|
||||
|
@ -119,13 +118,13 @@ static timers_info_t gs_timers_table[] = {
|
|||
/**
|
||||
* \brief Process timing functions.
|
||||
*/
|
||||
static void timers_update(void)
|
||||
void ethernet_timers_update(void)
|
||||
{
|
||||
static uint32_t ul_last_time;
|
||||
uint32_t ul_cur_time, ul_time_diff, ul_idx_timer;
|
||||
timers_info_t *p_tmr_inf;
|
||||
|
||||
ul_cur_time = sys_get_ms();
|
||||
ul_cur_time = millis();
|
||||
ul_time_diff = ul_cur_time - ul_last_time; // we're using unsigned arithmetic, so this handles wrap around
|
||||
|
||||
if (ul_time_diff) {
|
||||
|
@ -176,7 +175,7 @@ static void ethernet_configure_interface(unsigned char ipAddress[], unsigned cha
|
|||
netif_set_default(&gs_net_if);
|
||||
|
||||
/* Setup callback function for netif status change */
|
||||
netif_set_status_callback(&gs_net_if, status_callback);
|
||||
netif_set_status_callback(&gs_net_if, ethernet_status_callback);
|
||||
|
||||
/* Bring it up */
|
||||
if (x_ip_addr.addr == 0)
|
||||
|
@ -215,9 +214,6 @@ void start_ethernet(const unsigned char ipAddress[], const unsigned char netMask
|
|||
{
|
||||
/* Set hw and IP parameters, initialize MAC too */
|
||||
ethernet_configure_interface(ipAddress, netMask, gateWay);
|
||||
|
||||
/* Init timer service */
|
||||
sys_init_timing();
|
||||
}
|
||||
|
||||
|
||||
|
@ -228,7 +224,7 @@ void start_ethernet(const unsigned char ipAddress[], const unsigned char netMask
|
|||
*
|
||||
* \param netif Instance to network interface.
|
||||
*/
|
||||
void status_callback(struct netif *netif)
|
||||
void ethernet_status_callback(struct netif *netif)
|
||||
{
|
||||
char c_mess[20]; // 15 for IP address, 1 for \n, 1 for null, so 3 spare
|
||||
if (netif_is_up(netif))
|
||||
|
@ -250,15 +246,29 @@ void status_callback(struct netif *netif)
|
|||
/**0
|
||||
* \brief Manage the Ethernet packets, if any received process them.
|
||||
* After processing any packets, manage the lwIP timers.
|
||||
*
|
||||
* \return Returns true if data has been processed.
|
||||
*/
|
||||
//int HttpSend();
|
||||
|
||||
void ethernet_task(void)
|
||||
bool ethernet_read(void)
|
||||
{
|
||||
//HttpSend();
|
||||
/* Run polling tasks */
|
||||
ethernetif_input(&gs_net_if);
|
||||
bool data_read = ethernetif_input(&gs_net_if);
|
||||
|
||||
/* Run periodic tasks */
|
||||
timers_update();
|
||||
ethernet_timers_update();
|
||||
|
||||
return data_read;
|
||||
}
|
||||
|
||||
/*
|
||||
* \brief Sets the EMAC RX callback. It will be called when a new packet
|
||||
* can be processed and should be called with a NULL parameter inside
|
||||
* the actual callback.
|
||||
*
|
||||
* \param callback The callback to be called when a new packet is ready
|
||||
*/
|
||||
void ethernet_set_rx_callback(emac_dev_tx_cb_t callback)
|
||||
{
|
||||
|
||||
ethernetif_set_rx_callback(callback);
|
||||
}
|
||||
|
|
|
@ -66,9 +66,9 @@ void init_ethernet(void);
|
|||
bool establish_ethernet_link(void);
|
||||
void start_ethernet(const unsigned char ipAddress[], const unsigned char netMask[], const unsigned char gateWay[]);
|
||||
|
||||
struct netif* GetConfiguration();
|
||||
struct netif* ethernet_get_configuration();
|
||||
|
||||
static void timers_update(void);
|
||||
void ethernet_timers_update(void);
|
||||
|
||||
/**
|
||||
* \brief Status callback used to print address given by DHCP.
|
||||
|
@ -76,13 +76,23 @@ static void timers_update(void);
|
|||
* \param netif Instance to network interface.
|
||||
*
|
||||
*/
|
||||
void status_callback(struct netif *netif);
|
||||
void ethernet_status_callback(struct netif *netif);
|
||||
|
||||
/**
|
||||
* \brief Manage the ethernet packets, if any received process them.
|
||||
*
|
||||
* \return Returns true if data has been processed.
|
||||
*/
|
||||
void ethernet_task(void);
|
||||
bool ethernet_read(void);
|
||||
|
||||
/*
|
||||
* \brief Sets the EMAC RX callback. It will be called when a new packet
|
||||
* can be processed and should be called with a NULL parameter inside
|
||||
* the actual callback.
|
||||
*
|
||||
* \param callback The callback to be called when a new packet is ready
|
||||
*/
|
||||
void ethernet_set_rx_callback(emac_dev_tx_cb_t callback);
|
||||
|
||||
/// @cond 0
|
||||
/**INDENT-OFF**/
|
||||
|
|
|
@ -1,147 +0,0 @@
|
|||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Timer management for lwIP example.
|
||||
*
|
||||
* Copyright (c) 2012 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
|
||||
//#include "board.h"
|
||||
#include "timer_mgt_sam.h"
|
||||
#include "include/tc.h"
|
||||
#include "include/pmc.h"
|
||||
//#include "sysclk.h"
|
||||
#include "lwip/src/include/lwip/sys.h"
|
||||
#include "lwip_test.h"
|
||||
|
||||
volatile int ledState;
|
||||
/** Clock tick count */
|
||||
static volatile uint32_t gs_ul_clk_tick;
|
||||
|
||||
/**
|
||||
* Interrupt handler for TC0 interrupt.
|
||||
*/
|
||||
//void TC0_Handler(void)
|
||||
//{
|
||||
/* Remove warnings */
|
||||
// volatile uint32_t ul_dummy;
|
||||
|
||||
/* Clear status bit to acknowledge interrupt */
|
||||
// ul_dummy = TC0->TC_CHANNEL[0].TC_SR;
|
||||
|
||||
/* Increase tick */
|
||||
// gs_ul_clk_tick++;
|
||||
//}
|
||||
|
||||
void TC4_Handler()
|
||||
{
|
||||
// You must do TC_GetStatus to "accept" interrupt
|
||||
// As parameters use the first two parameters used in startTimer (TC1, 0 in this case)
|
||||
TC_GetStatus(TC1, 1);
|
||||
|
||||
/* Increase tick */
|
||||
gs_ul_clk_tick++;
|
||||
|
||||
ledState = !ledState;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Initialize for timing operation.
|
||||
*/
|
||||
void sys_init_timing(void)
|
||||
{
|
||||
uint32_t ul_div;
|
||||
uint32_t ul_tcclks;
|
||||
|
||||
/* Clear tick value */
|
||||
gs_ul_clk_tick = 0;
|
||||
|
||||
startTimer(TC1,1,TC4_IRQn,4);
|
||||
|
||||
}
|
||||
// Start timer. Parameters are:
|
||||
|
||||
// TC1 : timer counter. Can be TC0, TC1 or TC2
|
||||
// 0 : channel. Can be 0, 1 or 2
|
||||
// TC3_IRQn: irq number. See table.
|
||||
// 40 : frequency (in Hz)
|
||||
// The interrupt service routine is TC3_Handler. See table.
|
||||
void startTimer(Tc *tc, uint32_t channel, IRQn_Type irq, uint32_t frequency) {
|
||||
pmc_set_writeprotect(false);
|
||||
pmc_enable_periph_clk((uint32_t)irq);
|
||||
TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK4);
|
||||
uint32_t rc = VARIANT_MCK/128/frequency; //128 because we selected TIMER_CLOCK4 above
|
||||
TC_SetRA(tc, channel, rc/2); //50% high, 50% low
|
||||
TC_SetRC(tc, channel, rc);
|
||||
TC_Start(tc, channel);
|
||||
tc->TC_CHANNEL[channel].TC_IER=TC_IER_CPCS;
|
||||
tc->TC_CHANNEL[channel].TC_IDR=~TC_IER_CPCS;
|
||||
NVIC_EnableIRQ(irq);
|
||||
}
|
||||
// Paramters table:
|
||||
// TC0, 0, TC0_IRQn => TC0_Handler()
|
||||
// TC0, 1, TC1_IRQn => TC1_Handler()
|
||||
// TC0, 2, TC2_IRQn => TC2_Handler()
|
||||
// TC1, 0, TC3_IRQn => TC3_Handler()
|
||||
// TC1, 1, TC4_IRQn => TC4_Handler()
|
||||
// TC1, 2, TC5_IRQn => TC5_Handler()
|
||||
// TC2, 0, TC6_IRQn => TC6_Handler()
|
||||
// TC2, 1, TC7_IRQn => TC7_Handler()
|
||||
// TC2, 2, TC8_IRQn => TC8_Handler()
|
||||
|
||||
|
||||
/**
|
||||
* \brief Read for clock time (ms).
|
||||
*/
|
||||
uint32_t sys_get_ms(void)
|
||||
{
|
||||
return gs_ul_clk_tick;
|
||||
}
|
||||
|
||||
#if (THIRDPARTY_LWIP_VERSION != 132)
|
||||
|
||||
/* See lwip/sys.h for more information
|
||||
Returns number of milliseconds expired
|
||||
since lwip is initialized
|
||||
*/
|
||||
u32_t sys_now(void)
|
||||
{
|
||||
return (sys_get_ms());
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,57 +0,0 @@
|
|||
/**
|
||||
* \file
|
||||
*
|
||||
* \brief Timer management definitions for lwIP example.
|
||||
*
|
||||
* Copyright (c) 2012 Atmel Corporation. All rights reserved.
|
||||
*
|
||||
* \asf_license_start
|
||||
*
|
||||
* \page License
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. The name of Atmel may not be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* 4. This software may only be redistributed and used in connection with an
|
||||
* Atmel microcontroller product.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
|
||||
* EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR
|
||||
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
* \asf_license_stop
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef TIMER_MGT_SAM_H_INCLUDED
|
||||
#define TIMER_MGT_SAM_H_INCLUDED
|
||||
|
||||
#include "Arduino.h"
|
||||
|
||||
#define CLOCK_CONF_SECOND 1000
|
||||
|
||||
void sys_init_timing(void);
|
||||
extern uint32_t sys_get_ms(void);
|
||||
void startTimer(Tc *tc, uint32_t channel, IRQn_Type irq, uint32_t frequency);
|
||||
|
||||
extern volatile int ledState;
|
||||
|
||||
#endif /* TIMER_MGT_SAM_H_INCLUDED */
|
Reference in a new issue