diff --git a/Configuration.h b/Configuration.h index 227cc83..a70a204 100644 --- a/Configuration.h +++ b/Configuration.h @@ -24,9 +24,16 @@ Licence: GPL #define CONFIGURATION_H #define NAME "RepRapFirmware" -#define VERSION "1.09h-dc42" -#define DATE "2015-08-24" -#define AUTHORS "reprappro, dc42, zpl" + +#ifndef VERSION +#define VERSION "1.09i-dc42" +#endif + +#ifndef DATE +#define DATE "2015-09-02" +#endif + +#define AUTHORS "reprappro, dc42, zpl, t3p3, dnewman" #define FLASH_SAVE_ENABLED (1) diff --git a/DDA.cpp b/DDA.cpp index 6a9787e..28d10c6 100644 --- a/DDA.cpp +++ b/DDA.cpp @@ -738,18 +738,14 @@ extern uint32_t maxReps; // This is called by the interrupt service routine to execute steps. // It returns true if it needs to be called again on the DDA of the new current move, otherwise false. +// This must be as fast as possible, because it determines the maximum movement speed. bool DDA::Step() { bool repeat; uint32_t numReps = 0; do { - ++numReps; - if (numReps > maxReps) - { - maxReps = numReps; - } - + // Keep this loop as fast as possible, in the case that there are no endstops to check! // Check endstop switches and Z probe if asked if (endStopsToCheck != 0) // if any homing switches or the Z probe is enabled in this move { @@ -819,47 +815,63 @@ bool DDA::Step() } } } + + if (state == completed) // we may have completed the move due to triggering an endstop switch or Z probe + { + break; + } } - if (state != completed) + // Generate any steps that are now due, overdue, or will be due very shortly + DriveMovement* dm = firstDM; + if (dm == nullptr) // I don't think this should happen, but best to be sure { - DriveMovement* dm = firstDM; - if (dm == nullptr) // I don't think this should happen, but best to be sure + state = completed; + break; + } + + const uint32_t elapsedTime = (Platform::GetInterruptClocks() - moveStartTime) + minInterruptInterval; + while (elapsedTime >= dm->nextStepTime) // if the next step is due + { + size_t drive = dm->drive; + reprap.GetPlatform()->StepHigh(drive); + ++numReps; + firstDM = dm->nextDM; + bool moreSteps = (isDeltaMovement && drive < AXES) ? dm->CalcNextStepTimeDelta(*this, drive) : dm->CalcNextStepTimeCartesian(*this, drive); + if (moreSteps) + { + InsertDM(dm); + } + else if (firstDM == nullptr) { state = completed; - } - else if ((Platform::GetInterruptClocks() - moveStartTime) + minInterruptInterval > dm->nextStepTime) // if the next step is due - { - size_t drive = dm->drive; - reprap.GetPlatform()->StepHigh(drive); - firstDM = dm->nextDM; - bool moreSteps = (isDeltaMovement && drive < AXES) ? dm->CalcNextStepTimeDelta(*this, drive) : dm->CalcNextStepTimeCartesian(*this, drive); - if (moreSteps) - { - InsertDM(dm); - } - else if (firstDM == nullptr) - { - state = completed; - } reprap.GetPlatform()->StepLow(drive); + goto quit; // yukky multi-level break, but saves us another test in this time-critical code + } + reprap.GetPlatform()->StepLow(drive); + dm = firstDM; + //uint32_t t3 = Platform::GetInterruptClocks() - t2; //if (t3 > maxCalcTime) maxCalcTime = t3; //if (t3 < minCalcTime) minCalcTime = t3; - } - } - - if (state == completed) - { - uint32_t finishTime = moveStartTime + clocksNeeded; // calculate how long this move should take - Move *move = reprap.GetMove(); - move->CurrentMoveCompleted(); // tell Move that the current move is complete - return move->StartNextMove(finishTime); // schedule the next move } repeat = reprap.GetPlatform()->ScheduleInterrupt(firstDM->nextStepTime + moveStartTime); } while (repeat); +quit: + if (numReps > maxReps) + { + maxReps = numReps; + } + + if (state == completed) + { + uint32_t finishTime = moveStartTime + clocksNeeded; // calculate how long this move should take + Move *move = reprap.GetMove(); + move->CurrentMoveCompleted(); // tell Move that the current move is complete + return move->StartNextMove(finishTime); // schedule the next move + } return false; } diff --git a/DDA.h b/DDA.h index 690b592..5d2b1e1 100644 --- a/DDA.h +++ b/DDA.h @@ -69,10 +69,9 @@ public: // the calculation can just be managed in time at speeds of 15000mm/min (step interval 50us), but not at 20000mm/min (step interval 37.5us). // Therefore, where the step interval falls below 70us, we don't calculate on every step. static const int32_t MinCalcInterval = (70 * stepClockRate)/1000000; // the smallest sensible interval between calculations (70us) in step timer clocks - -private: static const uint32_t minInterruptInterval = 6; // about 2us minimum interval between interrupts, in clocks +private: void RecalculateMove(); void CalcNewSpeeds(); void ReduceHomingSpeed(); // called to reduce homing speed when a near-endstop is triggered diff --git a/Dictionay b/Dictionay new file mode 100644 index 0000000..1a68717 --- /dev/null +++ b/Dictionay @@ -0,0 +1,7 @@ +duet +thermistor +debounce +struct +arduino +extruder +deprecated diff --git a/GCodeBuffer.cpp b/GCodeBuffer.cpp index a4af71c..ff2a840 100644 --- a/GCodeBuffer.cpp +++ b/GCodeBuffer.cpp @@ -344,7 +344,18 @@ long GCodeBuffer::GetLValue() // Return true if this buffer contains a poll request or empty request that can be executed while macros etc. from another source are being completed bool GCodeBuffer::IsPollRequest() { - return state == executing && (IsEmpty() || (Seen('M') && GetIValue() == 105)); + if (state == executing) + { if (IsEmpty()) + { + return true; + } + if (Seen('M')) + { + int i = GetIValue(); + return i == 105 || i == 408; + } + } + return false; } // End diff --git a/GCodes.cpp b/GCodes.cpp index 059d1ec..ae9aec8 100644 --- a/GCodes.cpp +++ b/GCodes.cpp @@ -354,7 +354,8 @@ void GCodes::Spin() case GCodeState::resuming3: if (AllMovesAreFinishedAndMoveBufferIsLoaded()) { - platform->SetFanValue(pausedFanValue); + platform->SetFanValue(0,pausedFan0Value); + platform->SetFanValue(1,pausedFan1Value); fileBeingPrinted.MoveFrom(fileToPrint); for (size_t drive = AXES; drive < DRIVES; ++drive) { @@ -2256,8 +2257,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) bool resend = false; int code = gb->GetIValue(); - if (simulating && (code < 20 || code > 37) && code != 82 && code != 83 && code != 111 && code != 105 && code != 122 - && code != 999) + if (simulating && (code < 20 || code > 37) && code != 82 && code != 83 && code != 111 && code != 105 && code != 122 && code != 999) { return true; // we don't yet simulate most M codes } @@ -2536,7 +2536,8 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) pausedMoveBuffer[DRIVES] = moveBuffer[DRIVES]; } - pausedFanValue = platform->GetFanValue(); + pausedFan0Value = platform->GetFanValue(0); + pausedFan1Value = platform->GetFanValue(1); fileToPrint.MoveFrom(fileBeingPrinted); fileGCode->Pause(); state = GCodeState::pausing1; @@ -2843,42 +2844,50 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) break; case 106: // Set/report fan values + { + bool seen = false; + int fanNum = 0; //default to the first fan + if (gb->Seen('P')) // Choose fan number { - bool seen = false; - - if (gb->Seen('I')) // Invert cooling - { - coolingInverted = (gb->GetIValue() > 0); - seen = true; - } - - if (gb->Seen('S')) // Set new fan value - { - float f = gb->GetFValue(); - f = min(f, 255.0); - f = max(f, 0.0); - seen = true; - if (coolingInverted) - { - // Check if 1.0 or 255.0 may be used as the maximum value - platform->SetFanValue((f <= 1.0 ? 1.0 : 255.0) - f); - } - else - { - platform->SetFanValue(f); - } - } - - if (!seen) - { - float f = coolingInverted ? (1.0 - platform->GetFanValue()) : platform->GetFanValue(); - reply.printf("Fan value: %d%%, Cooling inverted: %s\n", (byte) (f * 100.0), coolingInverted ? "yes" : "no"); + fanNum = gb->GetIValue(); + if(fanNum !=0 && fanNum !=1){ + reply.printf("Fan value: %i is invalid, 0 or 1 are valid", fanNum); } } + + if (gb->Seen('I')) // Invert cooling + { + coolingInverted = (gb->GetIValue() > 0); + seen = true; + } + + if (gb->Seen('S')) // Set new fan value + { + float f = gb->GetFValue(); + f = min(f, 255.0); + f = max(f, 0.0); + seen = true; + if (coolingInverted) + { + // Check if 1.0 or 255.0 may be used as the maximum value + platform->SetFanValue(fanNum,(f <= 1.0 ? 1.0 : 255.0) - f); + } + else + { + platform->SetFanValue(fanNum,f); + } + } + + if (!seen) + { + float f = coolingInverted ? (1.0 - platform->GetFanValue(fanNum)) : platform->GetFanValue(fanNum); + reply.printf("Fan%i value: %d%%, Cooling inverted: %s\n",fanNum, (byte) (f * 100.0), coolingInverted ? "yes" : "no"); + } + } break; case 107: // Fan off - deprecated - platform->SetFanValue(coolingInverted ? 255.0 : 0.0); + platform->SetFanValue(0,coolingInverted ? 255.0 : 0.0); //T3P3 as deprecated only applies to fan0 break; case 109: // Deprecated @@ -2937,8 +2946,15 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) reply.cat("\n"); break; - case 115: // Print firmware version - reply.printf("FIRMWARE_NAME:%s FIRMWARE_VERSION:%s ELECTRONICS:%s DATE:%s\n", NAME, VERSION, ELECTRONICS, DATE); + case 115: // Print firmware version or set hardware type + if (gb->Seen('P')) + { + platform->SetBoardType((BoardType)gb->GetIValue()); + } + else + { + reply.printf("FIRMWARE_NAME: %s FIRMWARE_VERSION: %s ELECTRONICS: %s DATE: %s\n", NAME, VERSION, platform->GetElectronicsString(), DATE); + } break; case 116: // Wait for everything, especially set temperatures @@ -3769,12 +3785,6 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) seen = true; } - if (gb->Seen('R')) - { - platform->SetZProbeChannel(gb->GetIValue()); - seen = true; - } - if (gb->Seen('S')) { ZProbeParameters params = platform->GetZProbeParameters(); @@ -3793,7 +3803,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) if (!seen) { - reply.printf("Z Probe type %d, channel %d, dive height %.1f", platform->GetZProbeType(), platform->GetZProbeChannel(), platform->GetZProbeDiveHeight()); + reply.printf("Z Probe type %d, dive height %.1f", platform->GetZProbeType(), platform->GetZProbeDiveHeight()); if (platform->GetZProbeType() == 5) { ZProbeParameters params = platform->GetZProbeParameters(); @@ -3971,14 +3981,52 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) case 569: // Set/report axis direction if (gb->Seen('P')) { - int8_t drive = gb->GetIValue(); - if (gb->Seen('S')) + size_t drive = gb->GetIValue(); + if (drive < DRIVES) { - platform->SetDirectionValue(drive, gb->GetIValue()); - } - else - { - reply.printf("A %d sends drive %d forwards.\n", (int) platform->GetDirectionValue(drive), drive); + bool seen = false; + if (gb->Seen('S')) + { + platform->SetDirectionValue(drive, gb->GetIValue()); + seen = true; + } + if (gb->Seen('R')) + { + platform->SetEnableValue(drive, gb->GetIValue() != 0); + seen = true; + } + for (size_t axis = 0; axis < AXES; ++axis) + { + if (gb->Seen(axisLetters[axis])) + { + platform->SetPhysicalDrive(drive, axis); + seen = true; + } + } + if (gb->Seen(extrudeLetter)) + { + size_t extruder = gb->GetIValue(); + if (extruder + AXES < DRIVES) + { + platform->SetPhysicalDrive(drive, extruder + AXES); + } + seen = true; + } + if (!seen) + { + int physicalDrive = platform->GetPhysicalDrive(drive); + if (physicalDrive < 0) + { + reply.printf("Driver %u is not used\n", drive); + } + else + { + const char phyDriveLetter = (physicalDrive < AXES) ? axisLetters[physicalDrive] : extrudeLetter; + const int phyDriveNumber = (physicalDrive < AXES) ? 0 : physicalDrive - AXES; + reply.printf("Driver %u drives the %c%d motor, a %d sends it forwards and a %d enables it\n", + drive, phyDriveLetter, phyDriveNumber, (int) platform->GetDirectionValue(drive), (int) platform->GetEnableValue(drive)); + } + } } } break; diff --git a/GCodes.h b/GCodes.h index 94d7c7b..3dc6ab1 100644 --- a/GCodes.h +++ b/GCodes.h @@ -204,7 +204,8 @@ class GCodes bool limitAxes; // Don't think outside the box. bool axisIsHomed[AXES]; // These record which of the axes have been homed bool coolingInverted; - float pausedFanValue; + float pausedFan0Value; + float pausedFan1Value; float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60 float speedFactorChange; // factor by which we changed the speed factor since the last move float extrusionFactors[DRIVES - AXES]; // extrusion factors (normally 1.0) @@ -238,6 +239,7 @@ inline int8_t GCodes::Heater(int8_t head) const return head+1; } +//@TOTO T3P3 cooling inverted applies for both PWM fans inline bool GCodes::CoolingInverted() const { return coolingInverted; diff --git a/Libraries/SamNonDuePin/SamNonDuePin.cpp b/Libraries/SamNonDuePin/SamNonDuePin.cpp index f84adb4..1a946cc 100644 --- a/Libraries/SamNonDuePin/SamNonDuePin.cpp +++ b/Libraries/SamNonDuePin/SamNonDuePin.cpp @@ -37,15 +37,25 @@ extern const PinDescription nonDuePinDescription[]= { PIOC, PIO_PC8B_PWML3, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH3, NOT_ON_TIMER }, // PWM X5 { PIOC, PIO_PC2B_PWML0, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH0, NOT_ON_TIMER }, // PWM X6 { PIOC, PIO_PC6B_PWML2, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH2, NOT_ON_TIMER }, // PWM X7 - { PIOC, PIO_PC20, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PWM X8 - // 9 .. 14 + { PIOC, PIO_PC20, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X8 + { PIOD, PIO_PD9, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X9 + //10-14 + { PIOC, PIO_PC29, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X10 + { PIOC, PIO_PC30, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X11 + { PIOC, PIO_PC10, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X12 + { PIOC, PIO_PC28, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X13 + { PIOB, PIO_PB22, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X14 + { PIOB, PIO_PB23, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X15 + { PIOB, PIO_PB24, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN X16 + { PIOC, PIO_PC4B_PWML1, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH1, NOT_ON_TIMER }, // PWM X17 + // 18-23 - HSMCI { PIOA, PIO_PA20A_MCCDA, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN_HSMCI_MCCDA_GPIO { PIOA, PIO_PA19A_MCCK, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN_HSMCI_MCCK_GPIO { PIOA, PIO_PA21A_MCDA0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN_HSMCI_MCDA0_GPIO { PIOA, PIO_PA22A_MCDA1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN_HSMCI_MCDA1_GPIO { PIOA, PIO_PA23A_MCDA2, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN_HSMCI_MCDA2_GPIO { PIOA, PIO_PA24A_MCDA3, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN_HSMCI_MCDA3_GPIO - // 15 .. 24 - ETHERNET MAC + // 24-33 - ETHERNET MAC { PIOB, PIO_PB0A_ETXCK, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ETXCK { PIOB, PIO_PB1A_ETXEN, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ETXEN { PIOB, PIO_PB2A_ETX0, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ETX0 @@ -55,12 +65,11 @@ extern const PinDescription nonDuePinDescription[]= { PIOB, PIO_PB6A_ERX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ERX1 { PIOB, PIO_PB7A_ERXER, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ERXER { PIOB, PIO_PB8A_EMDC, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // EMDC - { PIOB, PIO_PB9A_EMDIO, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // EMDIO - // 25 - { PIOC, PIO_PC10, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER } // PIN X25 + { PIOB, PIO_PB9A_EMDIO, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER } // EMDIO + }; -const uint32_t MaxPinNumber = X25; +const uint32_t MaxPinNumber = X17; /* pinModeNonDue @@ -177,6 +186,14 @@ extern int digitalReadNonDue( uint32_t ulPin ) return (PIO_Get(pinDesc.pPort, PIO_INPUT, pinDesc.ulPin ) == 1) ? HIGH : LOW; } +// Build a short-form pin descriptor for a IO pin +OutputPin::OutputPin(unsigned int pin) +{ + const PinDescription& pinDesc = (pin >= X0) ? nonDuePinDescription[pin - X0] : g_APinDescription[pin]; + pPort = pinDesc.pPort; + ulPin = pinDesc.ulPin; +} + static bool nonDuePWMEnabled = 0; static bool PWMChanEnabled[8] = {false,false,false,false, false,false,false,false}; // there are only 8 PWM channels @@ -184,7 +201,8 @@ static bool PWMChanEnabled[8] = {false,false,false,false, false,false,false,fals static void PWMC_ConfigureChannel_fixed( Pwm* pPwm, uint32_t ul_channel, uint32_t prescaler, uint32_t alignment, uint32_t polarity ) { /* Disable ul_channel (effective at the end of the current period) */ - if ((pPwm->PWM_SR & (1 << ul_channel)) != 0) { + if ((pPwm->PWM_SR & (1 << ul_channel)) != 0) + { pPwm->PWM_DIS = 1 << ul_channel; while ((pPwm->PWM_SR & (1 << ul_channel)) != 0); } @@ -193,6 +211,15 @@ static void PWMC_ConfigureChannel_fixed( Pwm* pPwm, uint32_t ul_channel, uint32_ pPwm->PWM_CH_NUM[ul_channel].PWM_CMR = prescaler | alignment | polarity; } +// Convert an Arduino Due analog pin number to the corresponding ADC channel number +adc_channel_num_t PinToAdcChannel(int pin) +{ + if (pin < A0) + { + pin += A0; + } + return (adc_channel_num_t) (int) g_APinDescription[pin].ulADCChannelNumber; +} /* analogWriteNonDue @@ -262,61 +289,63 @@ void analogWriteNonDue(uint32_t ulPin, uint32_t ulValue, bool fastPwm) //initialise HSMCI pins void hsmciPinsinit() { - PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCCK_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCCK_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCCK_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCCK_GPIO].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].pPort,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO - X0].pPort,nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO - X0].ulPinType,nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO - X0].ulPin,nonDuePinDescription[PIN_HSMCI_MCCDA_GPIO - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCCK_GPIO - X0].pPort,nonDuePinDescription[PIN_HSMCI_MCCK_GPIO - X0].ulPinType,nonDuePinDescription[PIN_HSMCI_MCCK_GPIO - X0].ulPin,nonDuePinDescription[PIN_HSMCI_MCCK_GPIO - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO - X0].pPort,nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO - X0].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO - X0].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA0_GPIO - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO - X0].pPort,nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO - X0].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO - X0].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA1_GPIO - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO - X0].pPort,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO - X0].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO - X0].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA2_GPIO - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO - X0].pPort,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO - X0].ulPinType,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO - X0].ulPin,nonDuePinDescription[PIN_HSMCI_MCDA3_GPIO - X0].ulPinConfiguration); //set pullups (not on clock!) - digitalWriteNonDue(PIN_HSMCI_MCCDA_GPIO+X0, HIGH); - digitalWriteNonDue(PIN_HSMCI_MCDA0_GPIO+X0, HIGH); - digitalWriteNonDue(PIN_HSMCI_MCDA1_GPIO+X0, HIGH); - digitalWriteNonDue(PIN_HSMCI_MCDA2_GPIO+X0, HIGH); - digitalWriteNonDue(PIN_HSMCI_MCDA3_GPIO+X0, HIGH); + digitalWriteNonDue(PIN_HSMCI_MCCDA_GPIO - X0, HIGH); + digitalWriteNonDue(PIN_HSMCI_MCDA0_GPIO - X0, HIGH); + digitalWriteNonDue(PIN_HSMCI_MCDA1_GPIO - X0, HIGH); + digitalWriteNonDue(PIN_HSMCI_MCDA2_GPIO - X0, HIGH); + digitalWriteNonDue(PIN_HSMCI_MCDA3_GPIO - X0, HIGH); } //initialise ethernet pins void ethPinsInit() { - PIO_Configure(nonDuePinDescription[PIN_EMAC_EREFCK].pPort, - nonDuePinDescription[PIN_EMAC_EREFCK].ulPinType, - nonDuePinDescription[PIN_EMAC_EREFCK].ulPin, - nonDuePinDescription[PIN_EMAC_EREFCK].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_ETXEN].pPort, - nonDuePinDescription[PIN_EMAC_ETXEN].ulPinType, - nonDuePinDescription[PIN_EMAC_ETXEN].ulPin, - nonDuePinDescription[PIN_EMAC_ETXEN].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_ETX0].pPort, - nonDuePinDescription[PIN_EMAC_ETX0].ulPinType, - nonDuePinDescription[PIN_EMAC_ETX0].ulPin, - nonDuePinDescription[PIN_EMAC_ETX0].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_ETX1].pPort, - nonDuePinDescription[PIN_EMAC_ETX1].ulPinType, - nonDuePinDescription[PIN_EMAC_ETX1].ulPin, - nonDuePinDescription[PIN_EMAC_ETX1].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_ECRSDV].pPort, - nonDuePinDescription[PIN_EMAC_ECRSDV].ulPinType, - nonDuePinDescription[PIN_EMAC_ECRSDV].ulPin, - nonDuePinDescription[PIN_EMAC_ECRSDV].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_ERX0].pPort, - nonDuePinDescription[PIN_EMAC_ERX0].ulPinType, - nonDuePinDescription[PIN_EMAC_ERX0].ulPin, - nonDuePinDescription[PIN_EMAC_ERX0].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_ERX1].pPort, - nonDuePinDescription[PIN_EMAC_ERX1].ulPinType, - nonDuePinDescription[PIN_EMAC_ERX1].ulPin, - nonDuePinDescription[PIN_EMAC_ERX1].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_ERXER].pPort, - nonDuePinDescription[PIN_EMAC_ERXER].ulPinType, - nonDuePinDescription[PIN_EMAC_ERXER].ulPin, - nonDuePinDescription[PIN_EMAC_ERXER].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_EMDC].pPort, - nonDuePinDescription[PIN_EMAC_EMDC].ulPinType, - nonDuePinDescription[PIN_EMAC_EMDC].ulPin, - nonDuePinDescription[PIN_EMAC_EMDC].ulPinConfiguration); - PIO_Configure(nonDuePinDescription[PIN_EMAC_EMDIO].pPort, - nonDuePinDescription[PIN_EMAC_EMDIO].ulPinType, - nonDuePinDescription[PIN_EMAC_EMDIO].ulPin, - nonDuePinDescription[PIN_EMAC_EMDIO].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_EREFCK - X0].pPort, + nonDuePinDescription[PIN_EMAC_EREFCK - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_EREFCK - X0].ulPin, + nonDuePinDescription[PIN_EMAC_EREFCK - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_ETXEN - X0].pPort, + nonDuePinDescription[PIN_EMAC_ETXEN - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_ETXEN - X0].ulPin, + nonDuePinDescription[PIN_EMAC_ETXEN - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_ETX0 - X0].pPort, + nonDuePinDescription[PIN_EMAC_ETX0 - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_ETX0 - X0].ulPin, + nonDuePinDescription[PIN_EMAC_ETX0 - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_ETX1 - X0].pPort, + nonDuePinDescription[PIN_EMAC_ETX1 - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_ETX1 - X0].ulPin, + nonDuePinDescription[PIN_EMAC_ETX1 - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_ECRSDV - X0].pPort, + nonDuePinDescription[PIN_EMAC_ECRSDV - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_ECRSDV - X0].ulPin, + nonDuePinDescription[PIN_EMAC_ECRSDV - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_ERX0 - X0].pPort, + nonDuePinDescription[PIN_EMAC_ERX0 - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_ERX0 - X0].ulPin, + nonDuePinDescription[PIN_EMAC_ERX0 - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_ERX1 - X0].pPort, + nonDuePinDescription[PIN_EMAC_ERX1 - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_ERX1 - X0].ulPin, + nonDuePinDescription[PIN_EMAC_ERX1 - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_ERXER - X0].pPort, + nonDuePinDescription[PIN_EMAC_ERXER - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_ERXER - X0].ulPin, + nonDuePinDescription[PIN_EMAC_ERXER - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_EMDC - X0].pPort, + nonDuePinDescription[PIN_EMAC_EMDC - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_EMDC - X0].ulPin, + nonDuePinDescription[PIN_EMAC_EMDC - X0].ulPinConfiguration); + PIO_Configure(nonDuePinDescription[PIN_EMAC_EMDIO - X0].pPort, + nonDuePinDescription[PIN_EMAC_EMDIO - X0].ulPinType, + nonDuePinDescription[PIN_EMAC_EMDIO - X0].ulPin, + nonDuePinDescription[PIN_EMAC_EMDIO - X0].ulPinConfiguration); } + +// End diff --git a/Libraries/SamNonDuePin/SamNonDuePin.h b/Libraries/SamNonDuePin/SamNonDuePin.h index d404800..e230de8 100644 --- a/Libraries/SamNonDuePin/SamNonDuePin.h +++ b/Libraries/SamNonDuePin/SamNonDuePin.h @@ -18,7 +18,7 @@ /* Code from wiring-digital.c and wiring-analog.c from the arduino core. -See undefined.cpp file for more info +See SamNonDuePin.cpp file for more info */ #ifndef SAM_NON_DUE_PIN_H @@ -27,7 +27,7 @@ See undefined.cpp file for more info #include "Arduino.h" // Number of pins defined in PinDescription array -#define PINS_C 26 +//#define PINS_C 28 //not used static const unsigned int pwmFastFrequency = 25000; // fast PWM frequency for Intel spec PWM fans @@ -35,46 +35,69 @@ static const unsigned int pwmFastFrequency = 25000; // fast PWM frequency for I // Any pin numbers below X0 we assume are ordinary Due pin numbers // Note: these must all be <=127 because pin numbers are held in int8_t in some places. // There are 92 pins defined in the Arduino Due core as at version 1.5.4, so these must all be >=92 -static const uint8_t X0 = 100; -static const uint8_t X1 = 101; -static const uint8_t X2 = 102; -static const uint8_t X3 = 103; -static const uint8_t X4 = 104; -static const uint8_t X5 = 105; -static const uint8_t X6 = 106; -static const uint8_t X7 = 107; -static const uint8_t X8 = 108; +// 2015-07-08 Tony@t3p3 Added the additional pins for the Duet 0.8.5, changed the mapping to start at 93 (>=92) and +// finish at 126 (<=127). +static const uint8_t X0 = 93; +static const uint8_t X1 = 94; +static const uint8_t X2 = 95; +static const uint8_t X3 = 96; +static const uint8_t X4 = 97; +static const uint8_t X5 = 98; +static const uint8_t X6 = 99; +static const uint8_t X7 = 100; +static const uint8_t X8 = 101; +static const uint8_t X9 = 102; +static const uint8_t X10 = 103; +static const uint8_t X11 = 104; +static const uint8_t X12 = 105; //probe +static const uint8_t X13 = 106; +static const uint8_t X14 = 107; +static const uint8_t X15 = 108; +static const uint8_t X16 = 109; +static const uint8_t X17 = 110; //HSMCI -static const uint8_t PIN_HSMCI_MCCDA_GPIO = 9; -static const uint8_t PIN_HSMCI_MCCK_GPIO = 10; -static const uint8_t PIN_HSMCI_MCDA0_GPIO = 11; -static const uint8_t PIN_HSMCI_MCDA1_GPIO = 12; -static const uint8_t PIN_HSMCI_MCDA2_GPIO = 13; -static const uint8_t PIN_HSMCI_MCDA3_GPIO = 14; +static const uint8_t PIN_HSMCI_MCCDA_GPIO = 111; +static const uint8_t PIN_HSMCI_MCCK_GPIO = 112; +static const uint8_t PIN_HSMCI_MCDA0_GPIO = 113; +static const uint8_t PIN_HSMCI_MCDA1_GPIO = 114; +static const uint8_t PIN_HSMCI_MCDA2_GPIO = 115; +static const uint8_t PIN_HSMCI_MCDA3_GPIO = 116; //EMAC -static const uint8_t PIN_EMAC_EREFCK_GPIO = 15; //What is this one for? -static const uint8_t PIN_EMAC_EREFCK = 15; -static const uint8_t PIN_EMAC_ETXEN = 16; -static const uint8_t PIN_EMAC_ETX0 = 17; -static const uint8_t PIN_EMAC_ETX1 = 18; -static const uint8_t PIN_EMAC_ECRSDV = 19; -static const uint8_t PIN_EMAC_ERX0 = 20; -static const uint8_t PIN_EMAC_ERX1 = 21; -static const uint8_t PIN_EMAC_ERXER = 22; -static const uint8_t PIN_EMAC_EMDC = 23; -static const uint8_t PIN_EMAC_EMDIO = 24; -//PROBE RIG -static const uint8_t X25 = 125; +static const uint8_t PIN_EMAC_EREFCK = 117; +static const uint8_t PIN_EMAC_ETXEN = 118; +static const uint8_t PIN_EMAC_ETX0 = 119; +static const uint8_t PIN_EMAC_ETX1 = 120; +static const uint8_t PIN_EMAC_ECRSDV = 121; +static const uint8_t PIN_EMAC_ERX0 = 122; +static const uint8_t PIN_EMAC_ERX1 = 123; +static const uint8_t PIN_EMAC_ERXER = 124; +static const uint8_t PIN_EMAC_EMDC = 125; +static const uint8_t PIN_EMAC_EMDIO = 126; -// struct used to hold the descriptions for the "non arduino" pins. +// Class to give fast access to digital output pins for stepping +class OutputPin +{ + Pio *pPort; + uint32_t ulPin; +public: + explicit OutputPin(unsigned int pin); + OutputPin() : pPort(PIOC), ulPin(1 << 31) {} // default constructor needed for array init - accesses PC31 which isn't on the package, so safe + void SetHigh() const { pPort->PIO_SODR = ulPin; } + void SetLow() const { pPort->PIO_CODR = ulPin; } +}; + +// struct used to hold the descriptions for the "non Arduino" pins. // from the Arduino.h files extern const PinDescription nonDuePinDescription[] ; -extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode, uint32_t debounceCutoff = 0 ); // NB only one debounce cutoff frequency can be set per PIO -extern void digitalWriteNonDue( uint32_t ulPin, uint32_t ulVal ); -extern int digitalReadNonDue( uint32_t ulPin); +extern void pinModeNonDue(uint32_t ulPin, uint32_t ulMode, uint32_t debounceCutoff = 0); // NB only one debounce cutoff frequency can be set per PIO +extern void digitalWriteNonDue(uint32_t ulPin, uint32_t ulVal); +extern int digitalReadNonDue(uint32_t ulPin); +extern OutputPin getPioPin(uint32_t ulPin); extern void analogWriteNonDue(uint32_t ulPin, uint32_t ulValue, bool fastPwm = false); extern void analogOutputNonDue(); extern void hsmciPinsinit(); extern void ethPinsInit(); +extern adc_channel_num_t PinToAdcChannel(int pin); // convert an analog pin number to an ADC channel + #endif /* SAM_NON_DUE_PIN_H */ diff --git a/Platform.cpp b/Platform.cpp index 0360e81..de37035 100644 --- a/Platform.cpp +++ b/Platform.cpp @@ -26,6 +26,7 @@ extern char _end; extern "C" char *sbrk(int i); const uint8_t memPattern = 0xA5; +const int Dac0DigitalPin = 66; // Arduino Due pin number corresponding to DAC0 output pin 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 @@ -105,7 +106,7 @@ bool PidParameters::operator==(const PidParameters& other) const // Platform class Platform::Platform() : - autoSaveEnabled(false), active(false), errorCodeBits(0), fileStructureInitialised(false), tickState(0), debugCode(0), + autoSaveEnabled(false), board(BoardType::Duet_06), active(false), errorCodeBits(0), fileStructureInitialised(false), tickState(0), debugCode(0), messageString(messageStringBuffer, ARRAY_SIZE(messageStringBuffer)) { line = new Line(SerialUSB); @@ -125,10 +126,13 @@ Platform::Platform() : void Platform::Init() { + // Deal with power first digitalWriteNonDue(atxPowerPin, LOW); // ensure ATX power is off by default pinModeNonDue(atxPowerPin, OUTPUT); - idleCurrentFactor = defaultIdleCurrentFactor; + SetBoardType(BoardType::Auto); + + // Comms baudRates[0] = MainBaudRate; baudRates[1] = AuxBaudRate; @@ -146,12 +150,13 @@ void Platform::Init() aux->Init(); messageIndent = 0; - // We need to initialize at least some of the time stuff before we call MassStorage::Init() + // We need to initialise at least some of the time stuff before we call MassStorage::Init() addToTime = 0.0; lastTimeCall = 0; lastTime = Time(); longWait = lastTime; + // File management massStorage->Init(); for (size_t file = 0; file < MAX_FILES; file++) @@ -172,6 +177,7 @@ void Platform::Init() ARRAY_INIT(stepPins, STEP_PINS); ARRAY_INIT(directionPins, DIRECTION_PINS); ARRAY_INIT(directions, DIRECTIONS); + ARRAY_INIT(enableValues, ENABLE_VALUES); ARRAY_INIT(enablePins, ENABLE_PINS); ARRAY_INIT(endStopPins, END_STOP_PINS); ARRAY_INIT(maxFeedrates, MAX_FEEDRATES); @@ -181,13 +187,13 @@ void Platform::Init() ARRAY_INIT(potWipes, POT_WIPES); senseResistor = SENSE_RESISTOR; maxStepperDigipotVoltage = MAX_STEPPER_DIGIPOT_VOLTAGE; - //numMixingDrives = NUM_MIXING_DRIVES; + maxStepperDACVoltage = MAX_STEPPER_DAC_VOLTAGE; // Z PROBE zProbePin = Z_PROBE_PIN; zProbeAdcChannel = PinToAdcChannel(zProbePin); - InitZProbe(); + InitZProbe(); // this also sets up zProbeModulationPin // AXES @@ -195,6 +201,7 @@ void Platform::Init() ARRAY_INIT(axisMinima, AXIS_MINIMA); ARRAY_INIT(homeFeedrates, HOME_FEEDRATES); + idleCurrentFactor = defaultIdleCurrentFactor; SetSlowestDrive(); // HEATERS - Bed is assumed to be the first @@ -205,8 +212,10 @@ void Platform::Init() ARRAY_INIT(activeTemperatures, ACTIVE_TEMPERATURES); heatSampleTime = HEAT_SAMPLE_TIME; - coolingFanValue = 0.0; - coolingFanPin = COOLING_FAN_PIN; + coolingFan0Value = 0.0; + coolingFan1Value = 0.0; + coolingFan0Pin = COOLING_FAN0_PIN; + coolingFan1Pin = COOLING_FAN1_PIN; coolingFanRpmPin = COOLING_FAN_RPM_PIN; timeToHot = TIME_TO_HOT; lastRpmResetTime = 0.0; @@ -215,8 +224,11 @@ void Platform::Init() gcodeDir = GCODE_DIR; tempDir = TEMP_DIR; + // Motors + for (size_t drive = 0; drive < DRIVES; drive++) { + SetPhysicalDrive(drive, drive); // map drivers directly to axes and extruders if (stepPins[drive] >= 0) { pinModeNonDue(stepPins[drive], OUTPUT); @@ -266,10 +278,15 @@ void Platform::Init() thermistorOverheatSums[heater] = (uint32_t) (thermistorOverheatAdcValue + 0.9) * numThermistorReadingsAveraged; } - if (coolingFanPin >= 0) + if (coolingFan0Pin >= 0) { // Inverse logic for Duet v0.6 and later; this turns it off - analogWriteNonDue(coolingFanPin, (HEAT_ON == 0) ? 255 : 0, true); + analogWriteNonDue(coolingFan0Pin, (HEAT_ON == 0) ? 255 : 0, true); + } + if (coolingFan1Pin >= 0) + { + // Inverse logic for Duet v0.6 and later; this turns it off + analogWriteNonDue(coolingFan1Pin, (HEAT_ON == 0) ? 255 : 0, true); } if (coolingFanRpmPin >= 0) @@ -321,18 +338,19 @@ void Platform::InitZProbe() { zProbeOnFilter.Init(0); zProbeOffFilter.Init(0); + zProbeModulationPin = (board == BoardType::Duet_07) ? Z_PROBE_MOD_PIN07 : Z_PROBE_MOD_PIN; switch (nvData.zProbeType) { case 1: case 2: - pinModeNonDue(nvData.zProbeModulationPin, OUTPUT); - digitalWriteNonDue(nvData.zProbeModulationPin, HIGH); // enable the IR LED + pinModeNonDue(zProbeModulationPin, OUTPUT); + digitalWriteNonDue(zProbeModulationPin, HIGH); // enable the IR LED break; case 3: - pinModeNonDue(nvData.zProbeModulationPin, OUTPUT); - digitalWriteNonDue(nvData.zProbeModulationPin, LOW); // enable the alternate sensor + pinModeNonDue(zProbeModulationPin, OUTPUT); + digitalWriteNonDue(zProbeModulationPin, LOW); // enable the alternate sensor break; case 4: @@ -347,21 +365,6 @@ void Platform::InitZProbe() } } -int Platform::GetZProbeChannel() const -{ - return (nvData.zProbeModulationPin == Z_PROBE_MOD_PIN07) ? 1 : 0; -} - -void Platform::SetZProbeChannel(int chan) -{ - int temp = nvData.zProbeModulationPin; - nvData.zProbeModulationPin = (chan == 1) ? Z_PROBE_MOD_PIN07 : Z_PROBE_MOD_PIN; - if (autoSaveEnabled && temp != nvData.zProbeModulationPin) - { - WriteNvData(); - } -} - // Return the Z probe data. // The ADC readings are 12 bits, so we convert them to 10-bit readings for compatibility with the old firmware. int Platform::ZProbe() const @@ -579,7 +582,6 @@ void Platform::ResetNvData() nvData.switchZProbeParameters.Init(0.0); nvData.irZProbeParameters.Init(Z_PROBE_STOP_HEIGHT); nvData.alternateZProbeParameters.Init(Z_PROBE_STOP_HEIGHT); - nvData.zProbeModulationPin = Z_PROBE_MOD_PIN; for (size_t i = 0; i < HEATERS; ++i) { @@ -903,7 +905,10 @@ void Platform::InitialiseInterrupts() NVIC_EnableIRQ(TC4_IRQn); // Interrupt for 4-pin PWM fan sense line - attachInterrupt(coolingFanRpmPin, FanInterrupt, FALLING); + if (coolingFanRpmPin >= 0) + { + attachInterrupt(coolingFanRpmPin, FanInterrupt, FALLING); + } // Tick interrupt for ADC conversions tickState = 0; @@ -923,30 +928,25 @@ void Platform::DisableInterrupts() #pragma GCC push_options #pragma GCC optimize ("O3") -// Schedule an interrupt at the specified clock count, or return true if that time is imminent or has passed already +// Schedule an interrupt at the specified clock count, or return true if that time is imminent or has passed already. +// Must be called with interrupts disabled, /*static*/ bool Platform::ScheduleInterrupt(uint32_t tim) { - irqflags_t flags = cpu_irq_save(); // disable interrupts TC_SetRA(TC1, 0, tim); // set up the compare register TC_GetStatus(TC1, 0); // clear any pending interrupt int32_t diff = (int32_t)(tim - TC_ReadCV(TC1, 0)); // see how long we have to go - bool ret; - if (diff < 3) // if less than about 1us or already passed + if (diff < (int32_t)DDA::minInterruptInterval) // if less than about 2us or already passed { - ret = true; // tell the caller to simulate an interrupt instead + return true; // tell the caller to simulate an interrupt instead } - else - { - ret = false; - TC1 ->TC_CHANNEL[0].TC_IER = TC_IER_CPAS; // enable the interrupt + + TC1 ->TC_CHANNEL[0].TC_IER = TC_IER_CPAS; // enable the interrupt #ifdef MOVE_DEBUG ++numInterruptsScheduled; nextInterruptTime = tim; nextInterruptScheduledAt = Platform::GetInterruptClocks(); #endif - } - cpu_irq_restore(flags); // restore interrupt enable status - return ret; + return false; } // Process a 1ms tick interrupt @@ -999,7 +999,7 @@ void Platform::Tick() StartAdcConversion(heaterAdcChannels[currentHeater]); // read a thermistor if (nvData.zProbeType == 2) // if using a modulated IR sensor { - digitalWriteNonDue(nvData.zProbeModulationPin, LOW); // turn off the IR emitter + digitalWriteNonDue(zProbeModulationPin, LOW); // turn off the IR emitter } ++tickState; break; @@ -1012,7 +1012,7 @@ void Platform::Tick() StartAdcConversion(heaterAdcChannels[currentHeater]); // read a thermistor if (nvData.zProbeType == 2 || nvData.zProbeType == 3) // if using a modulated IR sensor { - digitalWriteNonDue(nvData.zProbeModulationPin, HIGH); // turn on the IR emitter + digitalWriteNonDue(zProbeModulationPin, HIGH); // turn on the IR emitter } tickState = 1; break; @@ -1039,16 +1039,6 @@ void Platform::Tick() adc_start(ADC ); } -// Convert an Arduino Due pin number to the corresponding ADC channel number -/*static*/ adc_channel_num_t Platform::PinToAdcChannel(int pin) -{ - if (pin < A0) - { - pin += A0; - } - return (adc_channel_num_t) (int) g_APinDescription[pin].ulADCChannelNumber; -} - #pragma GCC pop_options //************************************************************************************************* @@ -1288,11 +1278,15 @@ EndStopHit Platform::GetZProbeResult() const // This is called from the step ISR as well as other places, so keep it fast, especially in the case where the motor is already enabled void Platform::SetDirection(size_t drive, bool direction) { - const int pin = directionPins[drive]; - if (pin >= 0) + const int driver = driverNumbers[drive]; + if (driver >= 0) { - bool d = (direction == FORWARDS) ? directions[drive] : !directions[drive]; - digitalWriteNonDue(pin, d); + const int pin = directionPins[driver]; + if (pin >= 0) + { + bool d = (direction == FORWARDS) ? directions[driver] : !directions[driver]; + digitalWriteNonDue(pin, d); + } } } @@ -1302,12 +1296,16 @@ void Platform::EnableDrive(size_t drive) if (drive < DRIVES && driveState[drive] != DriveStatus::enabled) { driveState[drive] = DriveStatus::enabled; - UpdateMotorCurrent(drive); // the current may have been reduced by the idle timeout - - const int pin = enablePins[drive]; - if (pin >= 0) + const size_t driver = driverNumbers[drive]; + if (driver >= 0) { - digitalWriteNonDue(pin, ENABLE_DRIVE); + UpdateMotorCurrent(driver); // the current may have been reduced by the idle timeout + + const int pin = enablePins[driver]; + if (pin >= 0) + { + digitalWriteNonDue(pin, enableValues[driver]); + } } } } @@ -1317,16 +1315,17 @@ void Platform::DisableDrive(size_t drive) { if (drive < DRIVES) { - const int pin = enablePins[drive]; + const size_t driver = driverNumbers[drive]; + const int pin = enablePins[driver]; if (pin >= 0) { - digitalWriteNonDue(pin, DISABLE_DRIVE); - driveState[drive] = DriveStatus::disabled; + digitalWriteNonDue(pin, !enableValues[driver]); } + driveState[drive] = DriveStatus::disabled; } } -// Set a drive to idle hold if it is enabled. If it is disabled, leave it alone. +// Set drives to idle hold if they are enabled. If a drive is disabled, leave it alone. // Must not be called from an ISR, or with interrupts disabled. void Platform::SetDrivesIdle() { @@ -1361,15 +1360,33 @@ void Platform::UpdateMotorCurrent(size_t drive) current *= idleCurrentFactor; } unsigned short pot = (unsigned short)((0.256*current*8.0*senseResistor + maxStepperDigipotVoltage/2)/maxStepperDigipotVoltage); - if (drive < 4) + unsigned short dac = (unsigned short)((0.256*current*8.0*senseResistor + maxStepperDACVoltage/2)/maxStepperDACVoltage); + const size_t driver = driverNumbers[drive]; + if (driver < 4) { - mcpDuet.setNonVolatileWiper(potWipes[drive], pot); - mcpDuet.setVolatileWiper(potWipes[drive], pot); + mcpDuet.setNonVolatileWiper(potWipes[driver], pot); + mcpDuet.setVolatileWiper(potWipes[driver], pot); } else { - mcpExpansion.setNonVolatileWiper(potWipes[drive], pot); - mcpExpansion.setVolatileWiper(potWipes[drive], pot); + if (board == BoardType::Duet_085) + { + // Extruder 0 is on DAC channel 0 + if (driver == 4) + { + analogWrite(DAC0, dac); + } + else + { + mcpExpansion.setNonVolatileWiper(potWipes[driver-1], pot); + mcpExpansion.setVolatileWiper(potWipes[driver-1], pot); + } + } + else + { + mcpExpansion.setNonVolatileWiper(potWipes[driver], pot); + mcpExpansion.setVolatileWiper(potWipes[driver], pot); + } } } } @@ -1392,10 +1409,42 @@ void Platform::SetIdleCurrentFactor(float f) } } -// Get current cooling fan speed on a scale between 0 and 1 -float Platform::GetFanValue() const +// Set the physical drive (i.e. axis or extruder) number used by this driver +void Platform::SetPhysicalDrive(size_t driverNumber, int8_t physicalDrive) { - return coolingFanValue; + int oldDrive = GetPhysicalDrive(driverNumber); + if (oldDrive >= 0) + { + driverNumbers[oldDrive] = -1; + stepPinDescriptors[oldDrive] = OutputPin(); + } + driverNumbers[physicalDrive] = driverNumber; + stepPinDescriptors[physicalDrive] = OutputPin(stepPins[driverNumber]); +} + +// Return the physical drive used by this driver, or -1 if not found +int Platform::GetPhysicalDrive(size_t driverNumber) const +{ + for (int drive = 0; drive < DRIVES; ++drive) + { + if (driverNumbers[drive] == (int8_t)driverNumber) + { + return drive; + } + } + return -1; +} + +// Get current cooling fan speed on a scale between 0 and 1 +float Platform::GetFanValue(size_t fan) const +{ + if (fan==0){ + return coolingFan0Value; + } + if (fan==1){ + return coolingFan1Value; + } + else return -1; } // This is a bit of a compromise - old RepRaps used fan speeds in the range @@ -1404,24 +1453,41 @@ float Platform::GetFanValue() const // the G Code reader will get right for a float or an int) and attempts to // do the right thing whichever the user has done. This will only not work // for an old-style fan speed of 1/255... -void Platform::SetFanValue(float speed) +void Platform::SetFanValue(size_t fan, float speed) { - if (coolingFanPin >= 0) + if (fan==0 && coolingFan0Pin >= 0) { byte p; if (speed <= 1.0) { p = (byte)(255.0 * max(0.0, speed)); - coolingFanValue = speed; + coolingFan0Value = speed; } else { p = (byte)speed; - coolingFanValue = speed / 255.0; + coolingFan0Value = speed / 255.0; } - // The cooling fan output pin gets inverted if HEAT_ON == 0 - analogWriteNonDue(coolingFanPin, (HEAT_ON == 0) ? (255 - p) : p, true); + // The cooling fan 0 output pin gets inverted if HEAT_ON == 0 + analogWriteNonDue(coolingFan0Pin, (HEAT_ON == 0) ? (255 - p) : p, true); + } + if (fan==1 && coolingFan1Pin >= 0) + { + byte p; + if (speed <= 1.0) + { + p = (byte)(255.0 * max(0.0, speed)); + coolingFan1Value = speed; + } + else + { + p = (byte)speed; + coolingFan1Value = speed / 255.0; + } + + // The cooling fan 1 output pin gets inverted if HEAT_ON == 0 + analogWriteNonDue(coolingFan1Pin, (HEAT_ON == 0) ? (255 - p) : p, true); } } @@ -1713,6 +1779,41 @@ void Platform::ResetChannel(size_t chan) } } +void Platform::SetBoardType(BoardType bt) +{ + if (bt == BoardType::Auto) + { + // Determine whether this is a Duet 0.6 or a Duet 0.8.5 board. + // If it is a 0.85 board then DAC0 (AKA digital pin 67) is connected to ground via a diode and a 2.15K resistor. + // So we enable the pullup (value 150K-150K) on pin 67 and read it, expecting a LOW on a 0.8.5 board and a HIGH on a 0.6 board. + // This may fail if anyone connects a load to the DAC0 pin on and Dur=et 0.6, hence we implement board selection in M115 as well. + pinModeNonDue(Dac0DigitalPin, INPUT_PULLUP); + board = (digitalReadNonDue(Dac0DigitalPin)) ? BoardType::Duet_06 : BoardType::Duet_085; + pinModeNonDue(Dac0DigitalPin, INPUT); // turn pullup off + } + else + { + board = bt; + } + + if (active) + { + InitZProbe(); // select and initialise the Z probe modulation pin + } +} + +// Get a string describing the electronics +const char* Platform::GetElectronicsString() const +{ + switch (board) + { + case BoardType::Duet_06: return "Duet 0.6"; + case BoardType::Duet_07: return "Duet 0.7"; + case BoardType::Duet_085: return "Duet 0.85"; + default: return "Unidentified"; + } +} + /********************************************************************************* Files & Communication diff --git a/Platform.h b/Platform.h index ac3fe82..3a8a8bd 100644 --- a/Platform.h +++ b/Platform.h @@ -64,9 +64,9 @@ Licence: GPL // The physical capabilities of the machine -#define DRIVES 8 // The number of drives in the machine, including X, Y, and Z plus extruder drives +#define DRIVES 9 // The number of drives in the machine, including X, Y, and Z plus extruder drives #define AXES 3 // The number of movement axes in the machine, usually just X, Y and Z. <= DRIVES -#define HEATERS 6 // The number of heaters in the machine; 0 is the heated bed even if there isn't one. +#define HEATERS 7 // The number of heaters in the machine; 0 is the heated bed even if there isn't one. // The numbers of entries in each array must correspond with the values of DRIVES, // AXES, or HEATERS. Set values to -1 to flag unavailability. @@ -75,36 +75,35 @@ Licence: GPL // DRIVES -#define STEP_PINS {14, 25, 5, X2, 41, 39, X4, 49} -#define DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48} +#define STEP_PINS {14, 25, 5, X2, 41, 39, X4, 49, X10} +#define DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48, X11} #define FORWARDS true // What to send to go... #define BACKWARDS (!FORWARDS) // ...in each direction -#define DIRECTIONS {BACKWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS} // What each axis needs to make it go forwards - defaults -#define ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47} -#define ENABLE_DRIVE false // What to send to enable... -#define DISABLE_DRIVE true // ...and disable a drive -#define DISABLE_DRIVES {false, false, true, false, false, false, false, false} // Set true to disable a drive when it becomes idle -#define END_STOP_PINS {11, 28, 60, 31, 24, 46, 45, 44} //E Stops not currently used +#define DIRECTIONS {BACKWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS} // What each axis needs to make it go forwards - defaults +#define ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47, X13} +#define ENABLE_VALUES {false, false, false, false, false, false, false, false, false} // what to send to enable a drive +#define END_STOP_PINS {11, 28, 60, 31, 24, 46, 45, 44, X9} // E0 stop used for switch-type Z probe, others not currently used // Indices for motor current digipots (if any) // first 4 are for digipot 1,(on duet) // second 4 for digipot 2(on expansion board) // Full order is {1, 3, 2, 0, 1, 3, 2, 0}, only include as many as you have DRIVES defined #define POT_WIPES {1, 3, 2, 0, 1, 3, 2, 0} -#define SENSE_RESISTOR 0.1 // Stepper motor current sense resistor +#define SENSE_RESISTOR 0.1 // Stepper motor current sense resistor #define MAX_STEPPER_DIGIPOT_VOLTAGE ( 3.3*2.5/(2.7+2.5) ) // Stepper motor current reference voltage +#define MAX_STEPPER_DAC_VOLTAGE 2.12 // Stepper motor current reference voltage for E1 if using a DAC -#define Z_PROBE_AD_VALUE (400) // Default for the Z probe - should be overwritten by experiment -#define Z_PROBE_STOP_HEIGHT (0.7) // mm +#define Z_PROBE_AD_VALUE (400) // Default for the Z probe - should be overwritten by experiment +#define Z_PROBE_STOP_HEIGHT (0.7) // mm #define Z_PROBE_PIN (10) // Analogue pin number #define Z_PROBE_MOD_PIN (52) // Digital pin number to turn the IR LED on (high) or off (low) -#define Z_PROBE_MOD_PIN07 (X25) // Digital pin number to turn the IR LED on (high) or off (low) Duet V0.7 onwards +#define Z_PROBE_MOD_PIN07 (X12) // Digital pin number to turn the IR LED on (high) or off (low) Duet V0.7 onwards #define Z_PROBE_AXES {true, false, true} // Axes for which the Z-probe is normally used const unsigned int numZProbeReadingsAveraged = 8; // we average this number of readings with IR on, and the same number with IR off -#define MAX_FEEDRATES {100.0, 100.0, 3.0, 20.0, 20.0, 20.0, 20.0, 20.0} // mm/sec -#define ACCELERATIONS {500.0, 500.0, 20.0, 250.0, 250.0, 250.0, 250.0, 250.0} // mm/sec^2 -#define DRIVE_STEPS_PER_UNIT {87.4890, 87.4890, 4000.0, 420.0, 420.0, 420.0, 420.0, 420.0} -#define INSTANT_DVS {30.0, 30.0, 0.2, 2.0, 2.0, 2.0, 2.0, 2.0} // (mm/sec) +#define MAX_FEEDRATES {100.0, 100.0, 3.0, 20.0, 20.0, 20.0, 20.0, 20.0, 20.0} // mm/sec +#define ACCELERATIONS {500.0, 500.0, 20.0, 250.0, 250.0, 250.0, 250.0, 250.0, 250.0} // mm/sec^2 +#define DRIVE_STEPS_PER_UNIT {87.4890, 87.4890, 4000.0, 420.0, 420.0, 420.0, 420.0, 420.0, 420.0} +#define INSTANT_DVS {30.0, 30.0, 0.2, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0} // (mm/sec) // AXES @@ -120,13 +119,13 @@ const size_t A_AXIS = 0, B_AXIS = 1, C_AXIS = 2; // The indices of the 3 tower m // HEATERS - The bed is assumed to be the at index 0 -#define TEMP_SENSE_PINS {5, 4, 0, 7, 8, 9} // Analogue pin numbers -#define HEAT_ON_PINS {6, X5, X7, 7, 8, 9} //pin D38 is PWM capable but not an Arduino PWM pin +#define TEMP_SENSE_PINS {5, 4, 0, 7, 8, 9, 11} // Analogue pin numbers +#define HEAT_ON_PINS {6, X5, X7, 7, 8, 9, -1} //heater Channel 7 (pin X17) is shared with Fan1. Only define 1 or the other // Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930 // Hot end thermistor: http://www.digikey.co.uk/product-search/en?x=20&y=11&KeyWords=480-3137-ND -const float defaultThermistorBetas[HEATERS] = {3988.0, 4138.0, 4138.0, 4138.0, 4138.0, 4138.0}; // Bed thermistor: B57861S104F40; Extruder thermistor: RS 198-961 -const float defaultThermistorSeriesRs[HEATERS] = {1000, 1000, 1000, 1000, 1000, 1000}; // Ohms in series with the thermistors -const float defaultThermistor25RS[HEATERS] = {10000.0, 100000.0, 100000.0, 100000.0, 100000.0, 100000.0}; // Thermistor ohms at 25 C = 298.15 K +const float defaultThermistorBetas[HEATERS] = {3988.0, 4138.0, 4138.0, 4138.0, 4138.0, 4138.0, 4138.0}; // Bed thermistor: B57861S104F40; Extruder thermistor: RS 198-961 +const float defaultThermistorSeriesRs[HEATERS] = {1000, 1000, 1000, 1000, 1000, 1000, 1000}; // Ohms in series with the thermistors +const float defaultThermistor25RS[HEATERS] = {10000.0, 100000.0, 100000.0, 100000.0, 100000.0, 100000.0, 100000.0}; // Thermistor ohms at 25 C = 298.15 K // Note on hot end PID parameters: // The system is highly nonlinear because the heater power is limited to a maximum value and cannot go negative. @@ -153,19 +152,20 @@ const float defaultThermistor25RS[HEATERS] = {10000.0, 100000.0, 100000.0, 10000 // This allows us to switch between PID and bang-bang using the M301 and M304 commands. // We use method 2 (see above) -const float defaultPidKis[HEATERS] = {5.0, 0.1, 0.1, 0.1, 0.1, 0.1}; // Integral PID constants -const float defaultPidKds[HEATERS] = {500.0, 100.0, 100.0, 100.0, 100.0, 100.0}; // Derivative PID constants -const float defaultPidKps[HEATERS] = {-1.0, 10.0, 10.0, 10.0, 10.0, 10.0}; // Proportional PID constants, negative values indicate use bang-bang instead of PID -const float defaultPidKts[HEATERS] = {2.7, 0.4, 0.4, 0.4, 0.4, 0.4}; // approximate PWM value needed to maintain temperature, per degC above room temperature -const float defaultPidKss[HEATERS] = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0}; // PWM scaling factor, to allow for variation in heater power and supply voltage -const float defaultFullBands[HEATERS] = {5.0, 30.0, 30.0, 30.0, 30.0, 30.0}; // errors larger than this cause heater to be on or off -const float defaultPidMins[HEATERS] = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; // minimum value of I-term -const float defaultPidMaxes[HEATERS] = {255, 180, 180, 180, 180, 180}; // maximum value of I-term, must be high enough to reach 245C for ABS printing +const float defaultPidKis[HEATERS] = {5.0, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1}; // Integral PID constants +const float defaultPidKds[HEATERS] = {500.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0}; // Derivative PID constants +const float defaultPidKps[HEATERS] = {-1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0}; // Proportional PID constants, negative values indicate use bang-bang instead of PID +const float defaultPidKts[HEATERS] = {2.7, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4}; // approximate PWM value needed to maintain temperature, per degC above room temperature +const float defaultPidKss[HEATERS] = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}; // PWM scaling factor, to allow for variation in heater power and supply voltage +const float defaultFullBands[HEATERS] = {5.0, 30.0, 30.0, 30.0, 30.0, 30.0, 30.0}; // errors larger than this cause heater to be on or off +const float defaultPidMins[HEATERS] = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; // minimum value of I-term +const float defaultPidMaxes[HEATERS] = {255, 180, 180, 180, 180, 180, 180}; // maximum value of I-term, must be high enough to reach 245C for ABS printing -#define STANDBY_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO} // We specify one for the bed, though it's not needed -#define ACTIVE_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO} -#define COOLING_FAN_PIN X6 // pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead -#define COOLING_FAN_RPM_PIN 36 // pin PC4 +#define STANDBY_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO} // We specify one for the bed, though it's not needed +#define ACTIVE_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO} +#define COOLING_FAN0_PIN X6 // pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead +#define COOLING_FAN1_PIN X17 +#define COOLING_FAN_RPM_PIN 23 #define COOLING_FAN_RPM_SAMPLE_TIME 2.0 // Time to wait before resetting the internal fan RPM stats #define HEAT_ON 0 // 0 for inverted heater (e.g. Duet v0.6) 1 for not (e.g. Duet v0.4) @@ -216,6 +216,14 @@ const size_t messageStringLength = 256; // max length of a message chunk sent /****************************************************************************************************/ +enum class BoardType : uint8_t +{ + Auto = 0, + Duet_06 = 1, + Duet_07 = 2, + Duet_085 = 3 +}; + enum class EndStopHit { noStop = 0, // no endstop hit @@ -584,6 +592,8 @@ public: void SoftwareReset(uint16_t reason); bool AtxPower() const; void SetAtxPower(bool on); + void SetBoardType(BoardType bt); + const char* GetElectronicsString() const; // Timing @@ -633,9 +643,13 @@ public: // Movement void EmergencyStop(); + void SetPhysicalDrive(size_t driverNumber, int8_t physicalDrive); + int GetPhysicalDrive(size_t driverNumber) const; void SetDirection(size_t drive, bool direction); void SetDirectionValue(size_t drive, bool dVal); bool GetDirectionValue(size_t drive) const; + void SetEnableValue(size_t drive, bool eVal); + bool GetEnableValue(size_t drive) const; void StepHigh(size_t drive); void StepLow(size_t drive); void EnableDrive(size_t drive); @@ -679,8 +693,6 @@ public: EndStopHit GetZProbeResult() const; int GetZProbeSecondaryValues(int& v1, int& v2); void SetZProbeType(int iZ); - int GetZProbeChannel() const; - void SetZProbeChannel(int chan); int GetZProbeType() const; void SetZProbeAxes(const bool axes[AXES]); void GetZProbeAxes(bool (&axes)[AXES]); @@ -693,11 +705,6 @@ public: void ExtrudeOn(); void ExtrudeOff(); - // Mixing support - -// void SetMixingDrives(int); -// int GetMixingDrives(); - size_t SlowestDrive() const; // Heat and temperature @@ -706,8 +713,8 @@ public: void SetHeater(size_t heater, float power); // power is a fraction in [0,1] float HeatSampleTime() const; void SetHeatSampleTime(float st); - float GetFanValue() const; // Result is returned in per cent - void SetFanValue(float speed); // Accepts values between 0..1 and 1..255 + float GetFanValue(size_t fan) const; // Result is returned in per cent + void SetFanValue(size_t fan,float speed); // Accepts values between 0..1 and 1..255 float GetFanRPM(); void SetPidParameters(size_t heater, const PidParameters& params); const PidParameters& GetPidParameters(size_t heater) const; @@ -766,7 +773,6 @@ private: ZProbeParameters irZProbeParameters; // Z probe values for the IR sensor ZProbeParameters alternateZProbeParameters; // Z probe values for the alternate sensor int zProbeType; // the type of Z probe we are currently using - Pin zProbeModulationPin; // which pin is used for Z probe modulation bool zProbeAxes[AXES]; // Z probe is used for these axes PidParameters pidParams[HEATERS]; byte ipAddress[4]; @@ -779,6 +785,8 @@ private: FlashData nvData; bool autoSaveEnabled; + BoardType board; + float lastTime; float longWait; float addToTime; @@ -795,13 +803,16 @@ private: void SetSlowestDrive(); void UpdateMotorCurrent(size_t drive); - Pin stepPins[DRIVES]; + // Note that + Pin stepPins[DRIVES]; // the Arduino pin numbers for the stepper pins + OutputPin stepPinDescriptors[DRIVES]; // output pin descriptors for faster access, with the driver number mapping already done Pin directionPins[DRIVES]; Pin enablePins[DRIVES]; -// bool disableDrives[DRIVES]; // not currently used volatile DriveStatus driveState[DRIVES]; bool directions[DRIVES]; + bool enableValues[DRIVES]; Pin endStopPins[DRIVES]; + int8_t driverNumbers[DRIVES]; float maxFeedrates[DRIVES]; float accelerations[DRIVES]; float driveStepsPerUnit[DRIVES]; @@ -817,11 +828,12 @@ private: Pin potWipes[DRIVES]; float senseResistor; float maxStepperDigipotVoltage; + float maxStepperDACVoltage; // Z probe Pin zProbePin; - + Pin zProbeModulationPin; volatile ZProbeAveragingFilter zProbeOnFilter; // Z probe readings we took with the IR turned on volatile ZProbeAveragingFilter zProbeOffFilter; // Z probe readings we took with the IR turned off volatile ThermistorAveragingFilter thermistorFilters[HEATERS]; // bed and extruder thermistor readings @@ -842,15 +854,17 @@ private: // HEATERS - Bed is assumed to be the first - int GetRawTemperature(byte heater) const; + int GetRawTemperature(size_t heater) const; Pin tempSensePins[HEATERS]; Pin heatOnPins[HEATERS]; float heatSampleTime; float standbyTemperatures[HEATERS]; float activeTemperatures[HEATERS]; - float coolingFanValue; - Pin coolingFanPin; + float coolingFan0Value; + float coolingFan1Value; + Pin coolingFan0Pin; + Pin coolingFan1Pin; Pin coolingFanRpmPin; float timeToHot; float lastRpmResetTime; @@ -886,7 +900,6 @@ private: static uint16_t GetAdcReading(adc_channel_num_t chan); static void StartAdcConversion(adc_channel_num_t chan); - static adc_channel_num_t PinToAdcChannel(int pin); char messageStringBuffer[messageStringLength]; StringRef messageString; @@ -1114,6 +1127,16 @@ inline bool Platform::GetDirectionValue(size_t drive) const return directions[drive]; } +inline void Platform::SetEnableValue(size_t drive, bool eVal) +{ + enableValues[drive] = eVal; +} + +inline bool Platform::GetEnableValue(size_t drive) const +{ + return enableValues[drive]; +} + inline float Platform::HomeFeedRate(size_t axis) const { return homeFeedrates[axis]; @@ -1152,12 +1175,12 @@ inline float Platform::AxisTotalLength(size_t axis) const // The A4988 requires 1us minimum pulse width, so we make separate StepHigh and StepLow calls so that we don't waste this time inline void Platform::StepHigh(size_t drive) { - digitalWriteNonDue(stepPins[drive], 1); + stepPinDescriptors[drive].SetHigh(); } inline void Platform::StepLow(size_t drive) { - digitalWriteNonDue(stepPins[drive], 0); + stepPinDescriptors[drive].SetLow(); } inline void Platform::SetExtrusionAncilliaryPWM(float v) @@ -1178,7 +1201,7 @@ inline void Platform::ExtrudeOn() { if (extrusionAncilliaryPWM > 0.0) { - SetFanValue(extrusionAncilliaryPWM); + SetFanValue(0,extrusionAncilliaryPWM); //@TODO T3P3 currently only turns fan0 on } } @@ -1189,7 +1212,7 @@ inline void Platform::ExtrudeOff() { if (extrusionAncilliaryPWM > 0.0) { - SetFanValue(0.0); + SetFanValue(0,0.0); //@TODO T3P3 currently only turns fan0 off } } @@ -1197,7 +1220,7 @@ inline void Platform::ExtrudeOff() // Drive the RepRap machine - Heat and temperature -inline int Platform::GetRawTemperature(byte heater) const +inline int Platform::GetRawTemperature(size_t heater) const { return (heater < HEATERS) ? thermistorFilters[heater].GetSum()/(numThermistorReadingsAveraged >> adOversampleBits) diff --git a/Release/RepRapFirmware-1.09i-dc42.bin b/Release/RepRapFirmware-1.09i-dc42.bin new file mode 100644 index 0000000..2b3aa6d Binary files /dev/null and b/Release/RepRapFirmware-1.09i-dc42.bin differ diff --git a/RepRapFirmware.cpp b/RepRapFirmware.cpp index 954b7c4..f07120c 100644 --- a/RepRapFirmware.cpp +++ b/RepRapFirmware.cpp @@ -754,7 +754,8 @@ void RepRap::GetStatusResponse(StringRef& response, uint8_t type, int seq, bool response.catf(",\"params\":{\"atxPower\":%d", platform->AtxPower() ? 1 : 0); // Cooling fan value - float fanValue = (gCodes->CoolingInverted() ? 1.0 - platform->GetFanValue() : platform->GetFanValue()); + //@TODO T3P3 only reports first PWM fan + float fanValue = (gCodes->CoolingInverted() ? 1.0 - platform->GetFanValue(0) : platform->GetFanValue(0)); response.catf(",\"fanPercent\":%.2f", fanValue * 100.0); // Speed and Extrusion factors diff --git a/Webserver.cpp b/Webserver.cpp index 1ed8249..85158f0 100644 --- a/Webserver.cpp +++ b/Webserver.cpp @@ -946,7 +946,6 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, StringRef& { // This is only possible if we have at least one HTTP session left response.copy("{\"err\":0}"); - } else {