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>2019-05-14 13:35:23 +0300
committerDavid Crocker <dcrocker@eschertech.com>2019-05-14 13:35:23 +0300
commit2a8a8e45d9617eaaaf3b1ffe81e230026819c890 (patch)
tree998b13f838a3806f2640319f40d906f1e139fefe
parent7684fee498303fe1803966538be1935e5685ad2d (diff)
Version 2.03RC2 provisional
Use new Wire library form CoreNG Use a separate task to keep DueX endstop input status up to date Task priority definitions moved from RRFLibraries project to ReprapFirmware.h Added folder src/Hardware and moved some files into it
-rw-r--r--.project2
-rw-r--r--src/BugList.txt4
-rw-r--r--src/CAN/CanSender.cpp2
-rw-r--r--src/Display/Display.cpp2
-rw-r--r--src/Display/RotaryEncoder.cpp2
-rw-r--r--src/DuetNG/DueXn.cpp65
-rw-r--r--src/DuetNG/DueXn.h1
-rw-r--r--src/DuetNG/SX1509.cpp47
-rw-r--r--src/DuetNG/SX1509.h6
-rw-r--r--src/GCodes/GCodes3.cpp17
-rw-r--r--src/Hardware/DmacManager.cpp (renamed from src/DmacManager.cpp)0
-rw-r--r--src/Hardware/DmacManager.h (renamed from src/DmacManager.h)0
-rw-r--r--src/Hardware/I2C.cpp66
-rw-r--r--src/Hardware/I2C.h48
-rw-r--r--src/Hardware/IoPorts.cpp (renamed from src/IoPorts.cpp)0
-rw-r--r--src/Hardware/IoPorts.h (renamed from src/IoPorts.h)0
-rw-r--r--src/Heating/Heat.cpp2
-rw-r--r--src/Heating/Sensors/DhtSensor.cpp4
-rw-r--r--src/Heating/Sensors/DhtSensor.h2
-rw-r--r--src/Movement/StepperDrivers/TMC51xx.cpp6
-rw-r--r--src/Networking/Network.cpp2
-rw-r--r--src/Platform.cpp36
-rw-r--r--src/Platform.h4
-rw-r--r--src/PortControl.h2
-rw-r--r--src/RepRap.cpp8
-rw-r--r--src/RepRapFirmware.h18
-rw-r--r--src/Spindle.h2
-rw-r--r--src/Tasks.cpp2
-rw-r--r--src/Version.h6
29 files changed, 237 insertions, 119 deletions
diff --git a/.project b/.project
index c1983b6b..f47c0375 100644
--- a/.project
+++ b/.project
@@ -4,8 +4,8 @@
<comment></comment>
<projects>
<project>CoreNG</project>
- <project>FreeRTOS</project>
<project>RRFLibraries</project>
+ <project>FreeRTOS</project>
</projects>
<buildSpec>
<buildCommand>
diff --git a/src/BugList.txt b/src/BugList.txt
index ba594e4a..d88c66ea 100644
--- a/src/BugList.txt
+++ b/src/BugList.txt
@@ -135,8 +135,8 @@ Menu.cpp
MenuItem.h, cpp
Planned for 2.03:
-- I2C errors: can we recover from them?
-- check: is stop.g always run at end of SD print, not just in response to M0?
+- [done, community to test] I2C errors: recover from them
+- [done, ok] Separate task to keep DuetX endstop input state up to date
- [ok] check: start.g should not be run when resurrecting a print
- [on hold] investigate filament file not run on initial tool change, https://forum.duet3d.com/topic/9405/first-t0-in-gcode-does-not-work/5
diff --git a/src/CAN/CanSender.cpp b/src/CAN/CanSender.cpp
index e4ecf7c9..7f98db3f 100644
--- a/src/CAN/CanSender.cpp
+++ b/src/CAN/CanSender.cpp
@@ -379,7 +379,7 @@ void CanSender::Init()
configure_mcan();
// Create the task that sends CAN messages
- canSenderTask.Create(CanSenderLoop, "CanSender", nullptr, TaskBase::CanSenderPriority);
+ canSenderTask.Create(CanSenderLoop, "CanSender", nullptr, TaskPriority::CanSenderPriority);
}
// Add a buffer to the end of the send queue
diff --git a/src/Display/Display.cpp b/src/Display/Display.cpp
index 37dc7c20..3037737b 100644
--- a/src/Display/Display.cpp
+++ b/src/Display/Display.cpp
@@ -11,7 +11,7 @@
#include "GCodes/GCodes.h"
#include "GCodes/GCodeBuffer.h"
-#include "IoPorts.h"
+#include "Hardware/IoPorts.h"
#include "Pins.h"
constexpr int DefaultPulsesPerClick = -4; // values that work with displays I have are 2 and -4
diff --git a/src/Display/RotaryEncoder.cpp b/src/Display/RotaryEncoder.cpp
index c4ba8f6c..69273719 100644
--- a/src/Display/RotaryEncoder.cpp
+++ b/src/Display/RotaryEncoder.cpp
@@ -3,7 +3,7 @@
#if SUPPORT_12864_LCD
#include "Pins.h"
-#include "IoPorts.h"
+#include "Hardware/IoPorts.h"
RotaryEncoder::RotaryEncoder(Pin p0, Pin p1, Pin pb)
: pin0(p0), pin1(p1), pinButton(pb), ppc(1), encoderChange(0), encoderState(0), newPress(false), reverseDirection(false) {}
diff --git a/src/DuetNG/DueXn.cpp b/src/DuetNG/DueXn.cpp
index 3b4b745f..b415e66e 100644
--- a/src/DuetNG/DueXn.cpp
+++ b/src/DuetNG/DueXn.cpp
@@ -10,16 +10,17 @@
#include "Platform.h"
#include "RepRap.h"
#include "Wire.h"
+#include "Hardware/I2C.h"
namespace DuetExpansion
{
- const uint8_t DueXnAddress = 0x3E; // address of the SX1509B on the DueX2/DueX5
+ constexpr uint8_t DueXnAddress = 0x3E; // address of the SX1509B on the DueX2/DueX5
+ static constexpr unsigned int DueXTaskStackWords = 100; // task stack size in dwords
static SX1509 dueXnExpander;
static uint16_t dueXnInputMask;
static uint16_t dueXnInputBits = 0;
static ExpansionBoardType dueXnBoardType = ExpansionBoardType::none;
- static volatile bool dueXstateChanged = false;
const uint8_t AdditionalIoExpanderAddress = 0x71; // address of the SX1509B we allow for general I/O expansion
@@ -27,6 +28,11 @@ namespace DuetExpansion
static bool additionalIoExpanderPresent = false;
static uint16_t additionalIoInputBits = 0;
+ static volatile bool taskWaiting = false;
+ static volatile bool inputsChanged = false;
+
+ Task<DueXTaskStackWords> *dueXTask = nullptr;
+
// The original DueX2 and DueX5 boards had 2 board ID pins, bits 14 and 15.
// The new ones use bit 15 for fan 8, so not we just have bit 14.
// If we want any more variants, they will have to use a different I2C address.
@@ -56,15 +62,44 @@ namespace DuetExpansion
const unsigned int Gpio4Bit = 8;
const uint16_t AllGpioBits = (1u << Gpio1Bit) | (1u << Gpio2Bit) | (1u << Gpio3Bit) | (1u <<Gpio4Bit);
+ // ISR for when the SX1509B on the DueX indicates that the state of an input has changed.
+ // Note, we must only wake up the DueX task if it is waiting on this specific interrupt.
+ // Otherwise we might wake it prematurely when it is waiting for an I2C transaction to be completed.
static void DueXIrq(CallbackParameter p)
{
- dueXstateChanged = true;
+ inputsChanged = true;
+ if (taskWaiting)
+ {
+ taskWaiting = false;
+ dueXTask->GiveFromISR();
+ }
+ }
+
+ extern "C" [[noreturn]] void DueXTask(void * pvParameters)
+ {
+ for (;;)
+ {
+ inputsChanged = false;
+ dueXnInputBits = dueXnExpander.digitalReadAll();
+
+ cpu_irq_disable();
+ if (!inputsChanged)
+ {
+ taskWaiting = true;
+ cpu_irq_enable();
+ TaskBase::Take();
+ }
+ else
+ {
+ cpu_irq_enable();
+ }
+ }
}
// Identify which expansion board (if any) is attached and initialise it
ExpansionBoardType DueXnInit()
{
- reprap.GetPlatform().InitI2c(); // initialise I2C
+ I2C::Init(); // initialise I2C
// DC 2018-07-12: occasionally the SX1509B isn't found after doing a software reset, so try a few more attempts
bool ret;
@@ -103,8 +138,10 @@ namespace DuetExpansion
attachInterrupt(DueX_INT, DueXIrq, InterruptMode::INTERRUPT_MODE_FALLING, nullptr);
// Clear any initial interrupts
- (void)dueXnExpander.interruptSource(true);
- dueXnInputBits = dueXnExpander.digitalReadAll();
+ (void)dueXnExpander.interruptSourceAndClear();
+
+ dueXTask = new Task<DueXTaskStackWords>();
+ dueXTask->Create(DueXTask, "DUEX", nullptr, TaskPriority::DueXPriority);
}
return dueXnBoardType;
@@ -113,7 +150,7 @@ namespace DuetExpansion
// Look for an additional output pin expander
void AdditionalOutputInit()
{
- reprap.GetPlatform().InitI2c(); // initialise I2C
+ I2C::Init(); // initialise I2C
bool ret;
unsigned int attempts = 0;
@@ -155,20 +192,6 @@ namespace DuetExpansion
return (additionalIoExpanderPresent) ? "SX1509B expander" : nullptr;
}
- // Update the input bits. The purpose of this is so that the step interrupt can pick up values that are fairly up-to-date,
- // even though it is not safe for it to call expander.digitalReadAll(). When we move to RTOS, this will be a high priority task.
- void Spin()
- {
- if (dueXnBoardType != ExpansionBoardType::none && dueXstateChanged && !inInterrupt() && __get_BASEPRI() == 0)
- {
- // Interrupt occurred, so input data may have changed
- dueXstateChanged = false;
- dueXnInputBits = dueXnExpander.digitalReadAll();
- }
-
- // We don't have an interrupt from the additional I/O expander, so we don't poll it here
- }
-
// Set the I/O mode of a pin
void SetPinMode(Pin pin, PinMode mode)
{
diff --git a/src/DuetNG/DueXn.h b/src/DuetNG/DueXn.h
index bdd479c3..cc78db90 100644
--- a/src/DuetNG/DueXn.h
+++ b/src/DuetNG/DueXn.h
@@ -31,7 +31,6 @@ namespace DuetExpansion
void DigitalWrite(Pin pin, bool high); // Write a pin
void AnalogOut(Pin pin, float pwm); // Set the PWM value on this pin
uint16_t DiagnosticRead(); // Diagnose the SX1509 by setting all pins as inputs and reading them
- void Spin(); // Task to keep the endstop inputs up to date
void Diagnostics(MessageType mtype); // Print diagnostic data
};
diff --git a/src/DuetNG/SX1509.cpp b/src/DuetNG/SX1509.cpp
index 9c8bb129..a3412874 100644
--- a/src/DuetNG/SX1509.cpp
+++ b/src/DuetNG/SX1509.cpp
@@ -22,17 +22,17 @@ Distributed as-is; no warranty is given.
******************************************************************************/
#include "RepRapFirmware.h"
-#include "Wire.h"
#include "Tasks.h"
#include "SX1509.h"
#include "SX1509Registers.h"
-#include "RTOSIface/RTOSIface.h"
+#include "Hardware/I2C.h"
SX1509::SX1509() : _clkX(0)
{
}
-//************* Public functions. These must all acquire and release the I2C mutex around any I2C transactions. ***********
+// Public functions
+// Any operation requiring multiple I2C transactions must acquire and release the I2C mutex around them.
// Test for the presence of a SX1509B. The I2C subsystem must be initialised before calling this.
bool SX1509::begin(uint8_t address)
@@ -156,26 +156,24 @@ void SX1509::pinModeMultiple(uint16_t pins, PinMode inOut)
void SX1509::digitalWrite(uint8_t pin, bool highLow)
{
- MutexLocker lock(Tasks::GetI2CMutex());
-
if (((1u << pin) & pwmPins) != 0)
{
analogWrite(pin, (highLow) ? 255 : 0);
}
else if (highLow)
{
+ MutexLocker lock(Tasks::GetI2CMutex());
setBitsInWord(REG_DATA_B, 1u << pin);
}
else
{
+ MutexLocker lock(Tasks::GetI2CMutex());
clearBitsInWord(REG_DATA_B, 1u << pin);
}
}
bool SX1509::digitalRead(uint8_t pin)
{
- MutexLocker lock(Tasks::GetI2CMutex());
-
if (pin >= 8)
{
return (readByte(REG_DATA_B) & (1u << (pin - 8))) != 0;
@@ -188,8 +186,6 @@ bool SX1509::digitalRead(uint8_t pin)
uint16_t SX1509::digitalReadAll()
{
- MutexLocker lock(Tasks::GetI2CMutex());
-
return readWord(REG_DATA_B);
}
@@ -240,8 +236,6 @@ void SX1509::ledDriverInitMultiple(uint16_t pins, bool log, bool openDrain)
void SX1509::analogWrite(uint8_t pin, uint8_t iOn)
{
- MutexLocker lock(Tasks::GetI2CMutex());
-
// Write the on intensity of pin
// Linear mode: Ion = iOn
// Log mode: Ion = f(iOn)
@@ -292,23 +286,26 @@ void SX1509::enableInterruptMultiple(uint16_t pins, uint8_t riseFall)
}
writeDword(REG_SENSE_HIGH_B, pinMask);
-
clearBitsInWord(REG_INTERRUPT_MASK_B, pins);
}
-uint16_t SX1509::interruptSource(bool clear)
+uint16_t SX1509::interruptSource()
{
- const uint16_t intSource = readWord(REG_INTERRUPT_SOURCE_B);
- if (clear)
- {
- writeWord(REG_INTERRUPT_SOURCE_B, 0xFFFF); // Clear interrupts
- }
+ return readWord(REG_INTERRUPT_SOURCE_B);
+}
+
+uint16_t SX1509::interruptSourceAndClear()
+{
+ MutexLocker lock(Tasks::GetI2CMutex());
+
+ const uint16_t intSource = interruptSource();
+ writeWord(REG_INTERRUPT_SOURCE_B, intSource); // Clear interrupts
return intSource;
}
bool SX1509::checkInterrupt(uint8_t pin)
{
- return (interruptSource(false) & (1u << pin)) != 0;
+ return (interruptSource() & (1u << pin)) != 0;
}
//********* Private functions. The I2C mutex must be owned by the caller. ***********
@@ -413,7 +410,7 @@ uint8_t SX1509::readByte(uint8_t registerAddress)
{
uint8_t data[2];
data[0] = registerAddress;
- if (I2C_IFACE.Transfer(deviceAddress, data, 1, 1) == 2)
+ if (I2C::Transfer(deviceAddress, data, 1, 1) == 2)
{
return data[1];
}
@@ -429,7 +426,7 @@ uint16_t SX1509::readWord(uint8_t registerAddress)
{
uint8_t data[3];
data[0] = registerAddress;
- if (I2C_IFACE.Transfer(deviceAddress, data, 1, 2) == 3)
+ if (I2C::Transfer(deviceAddress, data, 1, 2) == 3)
{
return (data[1] << 8) | data[2];
}
@@ -445,7 +442,7 @@ uint32_t SX1509::readDword(uint8_t registerAddress)
{
uint8_t data[5];
data[0] = registerAddress;
- if (I2C_IFACE.Transfer(deviceAddress, data, 1, 4) == 5)
+ if (I2C::Transfer(deviceAddress, data, 1, 4) == 5)
{
return (data[1] << 24) | (data[2] << 16) | (data[3] << 8) | data[4];
}
@@ -460,7 +457,7 @@ uint32_t SX1509::readDword(uint8_t registerAddress)
void SX1509::writeByte(uint8_t registerAddress, uint8_t writeValue)
{
uint8_t data[2] = { registerAddress, writeValue };
- (void)I2C_IFACE.Transfer(deviceAddress, data, 2, 0);
+ (void)I2C::Transfer(deviceAddress, data, 2, 0);
}
// writeWord(uint8_t registerAddress, uint16_t writeValue)
@@ -471,7 +468,7 @@ void SX1509::writeByte(uint8_t registerAddress, uint8_t writeValue)
void SX1509::writeWord(uint8_t registerAddress, uint16_t writeValue)
{
uint8_t data[3] = { registerAddress, (uint8_t)(writeValue >> 8), (uint8_t)writeValue };
- (void)I2C_IFACE.Transfer(deviceAddress, data, 3, 0);
+ (void)I2C::Transfer(deviceAddress, data, 3, 0);
}
// writeDword(uint8_t registerAddress, uint32_t writeValue)
@@ -480,7 +477,7 @@ void SX1509::writeWord(uint8_t registerAddress, uint16_t writeValue)
void SX1509::writeDword(uint8_t registerAddress, uint32_t writeValue)
{
uint8_t data[5] = { registerAddress, (uint8_t)(writeValue >> 24), (uint8_t)(writeValue >> 16), (uint8_t)(writeValue >> 8), (uint8_t)writeValue };
- (void)I2C_IFACE.Transfer(deviceAddress, data, 5, 0);
+ (void)I2C::Transfer(deviceAddress, data, 5, 0);
}
// End
diff --git a/src/DuetNG/SX1509.h b/src/DuetNG/SX1509.h
index 64587c5c..41ebfe00 100644
--- a/src/DuetNG/SX1509.h
+++ b/src/DuetNG/SX1509.h
@@ -233,11 +233,9 @@ public:
// Output: 16-bit value, with a single bit set representing the pin(s) that
// generated an interrupt. E.g. a return value of 0x0104 would mean pins 8
// and 3 (bits 8 and 3) have generated an interrupt.
- // Input:
- // - clear: boolean commanding whether the interrupt should be cleared
- // after reading or not.
// -----------------------------------------------------------------------------
- uint16_t interruptSource(bool clear);
+ uint16_t interruptSource();
+ uint16_t interruptSourceAndClear();
// -----------------------------------------------------------------------------
// checkInterrupt(void): Checks if a single pin generated an interrupt.
diff --git a/src/GCodes/GCodes3.cpp b/src/GCodes/GCodes3.cpp
index 36a60cf4..2e2afd24 100644
--- a/src/GCodes/GCodes3.cpp
+++ b/src/GCodes/GCodes3.cpp
@@ -15,6 +15,7 @@
#include "Tools/Tool.h"
#include "PrintMonitor.h"
#include "Tasks.h"
+#include "Hardware/I2C.h"
#if HAS_WIFI_NETWORKING
# include "FirmwareUpdater.h"
@@ -1059,12 +1060,8 @@ GCodeResult GCodes::SendI2c(GCodeBuffer& gb, const StringRef &reply)
bValues[i] = (uint8_t)values[i];
}
- platform.InitI2c();
- size_t bytesTransferred;
- {
- MutexLocker lock(Tasks::GetI2CMutex());
- bytesTransferred = I2C_IFACE.Transfer(address, bValues, numToSend, numToReceive);
- }
+ I2C::Init();
+ const size_t bytesTransferred = I2C::Transfer(address, bValues, numToSend, numToReceive);
if (bytesTransferred < numToSend)
{
@@ -1109,14 +1106,10 @@ GCodeResult GCodes::ReceiveI2c(GCodeBuffer& gb, const StringRef &reply)
const uint32_t numBytes = gb.GetUIValue();
if (numBytes > 0 && numBytes <= MaxI2cBytes)
{
- platform.InitI2c();
+ I2C::Init();
uint8_t bValues[MaxI2cBytes];
- size_t bytesRead;
- {
- MutexLocker lock(Tasks::GetI2CMutex());
- bytesRead = I2C_IFACE.Transfer(address, bValues, 0, numBytes);
- }
+ const size_t bytesRead = I2C::Transfer(address, bValues, 0, numBytes);
reply.copy("Received");
if (bytesRead == 0)
diff --git a/src/DmacManager.cpp b/src/Hardware/DmacManager.cpp
index d11a92f0..d11a92f0 100644
--- a/src/DmacManager.cpp
+++ b/src/Hardware/DmacManager.cpp
diff --git a/src/DmacManager.h b/src/Hardware/DmacManager.h
index 23a3c328..23a3c328 100644
--- a/src/DmacManager.h
+++ b/src/Hardware/DmacManager.h
diff --git a/src/Hardware/I2C.cpp b/src/Hardware/I2C.cpp
new file mode 100644
index 00000000..9db08524
--- /dev/null
+++ b/src/Hardware/I2C.cpp
@@ -0,0 +1,66 @@
+/*
+ * I2C.cpp
+ *
+ * Created on: 13 May 2019
+ * Author: David
+ */
+
+#include "I2C.h"
+#include "Tasks.h"
+
+#if defined(I2C_IFACE)
+static bool i2cInitialised = false;
+#endif
+
+// Initialise the I2C interface, if not already done
+void I2C::Init()
+{
+#if defined(I2C_IFACE)
+ if (!i2cInitialised)
+ {
+ MutexLocker lock(Tasks::GetI2CMutex());
+ if (!i2cInitialised) // test it again, now that we own the mutex
+ {
+ I2C_IFACE.BeginMaster(I2cClockFreq);
+ i2cInitialised = true;
+ }
+ }
+#endif
+}
+
+#if defined(I2C_IFACE) && defined(RTOS)
+
+#include "RTOSIface/RTOSIface.h"
+
+static TaskHandle_t twiTask = nullptr; // the task that is waiting for a TWI command to complete
+
+extern "C" void WIRE_ISR_HANDLER()
+{
+ WIRE_INTERFACE->TWI_IDR = 0xFFFFFFFF;
+ if (twiTask != nullptr)
+ {
+ BaseType_t higherPriorityTaskWoken = pdFALSE;
+ vTaskNotifyGiveFromISR(twiTask, &higherPriorityTaskWoken); // wake up the task
+ twiTask = nullptr;
+ portYIELD_FROM_ISR(higherPriorityTaskWoken);
+ }
+}
+
+uint32_t I2C::statusWaitFunc(Twi *twi, uint32_t bitsToWaitFor)
+{
+ uint32_t sr = twi->TWI_SR;
+ if ((sr & bitsToWaitFor) == 0)
+ {
+ // Suspend this task until we get an interrupt indicating that a status bit that we are interested in has been set
+ twiTask = xTaskGetCurrentTaskHandle();
+ twi->TWI_IER = bitsToWaitFor;
+ (void)TaskBase::Take(2);
+ sr = twi->TWI_SR;
+ twi->TWI_IDR = 0xFFFFFFFF;
+ }
+ return sr;
+}
+
+#endif
+
+// End
diff --git a/src/Hardware/I2C.h b/src/Hardware/I2C.h
new file mode 100644
index 00000000..46fe135f
--- /dev/null
+++ b/src/Hardware/I2C.h
@@ -0,0 +1,48 @@
+/*
+ * I2C.h
+ *
+ * Created on: 13 May 2019
+ * Author: David
+ */
+
+#ifndef SRC_HARDWARE_I2C_H_
+#define SRC_HARDWARE_I2C_H_
+
+#include "Wire.h"
+#include "RepRapFirmware.h"
+#include "Tasks.h"
+
+namespace I2C
+{
+ void Init();
+
+#ifdef I2C_IFACE
+
+#ifdef RTOS
+
+ uint32_t statusWaitFunc(Twi *twi, uint32_t bitsToWaitFor);
+
+ // Transfer data to/from an I2C peripheral.
+ // If the caller needs to do multiple I2C transactions without being interrupted, it should own the i2C mutex before calling this.
+ // Otherwise the caller need nort own the mutex because it will be acquired here.
+ inline size_t Transfer(uint16_t address, uint8_t *buffer, size_t numToWrite, size_t numToRead)
+ {
+ MutexLocker Lock(Tasks::GetI2CMutex());
+ return I2C_IFACE.Transfer(address, buffer, numToWrite, numToRead, statusWaitFunc);
+ }
+
+#else
+
+ // Transfer data to/from an I2C peripheral
+ inline size_t Transfer(uint16_t address, uint8_t *buffer, size_t numToWrite, size_t numToRead)
+ {
+ return I2C_IFACE.Transfer(address, buffer, numToWrite, numToRead);
+ }
+
+#endif
+
+#endif
+
+}
+
+#endif /* SRC_HARDWARE_I2C_H_ */
diff --git a/src/IoPorts.cpp b/src/Hardware/IoPorts.cpp
index 0fb1605d..0fb1605d 100644
--- a/src/IoPorts.cpp
+++ b/src/Hardware/IoPorts.cpp
diff --git a/src/IoPorts.h b/src/Hardware/IoPorts.h
index 9570e72c..9570e72c 100644
--- a/src/IoPorts.h
+++ b/src/Hardware/IoPorts.h
diff --git a/src/Heating/Heat.cpp b/src/Heating/Heat.cpp
index cd852262..8362c3e1 100644
--- a/src/Heating/Heat.cpp
+++ b/src/Heating/Heat.cpp
@@ -154,7 +154,7 @@ void Heat::Init()
coldExtrude = false;
#ifdef RTOS
- heaterTask.Create(HeaterTask, "HEAT", nullptr, TaskBase::HeatPriority);
+ heaterTask.Create(HeaterTask, "HEAT", nullptr, TaskPriority::HeatPriority);
#else
lastTime = millis() - HeatSampleIntervalMillis; // flag the PIDS as due for spinning
active = true;
diff --git a/src/Heating/Sensors/DhtSensor.cpp b/src/Heating/Sensors/DhtSensor.cpp
index fa255901..51af304e 100644
--- a/src/Heating/Sensors/DhtSensor.cpp
+++ b/src/Heating/Sensors/DhtSensor.cpp
@@ -9,7 +9,7 @@
#include "RepRap.h"
#include "GCodes/GCodeBuffer.h"
#include "Movement/StepTimer.h"
-#include "IoPorts.h"
+#include "Hardware/IoPorts.h"
#if SUPPORT_DHT_SENSOR
@@ -137,7 +137,7 @@ DhtSensorHardwareInterface *DhtSensorHardwareInterface::Create(unsigned int rela
if (dhtTask == nullptr)
{
dhtTask = new Task<DhtTaskStackWords>;
- dhtTask->Create(DhtTask, "DHTSENSOR", nullptr, TaskBase::HeatPriority);
+ dhtTask->Create(DhtTask, "DHTSENSOR", nullptr, TaskPriority::DhtPriority);
}
return activeSensors[relativeChannel];
diff --git a/src/Heating/Sensors/DhtSensor.h b/src/Heating/Sensors/DhtSensor.h
index 37eb0472..0263b7c0 100644
--- a/src/Heating/Sensors/DhtSensor.h
+++ b/src/Heating/Sensors/DhtSensor.h
@@ -48,7 +48,7 @@ private:
void TakeReading();
TemperatureError ProcessReadings();
- static constexpr uint32_t DhtTaskStackWords = 100; // task stack size in dwords. 80 was not enough. Use 300 if debugging is enabled.
+ static constexpr unsigned int DhtTaskStackWords = 100; // task stack size in dwords. 80 was not enough. Use 300 if debugging is enabled.
static Mutex dhtMutex;
static Task<DhtTaskStackWords> *dhtTask;
static DhtSensorHardwareInterface *activeSensors[MaxSpiTempSensors];
diff --git a/src/Movement/StepperDrivers/TMC51xx.cpp b/src/Movement/StepperDrivers/TMC51xx.cpp
index 3bf3d676..2613793f 100644
--- a/src/Movement/StepperDrivers/TMC51xx.cpp
+++ b/src/Movement/StepperDrivers/TMC51xx.cpp
@@ -12,7 +12,7 @@
#if SUPPORT_TMC51xx
#include "RTOSIface/RTOSIface.h"
-#include <Movement/Move.h>
+#include "Movement/Move.h"
#ifdef SAME51
# include "HAL/IoPorts.h"
@@ -20,7 +20,7 @@
# include "peripheral_clk_config.h"
# include "HAL/SAME5x.h"
#elif SAME70
-# include "DmacManager.h"
+# include "Hardware/DmacManager.h"
#endif
//#define TMC_TYPE 5130
@@ -1289,7 +1289,7 @@ namespace SmartDrivers
xdmac_enable_interrupt(XDMAC, DmacChanTmcRx);
#endif
- tmcTask.Create(TmcLoop, "TMC", nullptr, TaskBase::TmcPriority);
+ tmcTask.Create(TmcLoop, "TMC", nullptr, TaskPriority::TmcPriority);
}
void SetAxisNumber(size_t driver, uint32_t axisNumber)
diff --git a/src/Networking/Network.cpp b/src/Networking/Network.cpp
index 6f3557d5..c0217380 100644
--- a/src/Networking/Network.cpp
+++ b/src/Networking/Network.cpp
@@ -274,7 +274,7 @@ void Network::Activate()
}
#ifdef RTOS
- networkTask.Create(NetworkLoop, "NETWORK", nullptr, TaskBase::SpinPriority);
+ networkTask.Create(NetworkLoop, "NETWORK", nullptr, TaskPriority::SpinPriority);
#endif
}
diff --git a/src/Platform.cpp b/src/Platform.cpp
index 1edfb007..eb7160bb 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -35,9 +35,9 @@
#include "SoftTimer.h"
#include "Logger.h"
#include "Tasks.h"
-#include "DmacManager.h"
+#include "Hardware/DmacManager.h"
#include "Math/Isqrt.h"
-#include "Wire.h"
+#include "Hardware/I2C.h"
#ifndef __LPC17xx__
# include "sam/drivers/tc/tc.h"
@@ -166,13 +166,13 @@ extern "C" void UrgentInit()
uint8_t Platform::softwareResetDebugInfo = 0; // extra info for debugging
-Platform::Platform() :
- logger(nullptr), board(DEFAULT_BOARD_TYPE), active(false), errorCodeBits(0),
+Platform::Platform()
+ : logger(nullptr), board(DEFAULT_BOARD_TYPE), active(false), errorCodeBits(0),
#if HAS_SMART_DRIVERS
- nextDriveToPoll(0),
+ nextDriveToPoll(0),
#endif
- lastFanCheckTime(0), auxGCodeReply(nullptr), sysDir(nullptr), tickState(0), debugCode(0),
- lastWarningMillis(0), deliberateError(false), i2cInitialised(false)
+ lastFanCheckTime(0), auxGCodeReply(nullptr), sysDir(nullptr), tickState(0), debugCode(0),
+ lastWarningMillis(0), deliberateError(false)
{
massStorage = new MassStorage(this);
}
@@ -292,7 +292,7 @@ void Platform::Init()
ARRAY_INIT(defaultMacAddress, DefaultMacAddress);
// Motor current setting on Duet 0.6 and 0.8.5
- InitI2c();
+ I2C::Init();
mcpExpansion.setMCP4461Address(0x2E); // not required for mcpDuet, as this uses the default address
ARRAY_INIT(potWipes, POT_WIPES);
senseResistor = SENSE_RESISTOR;
@@ -2356,8 +2356,8 @@ void Platform::Diagnostics(MessageType mtype)
#ifdef I2C_IFACE
const TwoWire::ErrorCounts errs = I2C_IFACE.GetErrorCounts(true);
- MessageF(mtype, "I2C nak errors %" PRIu32 ", send timeouts %" PRIu32 ", receive timeouts %" PRIu32 ", finishTimeouts %" PRIu32 "\n",
- errs.naks, errs.sendTimeouts, errs.recvTimeouts, errs.finishTimeouts);
+ MessageF(mtype, "I2C nak errors %" PRIu32 ", send timeouts %" PRIu32 ", receive timeouts %" PRIu32 ", finishTimeouts %" PRIu32 ", resets %" PRIu32 "\n",
+ errs.naks, errs.sendTimeouts, errs.recvTimeouts, errs.finishTimeouts, errs.resets);
#endif
}
@@ -4782,22 +4782,6 @@ bool Platform::SetDateTime(time_t time)
return ok;
}
-// Initialise the I2C interface, if not already done
-void Platform::InitI2c()
-{
-#if defined(I2C_IFACE)
- if (!i2cInitialised)
- {
- MutexLocker lock(Tasks::GetI2CMutex());
- if (!i2cInitialised) // test it again, now that we own the mutex
- {
- I2C_IFACE.BeginMaster(I2cClockFreq);
- i2cInitialised = true;
- }
- }
-#endif
-}
-
#if SAM4E || SAM4S || SAME70
// Get a pseudo-random number
diff --git a/src/Platform.h b/src/Platform.h
index 0a5fde72..c511e00e 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -29,7 +29,7 @@ Licence: GPL
// Platform-specific includes
#include "RepRapFirmware.h"
-#include "IoPorts.h"
+#include "Hardware/IoPorts.h"
#include "DueFlashStorage.h"
#include "Fans/Fan.h"
#include "Fans/Tacho.h"
@@ -610,7 +610,6 @@ public:
float GetLaserPwmFrequency() const { return laserPort.GetFrequency(); }
// Misc
- void InitI2c();
#if SAM4E || SAM4S || SAME70
uint32_t Random();
@@ -936,7 +935,6 @@ private:
// Misc
bool deliberateError; // true if we deliberately caused an exception for testing purposes
- bool i2cInitialised; // true if the I2C subsystem has been initialised
};
// Where the htm etc files are
diff --git a/src/PortControl.h b/src/PortControl.h
index 455f2529..fd17527d 100644
--- a/src/PortControl.h
+++ b/src/PortControl.h
@@ -9,7 +9,7 @@
#define SRC_PORTCONTROL_H_
#include "RepRapFirmware.h"
-#include "IoPorts.h" // for PinConfiguration
+#include "Hardware/IoPorts.h" // for PinConfiguration
class GCodeBuffer;
diff --git a/src/RepRap.cpp b/src/RepRap.cpp
index 76e42b34..70c48857 100644
--- a/src/RepRap.cpp
+++ b/src/RepRap.cpp
@@ -43,7 +43,7 @@ static_assert(CONF_HSMCI_XDMAC_CHANNEL == DmacChanHsmci, "mismatched DMA channel
# include "task.h"
# if SAME70
-# include "DmacManager.h"
+# include "Hardware/DmacManager.h"
# endif
// We call vTaskNotifyGiveFromISR from various interrupts, so the following must be true
@@ -409,12 +409,6 @@ void RepRap::Spin()
spinningModule = modulePrintMonitor;
printMonitor->Spin();
-#ifdef DUET_NG
- ticksInSpinState = 0;
- spinningModule = moduleDuetExpansion;
- DuetExpansion::Spin();
-#endif
-
ticksInSpinState = 0;
spinningModule = moduleFilamentSensors;
FilamentMonitor::Spin();
diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h
index 3483790c..e4e8f05a 100644
--- a/src/RepRapFirmware.h
+++ b/src/RepRapFirmware.h
@@ -335,6 +335,24 @@ constexpr float RadiansToDegrees = 180.0/3.141592653589793;
typedef uint32_t FilePosition;
const FilePosition noFilePosition = 0xFFFFFFFF;
+#ifdef RTOS
+
+// Task priorities
+namespace TaskPriority
+{
+ static constexpr int SpinPriority = 1; // priority for tasks that rarely block
+ static constexpr int HeatPriority = 2;
+ static constexpr int DhtPriority = 2;
+ static constexpr int TmcPriority = 2;
+ static constexpr int AinPriority = 2;
+ static constexpr int DueXPriority = 3;
+ static constexpr int LaserPriority = 3;
+ static constexpr int CanSenderPriority = 3;
+ static constexpr int CanReceiverPriority = 3;
+}
+
+#endif
+
//-------------------------------------------------------------------------------------------------
// Interrupt priorities - must be chosen with care! 0 is the highest priority, 15 is the lowest.
// This interacts with FreeRTOS config constant configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY which is currently defined as 3 for the SAME70 and 5 for the SAM4x.
diff --git a/src/Spindle.h b/src/Spindle.h
index 5e05993c..b1e7f3d2 100644
--- a/src/Spindle.h
+++ b/src/Spindle.h
@@ -9,7 +9,7 @@
#define SPINDLE_H
#include "RepRapFirmware.h"
-#include "IoPorts.h"
+#include "Hardware/IoPorts.h"
class Spindle
{
diff --git a/src/Tasks.cpp b/src/Tasks.cpp
index 545bddb9..abae4da6 100644
--- a/src/Tasks.cpp
+++ b/src/Tasks.cpp
@@ -137,7 +137,7 @@ extern "C" void AppMain()
# endif
// Create the startup task
- mainTask.Create(MainTask, "MAIN", nullptr, TaskBase::SpinPriority);
+ mainTask.Create(MainTask, "MAIN", nullptr, TaskPriority::SpinPriority);
vTaskStartScheduler(); // doesn't return
}
diff --git a/src/Version.h b/src/Version.h
index 2c8274bc..14b3437a 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -11,16 +11,16 @@
#ifndef VERSION
#ifdef RTOS
-# define MAIN_VERSION "2.03RC1+1"
+# define MAIN_VERSION "2.03RC2"
#else
-# define MAIN_VERSION "1.24RC1+1"
+# define MAIN_VERSION "1.24RC2"
#endif
# define VERSION MAIN_VERSION
#endif
#ifndef DATE
-# define DATE "2019-05-11b1"
+# define DATE "2019-05-14b2"
#endif
#define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman, printm3d"