diff --git a/Configuration.h b/Configuration.h index 408c938..86b50f9 100644 --- a/Configuration.h +++ b/Configuration.h @@ -24,8 +24,8 @@ Licence: GPL #define CONFIGURATION_H #define NAME "RepRapFirmware" -#define VERSION "0.78p-dc42" -#define DATE "2014-08-29" +#define VERSION "0.78q-dc42" +#define DATE "2014-08-31" #define AUTHORS "reprappro, dc42, zpl" // Other firmware that we might switch to be compatible with. diff --git a/Libraries/Lwip/lwip/src/sam/include/netif/ethernetif.h b/Libraries/Lwip/lwip/src/sam/include/netif/ethernetif.h index ba0eaab..4e41667 100644 --- a/Libraries/Lwip/lwip/src/sam/include/netif/ethernetif.h +++ b/Libraries/Lwip/lwip/src/sam/include/netif/ethernetif.h @@ -54,9 +54,11 @@ bool ethernetif_phy_link_status(void); //*****************************AB err_t ethernetif_init(struct netif *netif); -void ethernetif_input(void *pv_parameters); +bool ethernetif_input(void *pv_parameters); void ethernet_hardware_init(void); bool ethernet_establish_link(void); +void RepRapNetworkSetMACAddress(const u8_t macAddress[]); +void ethernetif_set_rx_callback(emac_dev_tx_cb_t callback); #endif /* ETHERNETIF_H_INCLUDED */ diff --git a/Libraries/Lwip/lwip/src/sam/netif/ethernetif.c b/Libraries/Lwip/lwip/src/sam/netif/ethernetif.c index 11fb6ab..3201b19 100644 --- a/Libraries/Lwip/lwip/src/sam/netif/ethernetif.c +++ b/Libraries/Lwip/lwip/src/sam/netif/ethernetif.c @@ -66,8 +66,6 @@ #include #include "conf_eth.h" -#include "SamNonDuePin.h" - //void my_ethernetif_input(void * pvParameters); //#include "gpio.h" @@ -416,29 +414,12 @@ static struct pbuf *low_level_input(struct netif *netif) * * \param pv_parameters the lwip network interface structure for this * ethernetif. + * + * \return Returns true if data has been processed. */ -//void ethernetif_input(void * pvParameters) -//{ -// struct netif *netif = (struct netif *)pvParameters; -// struct pbuf *p; -// -// /* move received packet into a new pbuf */ -// p = low_level_input( netif ); -// if( p == NULL ) -// return; -// -// if( ERR_OK != netif->input( p, netif ) ) -// { -// pbuf_free(p); -// p = NULL; -// } -//} - - -void ethernetif_input(void * pvParameters) +bool ethernetif_input(void * pvParameters) { - struct netif *netif = (struct netif *)pvParameters; struct pbuf *p; @@ -448,7 +429,8 @@ void ethernetif_input(void * pvParameters) #endif /* move received packet into a new pbuf */ p = low_level_input( netif ); - if( p == NULL ) { + if( p == NULL ) + { #ifdef FREERTOS_USED /* No packet could be read. Wait a for an interrupt to tell us there is more data available. */ @@ -456,17 +438,20 @@ void ethernetif_input(void * pvParameters) } }while( p == NULL ); #else - return; + return false; } #endif - if( ERR_OK != netif->input( p, netif ) ) { + if( ERR_OK != netif->input( p, netif ) ) + { pbuf_free(p); p = NULL; } #ifdef FREERTOS_USED } #endif + + return true; } @@ -540,3 +525,9 @@ void RepRapNetworkSetMACAddress(const u8_t macAddress[]) gs_uc_mac_address[i] = macAddress[i]; } } + + +void ethernetif_set_rx_callback(emac_dev_tx_cb_t callback) +{ + emac_dev_set_rx_callback(&gs_emac_dev, callback); +} diff --git a/Libraries/SamNonDuePin/SamNonDuePin.cpp b/Libraries/SamNonDuePin/SamNonDuePin.cpp index 4ce3cc5..9059f38 100644 --- a/Libraries/SamNonDuePin/SamNonDuePin.cpp +++ b/Libraries/SamNonDuePin/SamNonDuePin.cpp @@ -75,21 +75,22 @@ extern const PinDescription nonDuePinDescription[]= { NULL, 0, 0, PIO_NOT_A_PIN, PIO_DEFAULT, 0, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER } } ; +// Fixed version of PIO_SetDebounceFilter +static void SetDebounceFilter( Pio* pPio, const uint32_t dwMask, const uint32_t dwCuttOff ) +{ + pPio->PIO_IFER = dwMask; // enable input filtering, 0 bit field no effect + pPio->PIO_DIFSR = dwMask; // select debouncing filter, 0 bit field no effect + pPio->PIO_SCDR = ((32678/(2*(dwCuttOff))) - 1) & 0x3FFF; // the lowest 14 bits work +} /* pinModeNonDue copied from the pinMode function within wiring-digital.c file, part of the arduino core. Allows a non "Arduino Due" PIO pin to be setup. */ -extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode ) +extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode, uint32_t debounceCutoff ) { - if (ulPin < X0) - { - pinMode(ulPin, ulMode); // pass on to Arduino core - return; - } - - const PinDescription& pinDesc = nonDuePinDescription[ulPin - X0]; + const PinDescription& pinDesc = (ulPin >= X0) ? nonDuePinDescription[ulPin - X0] : g_APinDescription[ulPin]; if ( pinDesc.ulPinType == PIO_NOT_A_PIN ) { return; @@ -105,7 +106,11 @@ extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode ) PIO_INPUT, pinDesc.ulPin, 0 ) ; - break ; + if (debounceCutoff != 0) + { + SetDebounceFilter(pinDesc.pPort, pinDesc.ulPin, debounceCutoff); // enable debounce filer with specified cutoff frequency + } + break ; case INPUT_PULLUP: /* Enable peripheral for clocking input */ @@ -115,7 +120,11 @@ extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode ) PIO_INPUT, pinDesc.ulPin, PIO_PULLUP ) ; - break ; + if (debounceCutoff != 0) + { + SetDebounceFilter(pinDesc.pPort, pinDesc.ulPin, debounceCutoff); // enable debounce filer with specified cutoff frequency + } + break ; case OUTPUT: PIO_Configure( @@ -129,10 +138,10 @@ extern void pinModeNonDue( uint32_t ulPin, uint32_t ulMode ) { pmc_disable_periph_clk( pinDesc.ulPeripheralId ) ; } - break ; + break ; default: - break ; + break ; } } diff --git a/Libraries/SamNonDuePin/SamNonDuePin.h b/Libraries/SamNonDuePin/SamNonDuePin.h index 48e7393..4c32831 100644 --- a/Libraries/SamNonDuePin/SamNonDuePin.h +++ b/Libraries/SamNonDuePin/SamNonDuePin.h @@ -67,7 +67,7 @@ static const uint8_t PIN_EMAC_EMDIO = 24; // 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 ); +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 analogWriteNonDue(uint32_t ulPin, uint32_t ulValue, bool fastPwm = false); diff --git a/Platform.cpp b/Platform.cpp index 9e69009..8e251ba 100644 --- a/Platform.cpp +++ b/Platform.cpp @@ -28,7 +28,10 @@ extern "C" char *sbrk(int i); const uint8_t memPattern = 0xA5; -static volatile uint32_t fanRpmCounter = 0; +static uint32_t fanInterruptCount = 0; // accessed only in ISR, so no need to declare it volatile +const uint32_t fanMaxInterruptCount = 32; // number of fan interrupts that we average over +static volatile uint32_t fanLastResetTime = 0; // time (microseconds) at which we last reset the interrupt count, accessed inside and outside ISR +static volatile uint32_t fanInterval = 0; // written by ISR, read outside the ISR // Arduino initialise and loop functions // Put nothing in these other than calls to the RepRap equivalents @@ -230,11 +233,6 @@ void Platform::Init() gcodeDir = GCODE_DIR; tempDir = TEMP_DIR; - /* - FIXME Nasty having to specify individually if a pin is arduino or not. - requires a unified variant file. If implemented this would be much better - to allow for different hardware in the future - */ for (size_t i = 0; i < DRIVES; i++) { if (stepPins[i] >= 0) @@ -290,7 +288,7 @@ void Platform::Init() if (coolingFanRpmPin >= 0) { - pinModeNonDue(coolingFanRpmPin, INPUT_PULLUP); + pinModeNonDue(coolingFanRpmPin, INPUT_PULLUP, 500); // enable pullup and 500Hz debounce filter } InitialiseInterrupts(); @@ -627,7 +625,14 @@ void TC4_Handler() void FanInterrupt() { - fanRpmCounter++; + ++fanInterruptCount; + if (fanInterruptCount == fanMaxInterruptCount) + { + uint32_t now = micros(); + fanInterval = now - fanLastResetTime; + fanLastResetTime = now; + fanInterruptCount = 0; + } } void Platform::InitialiseInterrupts() @@ -1078,21 +1083,13 @@ void Platform::CoolingFan(float speed) float Platform::GetFanRPM() { - float now = Time(); - float diff = now - lastRpmResetTime; - - // Intel's 4-pin PWM fan specifications say we get two pulses per revolution. - // That means we get 2 ISR calls per pulse and 4 increments per revolution. - float result = (float)fanRpmCounter / (4.0 * diff) * 60.0; - - // Collect some values and reset the counters after a few seconds - if (diff > COOLING_FAN_RPM_SAMPLE_TIME) - { - fanRpmCounter = 0; - lastRpmResetTime = now; - } - - return result; + // The ISR sets fanInterval to the number of microseconds it took to get fanMaxInterruptCount interrupts. + // We get 2 tacho pulses per revolution, hence 2 interrupts per revolution. + // However, if the fan stops then we get no interrupts and fanInterval stops getting updated. + // We must recognise this and return zero. + return (fanInterval != 0 && micros() - fanLastResetTime < 3000000U) // if we have a reading and it is less than 3 second old + ? (float)((30000000U * fanMaxInterruptCount)/fanInterval) // then calculate RPM assuming 2 interrupts per rev + : 0.0; // else assume fan is off or tacho not connected } // Interrupts diff --git a/Release/RepRapFirmware-078q-dc42.bin b/Release/RepRapFirmware-078q-dc42.bin new file mode 100644 index 0000000..706a7c6 Binary files /dev/null and b/Release/RepRapFirmware-078q-dc42.bin differ diff --git a/Webserver.cpp b/Webserver.cpp index 97efeec..ffd7f7f 100644 --- a/Webserver.cpp +++ b/Webserver.cpp @@ -898,7 +898,7 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, StringRef& } else { - response.copy("{\"files\":[NONE]}"); + response.copy("{\"files\":[]}"); } } else if (StringEquals(request, "fileinfo"))