Browse Source

Clean up HAL ADC, old test scripts

Scott Lahteine 5 years ago
parent
commit
a578749622

+ 5 - 5
Marlin/src/HAL/HAL_AVR/HAL.h

@@ -358,9 +358,9 @@ void TIMER0_COMPB_vect_bottom()
 
 // ADC
 #ifdef DIDR2
-  #define HAL_ANALOG_SELECT(pin) do{ if (pin < 8) SBI(DIDR0, pin); else SBI(DIDR2, pin & 0x07); }while(0)
+  #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0)
 #else
-  #define HAL_ANALOG_SELECT(pin) do{ SBI(DIDR0, pin); }while(0)
+  #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind);
 #endif
 
 inline void HAL_adc_init() {
@@ -371,11 +371,11 @@ inline void HAL_adc_init() {
   #endif
 }
 
-#define SET_ADMUX_ADCSRA(pin) ADMUX = _BV(REFS0) | (pin & 0x07); SBI(ADCSRA, ADSC)
+#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC)
 #ifdef MUX5
-  #define HAL_START_ADC(pin) if (pin > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
+  #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
 #else
-  #define HAL_START_ADC(pin) ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
+  #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
 #endif
 
 #define HAL_ADC_RESOLUTION 10

+ 2 - 2
Marlin/src/HAL/HAL_DUE/HAL.cpp

@@ -94,8 +94,8 @@ int freeMemory() {
 // ADC
 // ------------------------
 
-void HAL_adc_start_conversion(const uint8_t adc_pin) {
-  HAL_adc_result = analogRead(adc_pin);
+void HAL_adc_start_conversion(const uint8_t ch) {
+  HAL_adc_result = analogRead(ch);
 }
 
 uint16_t HAL_adc_get_result() {

+ 3 - 3
Marlin/src/HAL/HAL_DUE/HAL.h

@@ -148,16 +148,16 @@ extern uint16_t HAL_adc_result;     // result of last ADC conversion
   #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
 #endif
 
-#define HAL_ANALOG_SELECT(pin)
+#define HAL_ANALOG_SELECT(ch)
 
 inline void HAL_adc_init() {}//todo
 
-#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
+#define HAL_START_ADC(ch)   HAL_adc_start_conversion(ch)
 #define HAL_ADC_RESOLUTION  10
 #define HAL_READ_ADC()      HAL_adc_result
 #define HAL_ADC_READY()     true
 
-void HAL_adc_start_conversion(const uint8_t adc_pin);
+void HAL_adc_start_conversion(const uint8_t ch);
 uint16_t HAL_adc_get_result();
 
 //

+ 1 - 1
Marlin/src/HAL/HAL_ESP32/HAL.cpp

@@ -191,7 +191,7 @@ void HAL_adc_init() {
   }
 }
 
-void HAL_adc_start_conversion(uint8_t adc_pin) {
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
   const adc1_channel_t chan = get_channel(adc_pin);
   uint32_t mv;
   esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv);

+ 1 - 1
Marlin/src/HAL/HAL_ESP32/HAL.h

@@ -125,7 +125,7 @@ void HAL_adc_init();
 #define HAL_READ_ADC()      HAL_adc_result
 #define HAL_ADC_READY()     true
 
-void HAL_adc_start_conversion(uint8_t adc_pin);
+void HAL_adc_start_conversion(const uint8_t adc_pin);
 
 #define GET_PIN_MAP_PIN(index) index
 #define GET_PIN_MAP_INDEX(pin) pin

+ 1 - 1
Marlin/src/HAL/HAL_LINUX/HAL.cpp

@@ -55,7 +55,7 @@ void HAL_adc_init() {
 
 }
 
-void HAL_adc_enable_channel(int ch) {
+void HAL_adc_enable_channel(const uint8_t ch) {
 
 }
 

+ 7 - 7
Marlin/src/HAL/HAL_LINUX/HAL.h

@@ -87,15 +87,15 @@ int freeMemory();
 #pragma GCC diagnostic pop
 
 // ADC
-#define HAL_ANALOG_SELECT(pin) HAL_adc_enable_channel(pin)
-#define HAL_START_ADC(pin)     HAL_adc_start_conversion(pin)
-#define HAL_ADC_RESOLUTION     10
-#define HAL_READ_ADC()         HAL_adc_get_result()
-#define HAL_ADC_READY()        true
+#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
+#define HAL_START_ADC(ch)     HAL_adc_start_conversion(ch)
+#define HAL_ADC_RESOLUTION    10
+#define HAL_READ_ADC()        HAL_adc_get_result()
+#define HAL_ADC_READY()       true
 
 void HAL_adc_init();
-void HAL_adc_enable_channel(int pin);
-void HAL_adc_start_conversion(const uint8_t adc_pin);
+void HAL_adc_enable_channel(const uint8_t ch);
+void HAL_adc_start_conversion(const uint8_t ch);
 uint16_t HAL_adc_get_result();
 
 // Reset source

+ 1 - 5
Marlin/src/HAL/HAL_SAMD51/HAL.cpp

@@ -426,7 +426,7 @@ void HAL_adc_init() {
     memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results));                 // Fill result with invalid values
 
     for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi)
-        pinPeripheral(adc_pins[pi], PIO_ANALOG);
+      pinPeripheral(adc_pins[pi], PIO_ANALOG);
 
     for (uint8_t ai = FIRST_ADC; ai <= LAST_ADC; ++ai) {
       Adc* adc = ((Adc*[])ADC_INSTS)[ai];
@@ -471,8 +471,4 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
   HAL_adc_result = 0xFFFF;
 }
 
-uint16_t HAL_adc_get_result() {
-  return HAL_adc_result;
-}
-
 #endif // __SAMD51__

+ 1 - 1
Marlin/src/HAL/HAL_SAMD51/HAL.h

@@ -135,7 +135,7 @@ void HAL_adc_init();
 #define HAL_ADC_READY()     true
 
 void HAL_adc_start_conversion(const uint8_t adc_pin);
-uint16_t HAL_adc_get_result();
+inline uint16_t HAL_adc_get_result() { return HAL_adc_result; }
 
 //
 // Pin Map

+ 1 - 1
Marlin/src/HAL/HAL_TEENSY35_36/HAL.cpp

@@ -94,7 +94,7 @@ extern "C" {
 }
 
 void HAL_adc_start_conversion(const uint8_t adc_pin) {
-  uint16_t pin = pin2sc1a[adc_pin];
+  const uint16_t pin = pin2sc1a[adc_pin];
   if (pin == 0xFF) {
     // Digital only
     HAL_adc_select = -1;

Some files were not shown because too many files changed in this diff