Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDavid Crocker <dcrocker@eschertech.com>2018-07-16 21:16:48 +0300
committerDavid Crocker <dcrocker@eschertech.com>2018-07-16 21:16:48 +0300
commitbec6793f62095a3a180affa463b6e0715868bd68 (patch)
tree2ea09ab1b0a87bc825fcd0ef6d0429667234c1f6
parent2c22c281c914b007af66cca5cc74fca0d85bac3d (diff)
More work on PCCB support
Support TMC22xx drivers with independent UARTs Support more thermistors than heaters Support configurations with no aux port Support multiple fan tacho inputs (move tacho support to a separate class) Corrected error in tacho RPM calculation
-rw-r--r--.cproject12
-rw-r--r--src/Alligator/Pins_Alligator.h28
-rw-r--r--src/Duet/Pins_Duet.h8
-rw-r--r--src/DuetM/Pins_DuetM.h22
-rw-r--r--src/DuetNG/Pins_DuetNG.h8
-rw-r--r--src/Fans/Fan.cpp (renamed from src/Fan.cpp)0
-rw-r--r--src/Fans/Fan.h (renamed from src/Fan.h)0
-rw-r--r--src/Fans/Tacho.cpp53
-rw-r--r--src/Fans/Tacho.h32
-rw-r--r--src/GCodes/GCodes.cpp38
-rw-r--r--src/GCodes/GCodes.h14
-rw-r--r--src/GCodes/GCodes2.cpp37
-rw-r--r--src/Heating/Sensors/TemperatureSensor.cpp4
-rw-r--r--src/Pccb/Pins_Pccb.h21
-rw-r--r--src/Platform.cpp109
-rw-r--r--src/Platform.h32
-rw-r--r--src/RADDS/Pins_RADDS.h29
-rw-r--r--src/RepRap.cpp46
-rw-r--r--src/SAME70_TEST/Pins_SAME70_TEST.h14
-rw-r--r--src/StepperDrivers/TMC22xx/TMC22xx.cpp186
-rw-r--r--src/StepperDrivers/TMC2660/TMC2660.cpp2
-rw-r--r--src/StepperDrivers/TMC2660/TMC2660.h2
-rw-r--r--src/Version.h2
23 files changed, 480 insertions, 219 deletions
diff --git a/.cproject b/.cproject
index 2256c371..d042dbc4 100644
--- a/.cproject
+++ b/.cproject
@@ -20,7 +20,7 @@
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
- <configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850" name="Duet085" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}.bin">
+ <configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850" name="Duet085" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850." name="/" resourcePath="">
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.947353540" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
<option id="cdt.managedbuild.option.gnu.cross.path.1742191832" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/>
@@ -135,7 +135,7 @@
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
- <configuration artifactExtension="elf" artifactName="${ProjName}-RADDS" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1027429289" name="RADDS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}-RADDS.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}-RADDS.bin">
+ <configuration artifactExtension="elf" artifactName="${ProjName}-RADDS" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1027429289" name="RADDS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1027429289." name="/" resourcePath="">
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.1973208555" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
<option id="cdt.managedbuild.option.gnu.cross.path.2092504710" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/>
@@ -245,7 +245,7 @@
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
- <configuration artifactExtension="elf" artifactName="${ProjName}-Alligator" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1745168887" name="Alligator" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}-Alligator.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}-Alligator.bin">
+ <configuration artifactExtension="elf" artifactName="${ProjName}-Alligator" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1745168887" name="Alligator" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1745168887." name="/" resourcePath="">
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.623324432" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
<option id="cdt.managedbuild.option.gnu.cross.path.645044151" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/>
@@ -366,7 +366,7 @@
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
- <configuration artifactExtension="elf" artifactName="Duet2CombinedFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622" name="Duet2_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/Duet2CombinedFirmware.elf ${workspace_loc:/${ProjName}/${ConfigName}}/Duet2CombinedFirmware.bin">
+ <configuration artifactExtension="elf" artifactName="Duet2CombinedFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622" name="Duet2_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622." name="/" resourcePath="">
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.435431950" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
<option id="cdt.managedbuild.option.gnu.cross.path.1881231799" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/>
@@ -486,7 +486,7 @@
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
- <configuration artifactExtension="elf" artifactName="DuetMaestroFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786" name="DuetM_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/DuetMaestroFirmware.elf ${workspace_loc:/${ProjName}/${ConfigName}}/DuetMaestroFirmware.bin">
+ <configuration artifactExtension="elf" artifactName="DuetMaestroFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786" name="DuetM_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786." name="/" resourcePath="">
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.1494327638" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
<option id="cdt.managedbuild.option.gnu.cross.path.1101985181" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/>
@@ -606,7 +606,7 @@
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
- <configuration artifactExtension="elf" artifactName="SAME70Firmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203" name="SAME70_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/SAME70Firmware.elf ${workspace_loc:/${ProjName}/${ConfigName}}/SAME70Firmware.bin">
+ <configuration artifactExtension="elf" artifactName="SAME70Firmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203" name="SAME70_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203." name="/" resourcePath="">
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.5959303" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
<option id="cdt.managedbuild.option.gnu.cross.path.163568524" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/>
diff --git a/src/Alligator/Pins_Alligator.h b/src/Alligator/Pins_Alligator.h
index 1f965e98..fe3bcff8 100644
--- a/src/Alligator/Pins_Alligator.h
+++ b/src/Alligator/Pins_Alligator.h
@@ -35,16 +35,16 @@ const size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers
#define AXES_(a,b,c,d,e,f,g,h,i) { a,b,c,d,e,f }
// Alligator + Piggy module max 5 heaters
-const int8_t Heaters = 5; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
-#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e }
+constexpr size_t Heaters = 5; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
-const size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
+constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
+constexpr size_t NumThermistorInputs = 5;
-const size_t MaxAxes = 7; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
-const size_t MinAxes = 3; // The minimum and default number of axes
-const size_t MaxExtruders = DRIVES - MinAxes; // The maximum number of extruders
+constexpr size_t MaxAxes = 7; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
+constexpr size_t MinAxes = 3; // The minimum and default number of axes
+constexpr size_t MaxExtruders = DRIVES - MinAxes; // The maximum number of extruders
-const size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB and two auxiliary UARTs)
+constexpr size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB and two auxiliary UARTs)
#define SERIAL_MAIN_DEVICE SerialUSB
#define SERIAL_AUX_DEVICE Serial
#define SERIAL_AUX2_DEVICE Serial1
@@ -67,19 +67,18 @@ const Pin MotorFaultDetectPin = 22;
// Alligator End-stop pinout mapping for RepRapFirmware:
// 5V SIGN SIGN GND , 5V SIGN SIGN GND, 5V SIGN SIGN GND
// X E0 Y E1 Z E2-Zprobe
-const Pin END_STOP_PINS[DRIVES] = { 33, 35, 38, 34, 37, 39 ,NoPin };
+const Pin END_STOP_PINS[DRIVES] = { 33, 35, 38, 34, 37, 39, NoPin };
// SPI DAC Motor for Current Vref
const size_t MaxSpiDac = 2;
const Pin SPI_DAC_CS[MaxSpiDac] = { 53, 6 };
// HEATERS
-const Pin TEMP_SENSE_PINS[Heaters] = HEATERS_(1, 0, 2, 3, 4, f, g, h); // Analogue pin numbers
+const Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 1, 0, 2, 3, 4 }; // Analogue pin numbers
// h1,h2,h3,h4: X2,8,9,X8 is hardware PWM
// b: X3 is not hardware PWM
-const Pin HEAT_ON_PINS[Heaters] = HEATERS_(X3, X2, 8, 9, X8, f, g, h); // b,h1,h2,h3,h4
-
+const Pin HEAT_ON_PINS[Heaters] = { X3, X2, 8, 9, X8 };
// Default thermistor parameters
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
@@ -110,11 +109,11 @@ const Pin ATX_POWER_PIN = NoPin; // Arduino Due pin number that control
const Pin Z_PROBE_PIN = 39; // Z min pin ,Last signal of the end-stop connectors
// Digital pin number to turn the IR LED on (high) or off (low)
-const Pin Z_PROBE_MOD_PIN = NoPin; // Digital pin number to turn the IR LED on (high) or off (low) on Duet v0.6 and v1.0 (PB21)
+const Pin Z_PROBE_MOD_PIN = NoPin; // Digital pin number to turn the IR LED on (high) or off (low) on Duet v0.6 and v1.0 (PB21)
const Pin DiagPin = NoPin;
// Pin number that the DAC that controls the second extruder motor current on the Duet 0.8.5 is connected to
-const int Dac0DigitalPin = NoPin; // Arduino Due pin number corresponding to DAC0 output pin
+const int Dac0DigitalPin = NoPin; // Arduino Due pin number corresponding to DAC0 output pin
// COOLING FANS
const size_t NUM_FANS = 4;
@@ -122,7 +121,8 @@ const size_t NUM_FANS = 4;
// Fan2: 31 is not hardware PWM
// J5 pin1 black connector ha hardware PWM, attached to FANS
const Pin COOLING_FAN_PINS[NUM_FANS] = { X0, 31, X17};
-const Pin COOLING_FAN_RPM_PIN = NoPin; // Pin PA15
+constexpr size_t NumTachos = 0;
+constexpr Pin TachoPins[NumTachos] = { };
// SD cards
const size_t NumSdCards = 1;
diff --git a/src/Duet/Pins_Duet.h b/src/Duet/Pins_Duet.h
index 766fd81f..ceefd4bc 100644
--- a/src/Duet/Pins_Duet.h
+++ b/src/Duet/Pins_Duet.h
@@ -30,9 +30,8 @@ constexpr size_t DRIVES = 9; // The number of drives in the machine, includ
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h,i }
constexpr size_t Heaters = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
-#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e,f,g }
-
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
+constexpr size_t NumThermistorInputs = 7;
constexpr size_t MinAxes = 3; // The minimum and default number of axes
constexpr size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
@@ -71,7 +70,7 @@ constexpr float STEPPER_DAC_VOLTAGE_RANGE = 2.02; // Stepper motor current
constexpr float STEPPER_DAC_VOLTAGE_OFFSET = -0.025; // Stepper motor current offset voltage for E1 if using a DAC
// HEATERS
-constexpr Pin TEMP_SENSE_PINS[Heaters] = { 5, 4, 0, 7, 8, 9, 11 }; // Analogue pin numbers
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 5, 4, 0, 7, 8, 9, 11 }; // Analogue pin numbers
constexpr Pin HEAT_ON_PINS[Heaters] = { 6, X5, X7, 7, 8, 9, X17 }; // Heater Channel 7 (pin X17) is shared with Fan1
// Default thermistor parameters
@@ -125,7 +124,8 @@ constexpr int Dac0DigitalPin = 66; // Arduino Due pin number correspon
// COOLING FANS
constexpr size_t NUM_FANS = 2;
constexpr Pin COOLING_FAN_PINS[NUM_FANS] = { X6, X17 }; // Pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
-constexpr Pin COOLING_FAN_RPM_PIN = 23; // Pin PA15
+constexpr size_t NumTachos = 1;
+constexpr Pin TachoPins[NumTachos] = { 23 }; // Pin PA15
// SD cards
constexpr size_t NumSdCards = 2;
diff --git a/src/DuetM/Pins_DuetM.h b/src/DuetM/Pins_DuetM.h
index 62da1bfb..8f11b2fd 100644
--- a/src/DuetM/Pins_DuetM.h
+++ b/src/DuetM/Pins_DuetM.h
@@ -41,10 +41,9 @@ constexpr size_t DRIVES = 7; // The maximum number of drives supported by t
constexpr size_t MaxSmartDrivers = 7; // The maximum number of smart drivers
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g }
-constexpr size_t Heaters = 4; // The number of heaters/thermistors in the machine. Duet M has 3 heaters but 4 thermistors.
-#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c }
-
+constexpr size_t Heaters = 3; // The number of heaters/thermistors in the machine. Duet M has 3 heaters but 4 thermistors.
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
+constexpr size_t NumThermistorInputs = 4;
constexpr size_t MinAxes = 3; // The minimum and default number of axes
constexpr size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
@@ -70,12 +69,12 @@ constexpr Pin STEP_PINS[DRIVES] = { 56, 38, 64, 40, 41, 67, 57 };
constexpr Pin DIRECTION_PINS[DRIVES] = { 54, 8, 30, 33, 42, 18, 60 };
// UART interface to stepper drivers
-#define UART_TMC_DRV UART0
-#define SERIAL_TMC_DRV_IRQn UART0_IRQn
-#define ID_UART_TMC_DRV ID_UART0
-#define UART_TMC_DRV_Handler UART0_Handler
+Uart * const UART_TMC_DRV = UART0;
+const IRQn UART_TMC_DRV_IRQn = UART0_IRQn;
+const uint32_t ID_UART_TMC_DRV = ID_UART0;
+const uint8_t UART_TMC_DRV_PINS = APINS_UART0;
-static const uint8_t UART_TMC_DRV_PINS = APINS_UART0;
+#define UART_TMC_DRV_Handler UART0_Handler
constexpr Pin DriverMuxPins[3] = { 50, 52, 53 }; // Pins that control the UART multiplexer, LSB first
@@ -85,8 +84,8 @@ constexpr Pin DriverMuxPins[3] = { 50, 52, 53 }; // Pins that control the UART m
constexpr Pin END_STOP_PINS[DRIVES] = { 24, 32, 46, 25, 43, NoPin, NoPin };
// Heaters and thermistors
-constexpr Pin HEAT_ON_PINS[Heaters] = { 36, 37, 16, NoPin }; // Heater pin numbers
-constexpr Pin TEMP_SENSE_PINS[Heaters] = { 20, 26, 66, 27 }; // Thermistor pin numbers
+constexpr Pin HEAT_ON_PINS[Heaters] = { 36, 37, 16 }; // Heater pin numbers
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 20, 26, 66, 27 }; // Thermistor pin numbers
constexpr Pin VssaSensePin = 19;
constexpr Pin VrefSensePin = 17;
@@ -125,7 +124,8 @@ constexpr Pin DiagPin = Z_PROBE_MOD_PIN;
// Cooling fans
constexpr size_t NUM_FANS = 3;
constexpr Pin COOLING_FAN_PINS[NUM_FANS] = { 59, 58, 65 };
-constexpr Pin COOLING_FAN_RPM_PIN = 21;
+constexpr size_t NumTachos = 1;
+constexpr Pin TachoPins[NumTachos] = { 21 };
// SD cards
constexpr size_t NumSdCards = 2;
diff --git a/src/DuetNG/Pins_DuetNG.h b/src/DuetNG/Pins_DuetNG.h
index c7709380..6f1063fa 100644
--- a/src/DuetNG/Pins_DuetNG.h
+++ b/src/DuetNG/Pins_DuetNG.h
@@ -37,9 +37,8 @@ constexpr size_t MaxSmartDrivers = 10; // The maximum number of smart drivers
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h,i,j,k,l }
constexpr size_t Heaters = 8; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
-#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e,f,g,h }
-
constexpr size_t NumExtraHeaterProtections = 8; // The number of extra heater protection instances
+constexpr size_t NumThermistorInputs = 8;
constexpr size_t MinAxes = 3; // The minimum and default number of axes
constexpr size_t MaxAxes = 9; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
@@ -77,7 +76,7 @@ constexpr Pin END_STOP_PINS[DRIVES] = { 46, 02, 93, 74, 48, 96, 97, 98, 99, 17,
constexpr Pin DUEX_END_STOP_PINS[5] = { 200, 203, 202, 201, 213 }; // these replace endstops 5-9 if a DueX is present
// HEATERS
-constexpr Pin TEMP_SENSE_PINS[Heaters] = { 45, 47, 44, 61, 62, 63, 59, 18 }; // Thermistor pin numbers
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 45, 47, 44, 61, 62, 63, 59, 18 }; // Thermistor pin numbers
constexpr Pin HEAT_ON_PINS[Heaters] = { 19, 20, 16, 35, 37, 40, 43, 15 }; // Heater pin numbers (heater 7 pin TBC)
// Default thermistor parameters
@@ -129,7 +128,8 @@ constexpr Pin DiagPin = Z_PROBE_MOD_PIN;
// Cooling fans
constexpr size_t NUM_FANS = 9;
constexpr Pin COOLING_FAN_PINS[NUM_FANS] = { 55, 58, 00, 212, 207, 206, 205, 204, 215 };
-constexpr Pin COOLING_FAN_RPM_PIN = 102; // PB6 on expansion connector
+constexpr size_t NumTachos = 1;
+constexpr Pin TachoPins[NumTachos] = { 102 }; // PB6 on expansion connector
// SD cards
constexpr size_t NumSdCards = 2;
diff --git a/src/Fan.cpp b/src/Fans/Fan.cpp
index 0351abce..0351abce 100644
--- a/src/Fan.cpp
+++ b/src/Fans/Fan.cpp
diff --git a/src/Fan.h b/src/Fans/Fan.h
index f0e5598f..f0e5598f 100644
--- a/src/Fan.h
+++ b/src/Fans/Fan.h
diff --git a/src/Fans/Tacho.cpp b/src/Fans/Tacho.cpp
new file mode 100644
index 00000000..00f697ad
--- /dev/null
+++ b/src/Fans/Tacho.cpp
@@ -0,0 +1,53 @@
+/*
+ * Tacho.cpp
+ *
+ * Created on: 16 Jul 2018
+ * Author: David
+ */
+
+#include "Tacho.h"
+#include "Platform.h"
+
+void FanInterrupt(CallbackParameter cb)
+{
+ static_cast<Tacho *>(cb.vp)->Interrupt();
+}
+
+Tacho::Tacho() : fanInterruptCount(0), fanLastResetTime(0), fanInterval(0), pin(NoPin)
+{
+}
+
+void Tacho::Init(Pin p_pin)
+{
+ pin = p_pin;
+ if (pin != NoPin)
+ {
+ pinModeDuet(pin, INPUT_PULLUP, 1500); // enable pullup and 1500Hz debounce filter (500Hz only worked up to 7000RPM)
+ attachInterrupt(pin, FanInterrupt, INTERRUPT_MODE_FALLING, this);
+ }
+}
+
+uint32_t Tacho::GetRPM() const
+{
+ // The ISR sets fanInterval to the number of step interrupt clocks it took to get fanMaxInterruptCount interrupts.
+ // We get 2 tacho pulses per revolution, hence 2 interrupts per revolution.
+ // However, if the fan stops then we get no interrupts and fanInterval stops getting updated.
+ // We must recognise this and return zero.
+ return (fanInterval != 0 && Platform::GetInterruptClocks() - fanLastResetTime < 3 * StepClockRate) // if we have a reading and it is less than 3 second old
+ ? (StepClockRate * fanMaxInterruptCount)/(2 * fanInterval) // then calculate RPM assuming 2 interrupts per rev
+ : 0; // else assume fan is off or tacho not connected
+}
+
+void Tacho::Interrupt()
+{
+ ++fanInterruptCount;
+ if (fanInterruptCount == fanMaxInterruptCount)
+ {
+ const uint32_t now = Platform::GetInterruptClocks();
+ fanInterval = now - fanLastResetTime;
+ fanLastResetTime = now;
+ fanInterruptCount = 0;
+ }
+}
+
+// End
diff --git a/src/Fans/Tacho.h b/src/Fans/Tacho.h
new file mode 100644
index 00000000..279f0d91
--- /dev/null
+++ b/src/Fans/Tacho.h
@@ -0,0 +1,32 @@
+/*
+ * Tacho.h
+ *
+ * Created on: 16 Jul 2018
+ * Author: David
+ */
+
+#ifndef SRC_FANS_TACHO_H_
+#define SRC_FANS_TACHO_H_
+
+#include "RepRapFirmware.h"
+
+class Tacho
+{
+public:
+ Tacho();
+ void Init(Pin p_pin);
+ uint32_t GetRPM() const;
+
+ void Interrupt();
+
+private:
+ static constexpr uint32_t fanMaxInterruptCount = 32; // number of fan interrupts that we average over
+
+ uint32_t fanInterruptCount; // accessed only in ISR, so no need to declare it volatile
+ volatile uint32_t fanLastResetTime; // time (microseconds) at which we last reset the interrupt count, accessed inside and outside ISR
+ volatile uint32_t fanInterval; // written by ISR, read outside the ISR
+
+ Pin pin;
+};
+
+#endif /* SRC_FANS_TACHO_H_ */
diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp
index 8724e9e7..28783186 100644
--- a/src/GCodes/GCodes.cpp
+++ b/src/GCodes/GCodes.cpp
@@ -66,16 +66,23 @@ GCodes::GCodes(Platform& p) :
telnetInput = new NetworkGCodeInput;
fileInput = new FileGCodeInput();
serialInput = new StreamGCodeInput(SERIAL_MAIN_DEVICE);
+#ifdef SERIAL_AUX_DEVICE
auxInput = new StreamGCodeInput(SERIAL_AUX_DEVICE);
-
+#endif
httpGCode = new GCodeBuffer("http", HttpMessage, false);
telnetGCode = new GCodeBuffer("telnet", TelnetMessage, true);
fileGCode = new GCodeBuffer("file", GenericMessage, true);
serialGCode = new GCodeBuffer("serial", UsbMessage, true);
+#ifdef SERIAL_AUX_DEVICE
auxGCode = new GCodeBuffer("aux", LcdMessage, false);
+#else
+ auxGCode = nullptr;
+#endif
daemonGCode = new GCodeBuffer("daemon", GenericMessage, false);
#if SUPPORT_12864_LCD
lcdGCode = new GCodeBuffer("lcd", GenericMessage, false);
+#else
+ lcdGCode = nullptr;
#endif
queuedGCode = new GCodeBuffer("queue", GenericMessage, false);
autoPauseGCode = new GCodeBuffer("autopause", GenericMessage, false);
@@ -240,7 +247,7 @@ bool GCodes::DoingFileMacro() const
{
for (const GCodeBuffer *gb : gcodeSources)
{
- if (gb->IsDoingFileMacro())
+ if (gb != nullptr && gb->IsDoingFileMacro())
{
return true;
}
@@ -296,9 +303,12 @@ bool GCodes::IsDaemonBusy() const
// Copy the feed rate etc. from the daemon to the input channels
void GCodes::CopyConfigFinalValues(GCodeBuffer& gb)
{
- for (size_t i = 0; i < ARRAY_SIZE(gcodeSources); ++i)
+ for (GCodeBuffer *gb2 : gcodeSources)
{
- gcodeSources[i]->MachineState().CopyStateFrom(gb.MachineState());
+ if (gb2 != nullptr)
+ {
+ gb2->MachineState().CopyStateFrom(gb.MachineState());
+ }
}
}
@@ -325,12 +335,15 @@ void GCodes::Spin()
GCodeBuffer *gbp = autoPauseGCode;
if (gbp->IsCompletelyIdle() && !(gbp->MachineState().fileState.IsLive()))
{
- gbp = gcodeSources[nextGcodeSource];
- ++nextGcodeSource; // move on to the next gcode source ready for next time
- if (nextGcodeSource == ARRAY_SIZE(gcodeSources) - 1) // the last one is autoPauseGCode, so don't do it again
+ do
{
- nextGcodeSource = 0;
- }
+ gbp = gcodeSources[nextGcodeSource];
+ ++nextGcodeSource; // move on to the next gcode source ready for next time
+ if (nextGcodeSource == ARRAY_SIZE(gcodeSources) - 1) // the last one is autoPauseGCode, so don't do it again
+ {
+ nextGcodeSource = 0;
+ }
+ } while (gbp == nullptr); // we must have at least one GCode source, so this can't loop indefinitely
}
GCodeBuffer& gb = *gbp;
@@ -1416,6 +1429,7 @@ void GCodes::StartNextGCode(GCodeBuffer& gb, const StringRef& reply)
// USB interface. This line may be shared with a 3D scanner
serialInput->FillBuffer(serialGCode);
}
+#ifdef SERIAL_AUX_DEVICE
else if (&gb == auxGCode)
{
// Aux serial port (typically PanelDue)
@@ -1425,6 +1439,7 @@ void GCodes::StartNextGCode(GCodeBuffer& gb, const StringRef& reply)
platform.SetAuxDetected();
}
}
+#endif
}
void GCodes::DoFilePrint(GCodeBuffer& gb, const StringRef& reply)
@@ -2061,7 +2076,10 @@ void GCodes::Diagnostics(MessageType mtype)
for (size_t i = 0; i < ARRAY_SIZE(gcodeSources); ++i)
{
- gcodeSources[i]->Diagnostics(mtype);
+ if (gcodeSources[i] != nullptr)
+ {
+ gcodeSources[i]->Diagnostics(mtype);
+ }
}
codeQueue->Diagnostics(mtype);
diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h
index 74f86ba9..086deb94 100644
--- a/src/GCodes/GCodes.h
+++ b/src/GCodes/GCodes.h
@@ -379,27 +379,21 @@ private:
NetworkGCodeInput* telnetInput; // ...
FileGCodeInput* fileInput; // ...
StreamGCodeInput* serialInput; // ...
+#ifdef SERIAL_AUX_DEVICE
StreamGCodeInput* auxInput; // ...for the GCodeBuffers below
+#endif
-#if SUPPORT_12864_LCD
GCodeBuffer* gcodeSources[9]; // The various sources of gcodes
-#else
- GCodeBuffer* gcodeSources[8]; // The various sources of gcodes
-#endif
GCodeBuffer*& httpGCode = gcodeSources[0];
GCodeBuffer*& telnetGCode = gcodeSources[1];
GCodeBuffer*& fileGCode = gcodeSources[2];
GCodeBuffer*& serialGCode = gcodeSources[3];
- GCodeBuffer*& auxGCode = gcodeSources[4]; // This one is for the LCD display on the async serial interface
+ GCodeBuffer*& auxGCode = gcodeSources[4]; // This one is for the PanelDue on the async serial interface
GCodeBuffer*& daemonGCode = gcodeSources[5]; // Used for executing config.g and trigger macro files
GCodeBuffer*& queuedGCode = gcodeSources[6];
-#if SUPPORT_12864_LCD
- GCodeBuffer*& lcdGCode = gcodeSources[7]; // This one for the internally-supported LCD
+ GCodeBuffer*& lcdGCode = gcodeSources[7]; // This one for the 12864 LCD
GCodeBuffer*& autoPauseGCode = gcodeSources[8]; // ***THIS ONE MUST BE LAST*** GCode state machine used to run macros on power fail, heater faults and filament out
-#else
- GCodeBuffer*& autoPauseGCode = gcodeSources[7]; // ***THIS ONE MUST BE LAST*** GCode state machine used to run macros on power fail, heater faults and filament out
-#endif
size_t nextGcodeSource; // The one to check next
diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp
index f996eb02..46d846eb 100644
--- a/src/GCodes/GCodes2.cpp
+++ b/src/GCodes/GCodes2.cpp
@@ -2021,13 +2021,16 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
// Update the feed rate for ALL input sources, and all feed rates on the stack
const float speedFactorRatio = newSpeedFactor / speedFactor;
- for (size_t i = 0; i < ARRAY_SIZE(gcodeSources); ++i)
+ for (GCodeBuffer *gb : gcodeSources)
{
- GCodeMachineState *ms = &gcodeSources[i]->MachineState();
- while (ms != nullptr)
+ if (gb != nullptr)
{
- ms->feedRate *= speedFactorRatio;
- ms = ms->previous;
+ GCodeMachineState *ms = &gb->MachineState();
+ while (ms != nullptr)
+ {
+ ms->feedRate *= speedFactorRatio;
+ ms = ms->previous;
+ }
}
}
// If the last move hasn't gone yet, update its feed rate too if it is not a firmware retraction
@@ -2262,13 +2265,13 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
case 303: // Run PID tuning
if (gb.Seen('H'))
{
- const int heater = gb.GetIValue();
+ const unsigned int heater = gb.GetUIValue();
const float temperature = (gb.Seen('S')) ? gb.GetFValue()
: reprap.GetHeat().IsBedHeater(heater) ? 75.0
: reprap.GetHeat().IsChamberHeater(heater) ? 50.0
: 200.0;
const float maxPwm = (gb.Seen('P')) ? gb.GetFValue() : reprap.GetHeat().GetHeaterModel(heater).GetMaxPwm();
- if (heater < 0 || heater >= (int)Heaters)
+ if (heater >= Heaters)
{
reply.copy("Bad heater number in M303 command");
}
@@ -2302,8 +2305,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
case 307: // Set heater process model parameters
if (gb.Seen('H'))
{
- const int heater = gb.GetIValue();
- if (heater >= 0 && heater < (int)Heaters)
+ const unsigned int heater = gb.GetUIValue();
+ if (heater < Heaters)
{
const FopDt& model = reprap.GetHeat().GetHeaterModel(heater);
bool seen = false;
@@ -2992,8 +2995,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
case 562: // Reset temperature fault - use with great caution
if (gb.Seen('P'))
{
- const int heater = gb.GetIValue();
- if (heater >= 0 && heater < (int)Heaters)
+ const unsigned int heater = gb.GetUIValue();
+ if (heater < Heaters)
{
reprap.ClearTemperatureFault(heater);
}
@@ -3006,7 +3009,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
else
{
// Clear all heater faults
- for (int heater = 0; heater < (int)Heaters; ++heater)
+ for (unsigned int heater = 0; heater < Heaters; ++heater)
{
reprap.ClearTemperatureFault(heater);
}
@@ -3207,8 +3210,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
}
if (gb.Seen('H'))
{
- const int heater = gb.GetIValue();
- if (heater >= 0 && heater < (int)Heaters)
+ const unsigned heater = gb.GetUIValue();
+ if (heater < Heaters)
{
bool seenValue = false;
float maxTempExcursion, maxFaultTime;
@@ -3305,10 +3308,10 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
case 573: // Report heater average PWM
if (gb.Seen('P'))
{
- const int heater = gb.GetIValue();
- if (heater >= 0 && heater < (int)Heaters)
+ const unsigned int heater = gb.GetUIValue();
+ if (heater < Heaters)
{
- reply.printf("Average heater %d PWM: %.3f", heater, (double)reprap.GetHeat().GetAveragePWM(heater));
+ reply.printf("Average heater %u PWM: %.3f", heater, (double)reprap.GetHeat().GetAveragePWM(heater));
}
}
break;
diff --git a/src/Heating/Sensors/TemperatureSensor.cpp b/src/Heating/Sensors/TemperatureSensor.cpp
index 2f97a41a..12b45866 100644
--- a/src/Heating/Sensors/TemperatureSensor.cpp
+++ b/src/Heating/Sensors/TemperatureSensor.cpp
@@ -86,11 +86,11 @@ void TemperatureSensor::TryConfigureHeaterName(GCodeBuffer& gb, bool& seen)
TemperatureSensor *TemperatureSensor::Create(unsigned int channel)
{
TemperatureSensor *ts = nullptr;
- if (channel < Heaters)
+ if (channel < NumThermistorInputs)
{
ts = new Thermistor(channel, false);
}
- else if (FirstPT1000Channel <= channel && channel < FirstPT1000Channel + Heaters)
+ else if (FirstPT1000Channel <= channel && channel < FirstPT1000Channel + NumThermistorInputs)
{
ts = new Thermistor(channel, true);
}
diff --git a/src/Pccb/Pins_Pccb.h b/src/Pccb/Pins_Pccb.h
index 32d988c8..3a70f215 100644
--- a/src/Pccb/Pins_Pccb.h
+++ b/src/Pccb/Pins_Pccb.h
@@ -41,10 +41,9 @@ constexpr size_t DRIVES = 8; // The maximum number of drives supported by t
constexpr size_t MaxSmartDrivers = 2; // The maximum number of smart drivers
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h }
-constexpr size_t Heaters = 2; // The number of heaters/thermistors in the machine. PCCB has no heaters but 2 thermistors.
-#define HEATERS_(a,b,c,d,e,f,g,h) { a,b }
-
+constexpr size_t Heaters = 1; // The number of heaters in the machine. PCCB has no heaters, but the code doesn't like that so we say 1
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
+constexpr size_t NumThermistorInputs = 2;
constexpr size_t MinAxes = 3; // The minimum and default number of axes
constexpr size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
@@ -70,9 +69,13 @@ constexpr Pin DIRECTION_PINS[DRIVES] = { 8, 11, 17, 57, 54, 34, 1, 53 };
#define TMC22xx_NO_MUX 1 // each driver has its own UART
-const Uart *DriverUarts[MaxSmartDrivers] = { UART0, UART1 };
+Uart * const DriverUarts[MaxSmartDrivers] = { UART0, UART1 };
constexpr uint32_t DriverUartIds[MaxSmartDrivers] = { ID_UART0, ID_UART1 };
constexpr IRQn DriverUartIRQns[MaxSmartDrivers] = { UART0_IRQn, UART1_IRQn };
+constexpr Pin DriverUartPins[MaxSmartDrivers] = { APINS_UART0, APINS_UART1 };
+
+#define UART_TMC_DRV0_Handler UART0_Handler
+#define UART_TMC_DRV1_Handler UART1_Handler
// Endstops
// RepRapFirmware only has a single endstop per axis.
@@ -80,8 +83,8 @@ constexpr IRQn DriverUartIRQns[MaxSmartDrivers] = { UART0_IRQn, UART1_IRQn };
constexpr Pin END_STOP_PINS[DRIVES] = { 24, 25, 67, 63, NoPin, NoPin, NoPin, NoPin };
// Heaters and thermistors
-constexpr Pin HEAT_ON_PINS[Heaters] = { NoPin, NoPin }; // Heater pin numbers
-constexpr Pin TEMP_SENSE_PINS[Heaters] = { 20, 49 }; // Thermistor pin numbers
+constexpr Pin HEAT_ON_PINS[Heaters] = { NoPin }; // Heater pin numbers
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 20, 49 }; // Thermistor pin numbers
constexpr Pin VssaSensePin = 19;
constexpr Pin VrefSensePin = 27;
@@ -116,16 +119,16 @@ constexpr Pin DiagPin = NoPin;
// Cooling fans
constexpr size_t NUM_FANS = 4;
-constexpr size_t NUM_TACHOS = 2;
+constexpr size_t NumTachos = 2;
constexpr Pin COOLING_FAN_PINS[NUM_FANS] = { 16, 39, 15, 37 }; // PWML2, PWML3, TIOA1, PWML1
-constexpr Pin TACHO_PINS[NUM_TACHOS] = { 26, 66 };
+constexpr Pin TachoPins[NumTachos] = { 26, 66 };
// Main LED control
constexpr size_t NUM_LEDS = 2; // number of main LEDs
constexpr Pin LedOnPins[NUM_LEDS] = { 36, 59 }; // LED control pins
// DotStar LED control
-const Usart *DotStarUsart = USART1;
+Usart * const DotStarUsart = USART1;
constexpr uint32_t DotStarUsartId = ID_USART1;
constexpr IRQn DotStarUsartIRQn = USART1_IRQn;
diff --git a/src/Platform.cpp b/src/Platform.cpp
index bf5a6053..8550bb6f 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -107,11 +107,6 @@ constexpr uint16_t driverNormalVoltageAdcReading = PowerVoltageToAdcReading(27.5
#endif
-static uint32_t fanInterruptCount = 0; // accessed only in ISR, so no need to declare it volatile
-const uint32_t fanMaxInterruptCount = 32; // number of fan interrupts that we average over
-static volatile uint32_t fanLastResetTime = 0; // time (microseconds) at which we last reset the interrupt count, accessed inside and outside ISR
-static volatile uint32_t fanInterval = 0; // written by ISR, read outside the ISR
-
const float MinStepPulseTiming = 0.2; // we assume that we always generate step high and low times at least this wide without special action
const LogicalPin Heater0LogicalPin = 0;
@@ -208,23 +203,31 @@ void Platform::Init()
// Comms
baudRates[0] = MAIN_BAUD_RATE;
+#ifdef SERIAL_AUX_DEVICE
baudRates[1] = AUX_BAUD_RATE;
+#endif
#ifdef SERIAL_AUX2_DEVICE
baudRates[2] = AUX2_BAUD_RATE;
#endif
commsParams[0] = 0;
+#ifdef SERIAL_AUX_DEVICE
commsParams[1] = 1; // by default we require a checksum on data from the aux port, to guard against overrun errors
+#endif
#ifdef SERIAL_AUX2_DEVICE
commsParams[2] = 0;
#endif
usbMutex.Create("USB");
+#ifdef SERIAL_AUX_DEVICE
auxMutex.Create("Aux");
auxDetected = false;
auxSeq = 0;
+#endif
SERIAL_MAIN_DEVICE.begin(baudRates[0]);
+#ifdef SERIAL_AUX_DEVICE
SERIAL_AUX_DEVICE.begin(baudRates[1]); // this can't be done in the constructor because the Arduino port initialisation isn't complete at that point
+#endif
#ifdef SERIAL_AUX2_DEVICE
SERIAL_AUX2_DEVICE.begin(baudRates[2]);
aux2Mutex.Create("Aux2");
@@ -493,18 +496,20 @@ void Platform::Init()
for (size_t heater = 0; heater < Heaters; heater++)
{
- if (heatOnPins[heater] != NoPin)
- {
- pinMode(heatOnPins[heater],
+ // pinMode is safe to call when the pin is NoPin, so we don't need to check it here
+ pinMode(heatOnPins[heater],
#if ACTIVE_LOW_HEAT_ON
OUTPUT_LOW
#else
OUTPUT_HIGH
#endif
);
- }
- pinMode(tempSensePins[heater], AIN);
- filteredAdcChannels[heater] = PinToAdcChannel(tempSensePins[heater]); // translate the pin number to the SAM ADC channel number;
+ }
+
+ for (size_t thermistor = 0; thermistor < NumThermistorInputs; thermistor++)
+ {
+ pinMode(tempSensePins[thermistor], AIN);
+ filteredAdcChannels[thermistor] = PinToAdcChannel(tempSensePins[thermistor]); // translate the pin number to the SAM ADC channel number;
}
#if HAS_VREF_MONITOR
@@ -528,6 +533,10 @@ void Platform::Init()
// Fans
InitFans();
+ for (size_t i = 0; i < NumTachos; ++i)
+ {
+ tachos[i].Init(TachoPins[i]);
+ }
// Hotend configuration
nozzleDiameter = NOZZLE_DIAMETER;
@@ -1120,6 +1129,7 @@ void Platform::Beep(int freq, int ms)
// Send a short message to the aux channel. There is no flow control on this port, so it can't block for long.
void Platform::SendAuxMessage(const char* msg)
{
+#ifdef SERIAL_AUX_DEVICE
OutputBuffer *buf;
if (OutputBuffer::Allocate(buf))
{
@@ -1129,6 +1139,7 @@ void Platform::SendAuxMessage(const char* msg)
auxOutput.Push(buf);
FlushAuxMessages();
}
+#endif
}
void Platform::Exit()
@@ -1147,7 +1158,9 @@ void Platform::Exit()
// Close down USB and serial ports
SERIAL_MAIN_DEVICE.end();
+#ifdef SERIAL_AUX_DEVICE
SERIAL_AUX_DEVICE.end();
+#endif
#ifdef SERIAL_AUX2_DEVICE
SERIAL_AUX2_DEVICE.end();
#endif
@@ -1202,6 +1215,7 @@ void Platform::SetNetMask(uint8_t nm[])
// Flush messages to aux, returning true if there is more to send
bool Platform::FlushAuxMessages()
{
+#ifdef SERIAL_AUX_DEVICE
// Write non-blocking data to the AUX line
MutexLocker lock(auxMutex);
OutputBuffer *auxOutputBuffer = auxOutput.GetFirstItem();
@@ -1220,6 +1234,9 @@ bool Platform::FlushAuxMessages()
}
}
return auxOutput.GetFirstItem() != nullptr;
+#else
+ return false;
+#endif
}
// Flush messages to USB and aux, returning true if there is more to send
@@ -1743,14 +1760,17 @@ void Platform::SoftwareReset(uint16_t reason, const uint32_t *stk)
reason |= (uint16_t)SoftwareResetReason::inLwipSpin;
}
#endif
+
+#ifdef SERIAL_AUX_DEVICE
if (SERIAL_AUX_DEVICE.canWrite() == 0
-#ifdef SERIAL_AUX2_DEVICE
+# ifdef SERIAL_AUX2_DEVICE
|| SERIAL_AUX2_DEVICE.canWrite() == 0
-#endif
+# endif
)
{
reason |= (uint16_t)SoftwareResetReason::inAuxOutput; // if we are resetting because we are stuck in a Spin function, record whether we are trying to send to aux
}
+#endif
}
reason |= (uint8_t)reprap.GetSpinningModule();
reason |= (softwareResetDebugInfo & 0x07) << 5;
@@ -1839,18 +1859,6 @@ void NETWORK_TC_HANDLER()
#endif
-static void FanInterrupt(CallbackParameter)
-{
- ++fanInterruptCount;
- if (fanInterruptCount == fanMaxInterruptCount)
- {
- const uint32_t now = Platform::GetInterruptClocks();
- fanInterval = now - fanLastResetTime;
- fanLastResetTime = now;
- fanInterruptCount = 0;
- }
-}
-
void Platform::InitialiseInterrupts()
{
#if SAM4E || SAM7E
@@ -1864,17 +1872,23 @@ void Platform::InitialiseInterrupts()
NVIC_SetPriority(SysTick_IRQn, NvicPrioritySystick); // set priority for tick interrupts
#endif
-#if SAM4E || SAME70
+ // Set UART interrupt priorities
+#ifdef PCCB
+ NVIC_SetPriority(DriverUartIRQns[0], NvicPriorityDriversSerialTMC);
+ NVIC_SetPriority(DriverUartIRQns[1], NvicPriorityDriversSerialTMC);
+#else
+# if SAM4E || SAME70
NVIC_SetPriority(UART0_IRQn, NvicPriorityPanelDueUart); // set priority for UART interrupt
NVIC_SetPriority(UART1_IRQn, NvicPriorityWiFiUart); // set priority for WiFi UART interrupt
-#elif SAM4S
+# elif SAM4S
NVIC_SetPriority(UART1_IRQn, NvicPriorityPanelDueUart); // set priority for UART interrupt
-#else
+# else
NVIC_SetPriority(UART_IRQn, NvicPriorityPanelDueUart); // set priority for UART interrupt
-#endif
+# endif
-#if HAS_SMART_DRIVERS
- NVIC_SetPriority(SERIAL_TMC_DRV_IRQn, NvicPriorityDriversSerialTMC);
+# if HAS_SMART_DRIVERS
+ NVIC_SetPriority(UART_TMC_DRV_IRQn, NvicPriorityDriversSerialTMC);
+# endif
#endif
// Timer interrupt for stepper motors
@@ -1946,12 +1960,6 @@ void Platform::InitialiseInterrupts()
NVIC_SetPriority(I2C_IRQn, NvicPriorityTwi);
#endif
- // Interrupt for 4-pin PWM fan sense line
- if (coolingFanRpmPin != NoPin)
- {
- attachInterrupt(coolingFanRpmPin, FanInterrupt, INTERRUPT_MODE_FALLING, nullptr);
- }
-
// Tick interrupt for ADC conversions
tickState = 0;
currentFilterNumber = 0;
@@ -3230,15 +3238,9 @@ const char *Platform::GetFanName(size_t fan) const
}
// Get current fan RPM
-float Platform::GetFanRPM() const
+uint32_t Platform::GetFanRPM(size_t tachoIndex) const
{
- // The ISR sets fanInterval to the number of microseconds it took to get fanMaxInterruptCount interrupts.
- // We get 2 tacho pulses per revolution, hence 2 interrupts per revolution.
- // However, if the fan stops then we get no interrupts and fanInterval stops getting updated.
- // We must recognise this and return zero.
- return (fanInterval != 0 && Platform::GetInterruptClocks() - fanLastResetTime < 3 * StepClockRate) // if we have a reading and it is less than 3 second old
- ? (float)(3 * StepClockRate * fanMaxInterruptCount)/fanInterval // then calculate RPM assuming 2 interrupts per rev
- : 0.0; // else assume fan is off or tacho not connected
+ return (tachoIndex < NumTachos) ? tachos[tachoIndex].GetRPM() : 0;
}
bool Platform::FansHardwareInverted(size_t fanNumber) const
@@ -3285,12 +3287,6 @@ void Platform::InitFans()
fans[1].SetPwm(1.0); // set it full on
#endif
}
-
- coolingFanRpmPin = COOLING_FAN_RPM_PIN;
- if (coolingFanRpmPin != NoPin)
- {
- pinModeDuet(coolingFanRpmPin, INPUT_PULLUP, 1500); // enable pullup and 1500Hz debounce filter (500Hz only worked up to 7000RPM)
- }
}
void Platform::SetEndStopConfiguration(size_t axis, EndStopPosition esPos, EndStopInputType inputType)
@@ -3309,6 +3305,7 @@ void Platform::GetEndStopConfiguration(size_t axis, EndStopPosition& esType, End
void Platform::AppendAuxReply(const char *msg, bool rawMessage)
{
+#ifdef SERIAL_AUX_DEVICE
// Discard this response if either no aux device is attached or if the response is empty
if (msg[0] != 0 && HaveAux())
{
@@ -3333,10 +3330,12 @@ void Platform::AppendAuxReply(const char *msg, bool rawMessage)
}
}
}
+#endif
}
void Platform::AppendAuxReply(OutputBuffer *reply, bool rawMessage)
{
+#ifdef SERIAL_AUX_DEVICE
// Discard this response if either no aux device is attached or if the response is empty
if (reply == nullptr || reply->Length() == 0 || !HaveAux())
{
@@ -3365,6 +3364,9 @@ void Platform::AppendAuxReply(OutputBuffer *reply, bool rawMessage)
}
}
}
+#else
+ OutputBuffer::ReleaseAll(reply);
+#endif
}
// Send the specified message to the specified destinations. The Error and Warning flags have already been handled.
@@ -3770,16 +3772,21 @@ void Platform::ResetChannel(size_t chan)
SERIAL_MAIN_DEVICE.end();
SERIAL_MAIN_DEVICE.begin(baudRates[0]);
break;
+
+#ifdef SERIAL_AUX_DEVICE
case 1:
SERIAL_AUX_DEVICE.end();
SERIAL_AUX_DEVICE.begin(baudRates[1]);
break;
+#endif
+
#ifdef SERIAL_AUX2_DEVICE
case 2:
SERIAL_AUX2_DEVICE.end();
SERIAL_AUX2_DEVICE.begin(baudRates[2]);
break;
#endif
+
default:
break;
}
diff --git a/src/Platform.h b/src/Platform.h
index 6afdb6b7..57d83de2 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -31,7 +31,8 @@ Licence: GPL
#include "RepRapFirmware.h"
#include "IoPorts.h"
#include "DueFlashStorage.h"
-#include "Fan.h"
+#include "Fans/Fan.h"
+#include "Fans/Tacho.h"
#include "Heating/TemperatureError.h"
#include "OutputMemory.h"
#include "Storage/FileStore.h"
@@ -57,19 +58,19 @@ constexpr bool BACKWARDS = !FORWARDS;
// Define the number of ADC filters and the indices of the extra ones
#if HAS_VREF_MONITOR
-constexpr size_t VrefFilterIndex = Heaters;
-constexpr size_t VssaFilterIndex = Heaters + 1;
+constexpr size_t VrefFilterIndex = NumThermistorInputs;
+constexpr size_t VssaFilterIndex = NumThermistorInputs + 1;
# if HAS_CPU_TEMP_SENSOR
-constexpr size_t CpuTempFilterIndex = Heaters + 2;
-constexpr size_t NumAdcFilters = Heaters + 3;
+constexpr size_t CpuTempFilterIndex = NumThermistorInputs + 2;
+constexpr size_t NumAdcFilters = NumThermistorInputs + 3;
# else
-constexpr size_t NumAdcFilters = Heaters + 2;
+constexpr size_t NumAdcFilters = NumThermistorInputs + 2;
# endif
#elif HAS_CPU_TEMP_SENSOR
-constexpr size_t CpuTempFilterIndex = Heaters;
-constexpr size_t NumAdcFilters = Heaters + 1;
+constexpr size_t CpuTempFilterIndex = NumThermistorInputs;
+constexpr size_t NumAdcFilters = NumThermistorInputs + 1;
#else
-constexpr size_t NumAdcFilters = Heaters;
+constexpr size_t NumAdcFilters = NumThermistorInputs;
#endif
/**************************************************************************************************/
@@ -525,7 +526,7 @@ public:
const char *GetFanName(size_t fan) const;
bool WriteFanSettings(FileStore *f) const; // Save some resume information
- float GetFanRPM() const;
+ uint32_t GetFanRPM(size_t tachoIndex) const;
// Flash operations
void UpdateFirmware();
@@ -813,7 +814,7 @@ private:
static bool WriteAxisLimits(FileStore *f, AxesBitmap axesProbed, const float limits[MaxAxes], int sParam);
// Heaters - bed is assumed to be the first
- Pin tempSensePins[Heaters];
+ Pin tempSensePins[NumThermistorInputs];
Pin heatOnPins[Heaters];
Pin spiTempSenseCsPins[MaxSpiTempSensors];
uint32_t configuredHeaters; // bitmask of all real heaters in use
@@ -821,20 +822,25 @@ private:
// Fans
Fan fans[NUM_FANS];
- Pin coolingFanRpmPin; // we currently support only one fan RPM input
uint32_t lastFanCheckTime;
void InitFans();
bool FansHardwareInverted(size_t fanNumber) const;
+ // Fan tachos
+ Tacho tachos[NumTachos];
+
// Serial/USB
uint32_t baudRates[NUM_SERIAL_CHANNELS];
uint8_t commsParams[NUM_SERIAL_CHANNELS];
+#ifdef SERIAL_AUX_DEVICE
volatile OutputStack auxOutput;
Mutex auxMutex;
+#endif
+
OutputBuffer *auxGCodeReply; // G-Code reply for AUX devices (special one because it is actually encapsulated before sending)
uint32_t auxSeq; // Sequence number for AUX devices
- bool auxDetected; // Have we processed at least one G-Code from an AUX device?
+ bool auxDetected; // Have we processed at least one G-Code from an AUX device?
#ifdef SERIAL_AUX2_DEVICE
volatile OutputStack aux2Output;
diff --git a/src/RADDS/Pins_RADDS.h b/src/RADDS/Pins_RADDS.h
index 01eac0ed..902c8e84 100644
--- a/src/RADDS/Pins_RADDS.h
+++ b/src/RADDS/Pins_RADDS.h
@@ -37,24 +37,20 @@ const size_t DRIVES = 9;
// The number of heaters in the machine
// 0 is the heated bed even if there isn't one.
-const size_t Heaters = 4;
+constexpr size_t Heaters = 4;
+constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
+constexpr size_t NumThermistorInputs = 4;
-const size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
-
-// Initialization macro used in statements needing to initialize values in arrays of size HEATERS. E.g.,
-// defaultPidKis[HEATERS] = {HEATERS_(5.0, 0.1, 0.1, 0.1, 0.1, 0.1)};
-#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d }
-
-const size_t MinAxes = 3; // The minimum and default number of axes
-const size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
+constexpr size_t MinAxes = 3; // The minimum and default number of axes
+constexpr size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
// Initialization macro used in statements needing to initialize values in arrays of size MAX_AXES
#define AXES_(a,b,c,d,e,f,g,h,i) { a,b,c,d,e,f }
-const size_t MIN_AXES = 3; // The minimum and default number of axes
-const size_t MaxExtruders = DRIVES - MIN_AXES; // The maximum number of extruders
-const size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis
+constexpr size_t MIN_AXES = 3; // The minimum and default number of axes
+constexpr size_t MaxExtruders = DRIVES - MIN_AXES; // The maximum number of extruders
+constexpr size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis
-const size_t NUM_SERIAL_CHANNELS = 2;
+constexpr size_t NUM_SERIAL_CHANNELS = 2;
// Use TX0/RX0 for the auxiliary serial line
#define SERIAL_MAIN_DEVICE SerialUSB
#define SERIAL_AUX_DEVICE Serial1
@@ -85,14 +81,14 @@ const Pin END_STOP_PINS[DRIVES] = { 28, 30, 32, 39, NoPin, NoPin, NoPin, NoPin }
// HEATERS - The bed is assumed to be the at index 0
// Analogue pin numbers
-const Pin TEMP_SENSE_PINS[Heaters] = HEATERS_(4, 0, 1, 2, e, f, g, h);
+const Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 4, 0, 1, 2 };
// Heater outputs
// Bed PMW: D7 has hardware PWM so bed has PWM
// h0, h1 PMW: D13 & D12 are on TIOB0 & B8 which are both TC B channels, so they get PWM
// h2 bang-bang: D11 is on TIOA8 which is a TC A channel shared with h1, it gets bang-bang control
-const Pin HEAT_ON_PINS[Heaters] = HEATERS_(7, 13, 12, 11, e, f, g, h); // bed, h0, h1, h2
+const Pin HEAT_ON_PINS[Heaters] = { 7, 13, 12, 11 }; // bed, h0, h1, h2
// Default thermistor betas
const float BED_R25 = 10000.0;
@@ -131,7 +127,8 @@ const Pin COOLING_FAN_PINS[NUM_FANS] = { 9, 8 }; // Fan 0, Fan 1
// see FanInterrupt() in Platform.cpp
//
// D25 -- Unused GPIO on AUX1
-const Pin COOLING_FAN_RPM_PIN = 25;
+constexpr size_t NumTachos = 1;
+constexpr Pin TachoPins[NumTachos] = { 25 };
// SD cards
const size_t NumSdCards = 2;
diff --git a/src/RepRap.cpp b/src/RepRap.cpp
index 1f8c15cd..e9ec6605 100644
--- a/src/RepRap.cpp
+++ b/src/RepRap.cpp
@@ -931,8 +931,27 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
break;
}
- // Fan RPM
- response->catf(",\"fanRPM\":%d}", static_cast<unsigned int>(platform->GetFanRPM()));
+ // Send fan RPM value(s)
+ if (NumTachos != 0)
+ {
+ response->cat(",\"fanRPM\":");
+ // For compatibility with older versions of DWC, if there is only one tacho value then we send it as a simple variable
+ if (NumTachos > 1)
+ {
+ char ch = '[';
+ for (size_t i = 0; i < NumTachos; ++i)
+ {
+ response->catf("%c%" PRIu32, ch, platform->GetFanRPM(i));
+ ch = ',';
+ }
+ response->cat(']');
+ }
+ else
+ {
+ response->catf("%" PRIu32, platform->GetFanRPM(0));
+ }
+ }
+ response->cat('}'); // end sensors
}
/* Temperatures */
@@ -1628,8 +1647,27 @@ OutputBuffer *RepRap::GetLegacyStatusResponse(uint8_t type, int seq)
ch = ',';
}
- // Send fan RPM value (we only support one)
- response->catf("],\"fanRPM\":%u", static_cast<unsigned int>(platform->GetFanRPM()));
+ // Send fan RPM value(s)
+ response->cat(']');
+ if (NumTachos != 0)
+ {
+ response->cat(",\"fanRPM\":");
+ // For compatibility with older versions of DWC, if there is only one tacho value then we send it as a simple variable
+ if (NumTachos > 1)
+ {
+ char ch = '[';
+ for (size_t i = 0; i < NumTachos; ++i)
+ {
+ response->catf("%c%" PRIu32, ch, platform->GetFanRPM(i));
+ ch = ',';
+ }
+ response->cat(']');
+ }
+ else
+ {
+ response->catf("%" PRIu32, platform->GetFanRPM(0));
+ }
+ }
// Send the home state. To keep the messages short, we send 1 for homed and 0 for not homed, instead of true and false.
response->cat(",\"homed\":");
diff --git a/src/SAME70_TEST/Pins_SAME70_TEST.h b/src/SAME70_TEST/Pins_SAME70_TEST.h
index 0c028c60..3dce6245 100644
--- a/src/SAME70_TEST/Pins_SAME70_TEST.h
+++ b/src/SAME70_TEST/Pins_SAME70_TEST.h
@@ -34,9 +34,8 @@ const size_t MaxSmartDrivers = 10; // The maximum number of smart drivers
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h,i,j,k,l }
constexpr size_t Heaters = 8; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
-#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e,f,g,h }
-
constexpr size_t NumExtraHeaterProtections = 8; // The number of extra heater protection instances
+constexpr size_t NumThermistorInputs = 8;
constexpr size_t MinAxes = 3; // The minimum and default number of axes
constexpr size_t MaxAxes = 9; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
@@ -59,12 +58,12 @@ constexpr Pin AdditionalIoExpansionStart = 220; // Pin numbers 220-235 are on t
// The numbers of entries in each array must correspond with the values of DRIVES, AXES, or HEATERS. Set values to NoPin to flag unavailability.
// DRIVES
-constexpr Pin GlobalTmcEnablePin = NoPin; // The pin that drives ENN of all TMC2660 drivers on production boards (on pre-production boards they are grounded)
+constexpr Pin GlobalTmcEnablePin = NoPin; // The pin that drives ENN of all TMC2660 drivers on production boards (on pre-production boards they are grounded)
constexpr Pin ENABLE_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
constexpr Pin STEP_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
constexpr Pin DIRECTION_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
-constexpr Pin DueX_SG = NoPin; // DueX stallguard detect pin (TBD)
+constexpr Pin DueX_SG = NoPin; // DueX stallguard detect pin (TBD)
constexpr Pin DueX_INT = NoPin; // DueX interrupt pin (TBD)
// Endstops
@@ -72,8 +71,8 @@ constexpr Pin DueX_INT = NoPin; // DueX interrupt pin (TBD)
// Gcode defines if it is a max ("high end") or min ("low end") endstop and sets if it is active HIGH or LOW.
constexpr Pin END_STOP_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
-// HEATERS
-constexpr Pin TEMP_SENSE_PINS[Heaters] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin }; // Thermistor pin numbers
+// Heater and thermistors
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin }; // Thermistor pin numbers
constexpr Pin HEAT_ON_PINS[Heaters] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin, NoPin }; // Heater pin numbers (TBD)
// Default thermistor parameters
@@ -116,7 +115,8 @@ constexpr Pin DiagPin = NoPin; // TBD
// Cooling fans
constexpr size_t NUM_FANS = 1;
constexpr Pin COOLING_FAN_PINS[NUM_FANS] = { NoPin };
-constexpr Pin COOLING_FAN_RPM_PIN = NoPin; // TBD
+constexpr size_t NumTachos = 1;
+constexpr Pin TachoPins[NumTachos] = { NoPin }; // TBD
// SD cards
constexpr size_t NumSdCards = 2;
diff --git a/src/StepperDrivers/TMC22xx/TMC22xx.cpp b/src/StepperDrivers/TMC22xx/TMC22xx.cpp
index 3a52f2e8..55ee62a6 100644
--- a/src/StepperDrivers/TMC22xx/TMC22xx.cpp
+++ b/src/StepperDrivers/TMC22xx/TMC22xx.cpp
@@ -280,11 +280,22 @@ public:
void TransferDone() __attribute__ ((hot)); // called by the ISR when the SPI transfer has completed
void StartTransfer() __attribute__ ((hot)); // called to start a transfer
void TransferTimedOut() { ++numTimeouts; }
- static void AbortTransfer();
+ void AbortTransfer();
uint32_t ReadLiveStatus() const;
uint32_t ReadAccumulatedStatus(uint32_t bitsToKeep);
+ // Variables used by the ISR
+#if TMC22xx_HAS_MUX
+ static TmcDriverState * volatile currentDriver; // volatile because the ISR changes it
+ static uint32_t transferStartedTime;
+#else
+ uint32_t transferStartedTime;
+
+ void CheckTransfer(); // start a transfer or check for timeout
+ void UartTmcHandler(); // core of the ISR for this driver
+#endif
+
private:
void UpdateRegister(size_t regIndex, uint32_t regVal);
void UpdateChopConfRegister(); // calculate the chopper control register and flag it for sending
@@ -326,6 +337,12 @@ private:
uint32_t microstepShiftFactor; // how much we need to shift 1 left by to get the current microstepping
uint32_t motorCurrent; // the configured motor current
+#if TMC22xx_HAS_MUX
+ static Uart * const uart;
+#else
+ Uart *uart; // the UART that controls this driver
+#endif
+
uint16_t readErrors; // how many read errors we had
uint16_t writeErrors; // how many write errors we had
uint16_t numReads; // how many successful reads we had
@@ -341,6 +358,10 @@ private:
bool enabled; // true if driver is enabled
};
+#if TMC22xx_HAS_MUX
+Uart * const TmcDriverState::uart = UART_TMC_DRV;
+#endif
+
const uint8_t TmcDriverState::WriteRegNumbers[NumWriteRegisters] =
{
REGNUM_GCONF,
@@ -365,15 +386,6 @@ const uint8_t TmcDriverState::ReadRegCRCs[NumReadRegisters] =
// State structures for all drivers
static TmcDriverState driverStates[MaxSmartDrivers];
-#if TMC22xx_HAS_MUX
-// PDC address for the single UART that communicates with all drivers
-static Pdc * const uartPdc = uart_get_pdc_base(UART_TMC_DRV);
-#endif
-
-// Variables used by the ISR
-static TmcDriverState * volatile currentDriver = nullptr; // volatile because the ISR changes it
-static uint32_t transferStartedTime;
-
// Set up the PDC to send a register
/*static*/ inline void TmcDriverState::SetupDMASend(Pdc *pdc, uint8_t regNum, uint32_t regVal, uint8_t crc)
{
@@ -444,10 +456,16 @@ pre(!driversPowered)
driverNumber = p_driverNumber;
axisNumber = p_driverNumber; // assume straight-through axis mapping initially
enablePin = p_pin; // this is NoPin for the built-in drivers
+
+#if !TMC22xx_HAS_MUX
+ uart = DriverUarts[p_driverNumber];
+#endif
+
if (p_pin != NoPin)
{
pinMode(p_pin, OUTPUT_HIGH);
}
+
enabled = false;
registersToUpdate = 0;
motorCurrent = 0;
@@ -677,14 +695,16 @@ inline void TmcDriverState::TransferDone()
// This is called to abandon the current transfer, if any
void TmcDriverState::AbortTransfer()
{
- UART_TMC_DRV->UART_IDR = UART_IDR_ENDRX; // disable end-of-receive interrupt
- uartPdc->PERIPH_PTCR = (PERIPH_PTCR_RXTDIS | PERIPH_PTCR_TXTDIS); // disable the PDC
- UART_TMC_DRV->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS | UART_CR_RSTSTA;
- currentDriver = nullptr;
+ uart->UART_IDR = UART_IDR_ENDRX; // disable end-of-receive interrupt
+ uart_get_pdc_base(uart)->PERIPH_PTCR = (PERIPH_PTCR_RXTDIS | PERIPH_PTCR_TXTDIS); // disable the PDC
+ uart->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS | UART_CR_RSTSTA;
}
#if TMC22xx_HAS_MUX
+TmcDriverState * volatile TmcDriverState::currentDriver = nullptr; // volatile because the ISR changes it
+uint32_t TmcDriverState::transferStartedTime;
+
// Set up the UART multiplexer to address the selected driver
inline void TmcDriverState::SetUartMux()
{
@@ -714,14 +734,31 @@ inline void TmcDriverState::SetUartMux()
}
}
+#else
+
+// If no transfer is in progress, start one
+// If a transfer is in progress, check for timeout
+void TmcDriverState::CheckTransfer()
+{
+ if ((uart->UART_IMR & UART_IMR_ENDRX) == 0) // if no transfer is in progress
+ {
+ StartTransfer();
+ }
+ else if (millis() - TmcDriverState::transferStartedTime > TransferTimeout)
+ {
+ // A UART transfer was started but has timed out
+ TransferTimedOut();
+ AbortTransfer();
+ }
+}
+
#endif
// This is called from the ISR or elsewhere to start a new SPI transfer. Inlined for ISR speed.
inline void TmcDriverState::StartTransfer()
{
- currentDriver = this;
-
#if TMC22xx_HAS_MUX
+ currentDriver = this;
SetUartMux();
#endif
@@ -732,10 +769,10 @@ inline void TmcDriverState::StartTransfer()
// Read a register
const irqflags_t flags = cpu_irq_save(); // avoid race condition
- UART_TMC_DRV->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX; // reset transmitter and receiver
- SetupDMAReceive(uartPdc, ReadRegNumbers[registerToRead], ReadRegCRCs[registerToRead]); // set up the PDC
- UART_TMC_DRV->UART_IER = UART_IER_ENDRX; // enable end-of-receive interrupt
- UART_TMC_DRV->UART_CR = UART_CR_RXEN | UART_CR_TXEN; // enable transmitter and receiver
+ uart->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX; // reset transmitter and receiver
+ SetupDMAReceive(uart_get_pdc_base(uart), ReadRegNumbers[registerToRead], ReadRegCRCs[registerToRead]); // set up the PDC
+ uart->UART_IER = UART_IER_ENDRX; // enable end-of-receive interrupt
+ uart->UART_CR = UART_CR_RXEN | UART_CR_TXEN; // enable transmitter and receiver
transferStartedTime = millis();
cpu_irq_restore(flags);
}
@@ -757,21 +794,25 @@ inline void TmcDriverState::StartTransfer()
// Kick off a transfer for that register
const irqflags_t flags = cpu_irq_save(); // avoid race condition
registerBeingUpdated = mask;
- UART_TMC_DRV->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX; // reset transmitter and receiver
- SetupDMASend(uartPdc, WriteRegNumbers[regNum], writeRegisters[regNum], writeRegCRCs[regNum]); // set up the PDC
- UART_TMC_DRV->UART_IER = UART_IER_ENDRX; // enable end-of-transfer interrupt
- UART_TMC_DRV->UART_CR = UART_CR_RXEN | UART_CR_TXEN; // enable transmitter and receiver
+ uart->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX; // reset transmitter and receiver
+ SetupDMASend(uart_get_pdc_base(uart), WriteRegNumbers[regNum], writeRegisters[regNum], writeRegCRCs[regNum]); // set up the PDC
+ uart->UART_IER = UART_IER_ENDRX; // enable end-of-transfer interrupt
+ uart->UART_CR = UART_CR_RXEN | UART_CR_TXEN; // enable transmitter and receiver
transferStartedTime = millis();
cpu_irq_restore(flags);
}
}
-// ISR for the UART
-extern "C" void UART_TMC_DRV_Handler(void) __attribute__ ((hot));
+// ISR(s) for the UART(s)
-void UART_TMC_DRV_Handler(void)
+#if TMC22xx_HAS_MUX
+
+// ISR for the single UART
+extern "C" void UART_TMC_DRV_Handler() __attribute__ ((hot));
+
+void UART_TMC_DRV_Handler()
{
- TmcDriverState *driver = currentDriver; // capture volatile variable
+ TmcDriverState *driver = TmcDriverState::currentDriver; // capture volatile variable
if (driver != nullptr)
{
driver->TransferDone(); // tidy up after the transfer we just completed
@@ -790,9 +831,40 @@ void UART_TMC_DRV_Handler(void)
// Driver power is down or there is no current driver, so stop polling
UART_TMC_DRV->UART_IDR = UART_IDR_ENDRX;
- currentDriver = nullptr; // signal that we are not waiting for an interrupt
+ TmcDriverState::currentDriver = nullptr; // signal that we are not waiting for an interrupt
+}
+
+#else
+
+inline void TmcDriverState::UartTmcHandler()
+{
+ TransferDone(); // tidy up after the transfer we just completed
+ if (driversState != DriversState::noPower)
+ {
+ // Power is still good, so send/receive again
+ StartTransfer();
+ }
+ else
+ {
+ // Driver power is down so disable interrupt to stop polling
+ uart->UART_IDR = UART_IDR_ENDRX;
+ }
+}
+
+extern "C" void UART_TMC_DRV0_Handler() __attribute__ ((hot));
+void UART_TMC_DRV0_Handler()
+{
+ driverStates[0].UartTmcHandler();
+}
+
+extern "C" void UART_TMC_DRV1_Handler() __attribute__ ((hot));
+void UART_TMC_DRV1_Handler()
+{
+ driverStates[1].UartTmcHandler();
}
+#endif
+
//--------------------------- Public interface ---------------------------------
namespace SmartDrivers
@@ -807,8 +879,8 @@ namespace SmartDrivers
pinMode(GlobalTmcEnablePin, OUTPUT_HIGH);
#if TMC22xx_HAS_MUX
- // The pins are already set up for UART use in the pins table
- ConfigurePin(GetPinDescription(UART_TMC_DRV_PINS));
+ // Set up- the single UART that communicates with all TMC22xx drivers
+ ConfigurePin(GetPinDescription(UART_TMC_DRV_PINS)); // the pins are already set up for UART use in the pins table
// Enable the clock to the UART
pmc_enable_periph_clk(ID_UART_TMC_DRV);
@@ -819,6 +891,7 @@ namespace SmartDrivers
UART_TMC_DRV->UART_MR = UART_MR_CHMODE_NORMAL | UART_MR_PAR_NO;
UART_TMC_DRV->UART_BRGR = VARIANT_MCK/(16 * DriversBaudRate); // set baud rate
UART_TMC_DRV->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS | UART_CR_RSTSTA;
+ NVIC_EnableIRQ(UART_TMC_DRV_IRQn);
// Set up the multiplexer control pins as outputs
pinMode(DriverMuxPins[0], OUTPUT_LOW);
@@ -829,6 +902,23 @@ namespace SmartDrivers
driversState = DriversState::noPower;
for (size_t drive = 0; drive < numTmc22xxDrivers; ++drive)
{
+#if !TMC22xx_HAS_MUX
+ // Initialise the UART that controls this driver
+ // The pins are already set up for UART use in the pins table
+ ConfigurePin(GetPinDescription(DriverUartPins[drive]));
+
+ // Enable the clock to the UART
+ pmc_enable_periph_clk(DriverUartIds[drive]);
+
+ // Set the UART baud rate, 8 bits, 2 stop bits, no parity
+ Uart * const uart = DriverUarts[drive];
+ uart->UART_IDR = ~0u;
+ uart->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
+ uart->UART_MR = UART_MR_CHMODE_NORMAL | UART_MR_PAR_NO;
+ uart->UART_BRGR = VARIANT_MCK/(16 * DriversBaudRate); // set baud rate
+ uart->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS | UART_CR_RSTSTA;
+ NVIC_EnableIRQ(DriverUartIRQns[drive]);
+#endif
driverStates[drive].Init(drive, driverSelectPins[drive]); // axes are mapped straight through to drivers initially
}
}
@@ -933,28 +1023,37 @@ namespace SmartDrivers
}
else if (powered)
{
- if (currentDriver == nullptr)
+ // If no transfer is in progress, kick one off.
+ // If a transfer has timed out, abort it.
+#if TMC22xx_HAS_MUX
+ if (TmcDriverState::currentDriver == nullptr)
{
// No transfer in progress, so start one
if (numTmc22xxDrivers != 0)
{
// Kick off the first transfer
- NVIC_EnableIRQ(SERIAL_TMC_DRV_IRQn);
driverStates[0].StartTransfer();
}
}
- else if (millis() - transferStartedTime > TransferTimeout)
+ else if (millis() - TmcDriverState::transferStartedTime > TransferTimeout)
{
// A UART transfer was started but has timed out
- currentDriver->TransferTimedOut();
- uint8_t driverNum = currentDriver->GetDriverNumber();
- TmcDriverState::AbortTransfer(); // this clears currentDriver
+ TmcDriverState::currentDriver->TransferTimedOut();
+ TmcDriverState::currentDriver->AbortTransfer();
+ TmcDriverState::currentDriver = nullptr;
+ uint8_t driverNum = TmcDriverState::currentDriver->GetDriverNumber();
++driverNum;
if (driverNum >= numTmc22xxDrivers)
{
driverNum = 0;
}
}
+#else
+ for (size_t drive = 0; drive < numTmc22xxDrivers; ++drive)
+ {
+ driverStates[drive].CheckTransfer();
+ }
+#endif
if (driversState == DriversState::initialising)
{
@@ -980,7 +1079,18 @@ namespace SmartDrivers
{
// We had power but we lost it
digitalWrite(GlobalTmcEnablePin, HIGH); // disable the drivers
- TmcDriverState::AbortTransfer();
+#if TMC22xx_HAS_MUX
+ if (TmcDriverState::currentDriver == nullptr)
+ {
+ TmcDriverState::currentDriver->AbortTransfer();
+ TmcDriverState::currentDriver = nullptr;
+ }
+#else
+ for (size_t drive = 0; drive < numTmc22xxDrivers; ++drive)
+ {
+ driverStates[drive].AbortTransfer();
+ }
+#endif
driversState = DriversState::noPower;
}
}
diff --git a/src/StepperDrivers/TMC2660/TMC2660.cpp b/src/StepperDrivers/TMC2660/TMC2660.cpp
index 51fbc84c..f99961ea 100644
--- a/src/StepperDrivers/TMC2660/TMC2660.cpp
+++ b/src/StepperDrivers/TMC2660/TMC2660.cpp
@@ -750,7 +750,7 @@ namespace SmartDrivers
if (currentDriver == nullptr && numTmc2660Drivers != 0)
{
// Kick off the first transfer
- NVIC_EnableIRQ(SERIAL_TMC_DRV_IRQn);
+ NVIC_EnableIRQ(UART_TMC_DRV_IRQn);
driverStates[0].StartTransfer();
}
}
diff --git a/src/StepperDrivers/TMC2660/TMC2660.h b/src/StepperDrivers/TMC2660/TMC2660.h
index fa18c27c..ceed9734 100644
--- a/src/StepperDrivers/TMC2660/TMC2660.h
+++ b/src/StepperDrivers/TMC2660/TMC2660.h
@@ -18,7 +18,7 @@
// The Platform class needs to know which USART we are using when assigning interrupt priorities
#define USART_TMC_DRV USART1
-#define SERIAL_TMC_DRV_IRQn USART1_IRQn
+#define UART_TMC_DRV_IRQn USART1_IRQn
#define ID_USART_TMC_DRV ID_USART1
#define USART_TMC_DRV_Handler USART1_Handler
diff --git a/src/Version.h b/src/Version.h
index 5d4587ba..2c5b9195 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -22,7 +22,7 @@
#endif
#ifndef DATE
-# define DATE "2018-07-15b1"
+# define DATE "2018-07-16b2"
#endif
#define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman"