diff --git a/Marlin/src/HAL/HAL_SAMD51/HAL.cpp b/Marlin/src/HAL/HAL_SAMD51/HAL.cpp index 1d7521270f..35863477e8 100644 --- a/Marlin/src/HAL/HAL_SAMD51/HAL.cpp +++ b/Marlin/src/HAL/HAL_SAMD51/HAL.cpp @@ -442,9 +442,11 @@ void HAL_adc_init() { // Preloaded data (fixed for all ADC instances hence not loaded by DMA) adc->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_AREFA_Val; // VRefA pin SYNC(adc->SYNCBUSY.bit.REFCTRL); - adc->CTRLB.bit.RESSEL = ADC_CTRLB_RESSEL_10BIT_Val; + adc->CTRLB.bit.RESSEL = ADC_CTRLB_RESSEL_12BIT_Val; SYNC(adc->SYNCBUSY.bit.CTRLB); adc->SAMPCTRL.bit.SAMPLEN = (6 - 1); // Sampling clocks + adc->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_16 | ADC_AVGCTRL_ADJRES(4); // 16 Accumulated conversions and shift 4 to get oversampled 12 bits result + SYNC(adc->SYNCBUSY.bit.AVGCTRL); // Registers loaded by DMA adc->DSEQCTRL.bit.INPUTCTRL = true; diff --git a/Marlin/src/HAL/HAL_SAMD51/HAL.h b/Marlin/src/HAL/HAL_SAMD51/HAL.h index 5966e958d4..dea84da5d1 100644 --- a/Marlin/src/HAL/HAL_SAMD51/HAL.h +++ b/Marlin/src/HAL/HAL_SAMD51/HAL.h @@ -109,8 +109,9 @@ extern uint16_t HAL_adc_result; // result of last ADC conversion void HAL_adc_init(); +#define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL +#define HAL_ADC_RESOLUTION 12 #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_ADC_RESOLUTION 10 #define HAL_READ_ADC() HAL_adc_result #define HAL_ADC_READY() true