1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-12-23 12:51:24 +01:00

SAMD21 ADCee fixes

This commit is contained in:
pmantoine 2022-10-14 18:55:12 +08:00
parent 578cbd08e5
commit f39a9d1510
2 changed files with 49 additions and 23 deletions

View File

@ -30,6 +30,8 @@
#include "DCCTimer.h"
#include <wiring_private.h>
#include <DIAG.h>
#include <FSH.h>
INTERRUPT_CALLBACK interruptHandler=0;
@ -161,20 +163,46 @@ int * ADCee::analogvals = NULL;
int ADCee::init(uint8_t pin) {
uint id = pin - A0;
int value = 0;
if (id > NUM_ADC_INPUTS)
return -1023;
analogReadResolution(12); // Consistent with settings in ADCee::begin below
int value = analogRead(pin);
// Dummy read using Arduino library
analogReadResolution(12);
value = analogRead(pin);
// Reconfigure ADC
ADC->CTRLA.bit.ENABLE = 0; // disable ADC
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
ADC->CTRLB.reg &= 0b1111100011001111; // mask PRESCALER and RESSEL bits
ADC->CTRLB.reg |= ADC_CTRLB_PRESCALER_DIV64 | // divide Clock by 16
ADC_CTRLB_RESSEL_12BIT; // Result 12 bits, 10 bits possible
ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_1 | // take 1 sample at a time
ADC_AVGCTRL_ADJRES(0x00ul); // adjusting result by 0
ADC->SAMPCTRL.reg = 0x00ul; // sampling Time Length = 0
ADC->CTRLA.bit.ENABLE = 1; // enable ADC
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
// Permanently configure SAMD IO MUX for that pin
pinPeripheral(pin, PIO_ANALOG);
ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[pin].ulADCChannelNumber; // Selection for the positive ADC input
// Start conversion
ADC->SWTRIG.bit.START = 1;
// Wait for the conversion to be ready
while (ADC->INTFLAG.bit.RESRDY == 0); // Waiting for conversion to complete
// Read the value
value = ADC->RESULT.reg;
if (analogvals == NULL)
analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int));
analogvals[id] = value;
usedpins |= (1<<id);
// Permanently configure SAMD IO MUX for that pin
pinPeripheral(pin, PIO_ANALOG);
ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[pin].ulADCChannelNumber; // Selection for the positive ADC input
return value;
}
int16_t ADCee::ADCmax() {
@ -207,8 +235,6 @@ void ADCee::scan() {
return; // no result, continue to wait
// found value
analogvals[id] = ADC->RESULT.reg;
// Clear the Data Ready flag
ADC->INTFLAG.reg = ADC_INTFLAG_RESRDY;
// advance at least one track
// for scope debug TrackManager::track[1]->setBrake(0);
waiting = false;
@ -226,8 +252,8 @@ void ADCee::scan() {
while (true) {
if (mask & usedpins) {
// start new ADC aquire on id
ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[id].ulADCChannelNumber; // Selection for the positive ADC input
// Start conversion
ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[id + A0].ulADCChannelNumber; // Selection for the positive ADC input
// Start conversion
ADC->SWTRIG.bit.START = 1;
// for scope debug TrackManager::track[1]->setBrake(1);
waiting = true;
@ -249,19 +275,18 @@ void ADCee::begin() {
// Set up ADC to do faster reads... default for Arduino Zero platform configs is 436uS,
// and we need sub-58uS. This code sets it to a read speed of around 5-6uS, and enables
// 12-bit mode
ADC->CTRLA.bit.ENABLE = 0; // disable ADC
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
// Reconfigure ADC
ADC->CTRLA.bit.ENABLE = 0; // disable ADC
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
ADC->CTRLB.reg &= 0b1111100011001111; // mask PRESCALER and RESSEL bits
ADC->CTRLB.reg |= ADC_CTRLB_PRESCALER_DIV16 | // divide Clock by 16
ADC_CTRLB_RESSEL_12BIT; // Result is 12 bits, 10 bits possible
ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_1 | // take 1 sample at a time
ADC_AVGCTRL_ADJRES(0x00ul); // adjusting result by 0
ADC->SAMPCTRL.reg = 0x00; // sampling Time Length = 0
ADC->CTRLA.bit.ENABLE = 1; // enable ADC
while(ADC->STATUS.bit.SYNCBUSY == 1); // wait for synchronization
ADC->CTRLB.reg &= 0b1111100011001111; // mask PRESCALER and RESSEL bits
ADC->CTRLB.reg |= ADC_CTRLB_PRESCALER_DIV64 | // divide Clock by 16
ADC_CTRLB_RESSEL_12BIT; // Result 12 bits, 10 bits possible
ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_1 | // take 1 sample at a time
ADC_AVGCTRL_ADJRES(0x00ul); // adjusting result by 0
ADC->SAMPCTRL.reg = 0x00ul; // sampling Time Length = 0
ADC->CTRLA.bit.ENABLE = 1; // enable ADC
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
interrupts();
}
#endif

View File

@ -59,7 +59,7 @@
// Arduino STANDARD Motor Shield, used on different architectures:
#if defined(ARDUINO_ARCH_SAMD)
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
// Setup for SAMD21 Sparkfun DEV board using Arduino standard Motor Shield R3 (MUST be R3
// for 3v3 compatibility!!) senseFactor for 3.3v systems is 1.95 as calculated when using
// 10-bit A/D samples, and for 12-bit samples it's more like 0.488, but we probably need
@ -68,6 +68,7 @@
new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 0.488, 1500, UNUSED_PIN), \
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 0.488, 1500, UNUSED_PIN)
#define SAMD_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
#define STM32_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
#elif defined(ARDUINO_ARCH_ESP32)
// STANDARD shield on an ESPDUINO-32 (ESP32 in Uno form factor). The shield must be eiter the