mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2024-11-30 15:26:18 +00:00
🐛 STM32 ADC followup (#22798)
This commit is contained in:
parent
a6b69ab6d5
commit
10fda222ea
@ -156,17 +156,17 @@ int freeMemory();
|
|||||||
|
|
||||||
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
|
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
|
||||||
extern uint32_t HAL_adc_reading;
|
extern uint32_t HAL_adc_reading;
|
||||||
[[gnu::always_inline]] inline void HAL_start_adc(const pin_t pin) {
|
[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) {
|
||||||
HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
|
HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
|
||||||
}
|
}
|
||||||
[[gnu::always_inline]] inline uint16_t HAL_read_adc() {
|
[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() {
|
||||||
return HAL_adc_reading;
|
return HAL_adc_reading;
|
||||||
}
|
}
|
||||||
|
|
||||||
#define HAL_adc_init()
|
#define HAL_adc_init()
|
||||||
#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
|
#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
|
||||||
#define HAL_START_ADC(pin) HAL_start_adc(pin)
|
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
|
||||||
#define HAL_READ_ADC() HAL_read_adc()
|
#define HAL_READ_ADC() HAL_adc_get_result()
|
||||||
#define HAL_ADC_READY() (true)
|
#define HAL_ADC_READY() (true)
|
||||||
|
|
||||||
// Test whether the pin is valid
|
// Test whether the pin is valid
|
||||||
|
@ -437,7 +437,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
|||||||
case POWER_MONITOR_VOLTAGE_PIN: pin_index = POWERMON_VOLTS; break;
|
case POWER_MONITOR_VOLTAGE_PIN: pin_index = POWERMON_VOLTS; break;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only.
|
HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
|
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
|
||||||
|
Loading…
Reference in New Issue
Block a user