diff --git a/src/current_sense/hardware_specific/samd/samd21_mcu.cpp b/src/current_sense/hardware_specific/samd/samd21_mcu.cpp index 046f3db4..3a045446 100644 --- a/src/current_sense/hardware_specific/samd/samd21_mcu.cpp +++ b/src/current_sense/hardware_specific/samd/samd21_mcu.cpp @@ -1,319 +1,173 @@ -#ifdef _SAMD21_ #include "samd21_mcu.h" -#include "../../hardware_api.h" - -static bool freeRunning = false; -static int _pinA, _pinB, _pinC; -static uint16_t a = 0xFFFF, b = 0xFFFF, c = 0xFFFF; // updated by adcStopWithDMA when configured in freerunning mode -static SAMDCurrentSenseADCDMA instance; +#if defined(_SAMD21_) -// function configuring low-side current sensing -void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC) -{ - _UNUSED(driver_params); +#include "../../hardware_api.h" +#include "../../../drivers/hardware_specific/samd/samd_mcu.h" - _pinA = pinA; - _pinB = pinB; - _pinC = pinC; - freeRunning = true; - instance.init(pinA, pinB, pinC); +static int _pinA = NOT_SET, _pinB = NOT_SET, _pinC = NOT_SET; +static uint16_t adc_raw[3] = {0, 0, 0}; +static uint8_t current_phase = 0; // which phase we're sampling +static bool is_high_side = true; // low-side current sense - GenericCurrentSenseParams* params = new GenericCurrentSenseParams { - .pins = { pinA, pinB, pinC } - }; +#define _SAMD21_ADC_VOLTAGE 3.3f +#define _SAMD21_ADC_RESOLUTION 4095.0f - return params; -} -void _startADC3PinConversionLowSide() -{ - instance.startADCScan(); -} -/** - * function reading an ADC value and returning the read voltage - * - * @param pinA - the arduino pin to be read (it has to be ADC pin) - */ -float _readADCVoltageLowSide(const int pinA, const void* cs_params) -{ - _UNUSED(cs_params); - - instance.readResults(a, b, c); +static void setupADCEventTriggerFromDriver(const SAMDHardwareDriverParams *par, const GenericCurrentSenseParams *cs_params) { - if(pinA == _pinA) - return instance.toVolts(a); - if(pinA == _pinB) - return instance.toVolts(b); - if(pinA == _pinC) - return instance.toVolts(c); - - return NAN; -} - -/** - * function syncing the Driver with the ADC for the LowSide Sensing - */ -void* _driverSyncLowSide(void* driver_params, void* cs_params) -{ - _UNUSED(driver_params); - - SIMPLEFOC_SAMD_DEBUG_SERIAL.println(F("TODO! _driverSyncLowSide() is not implemented")); - instance.startADCScan(); - //TODO: hook with PWM interrupts - - return cs_params; -} - - - - - - - - - - - // Credit: significant portions of this code were pulled from Paul Gould's git https://github.com/gouldpa/FOC-Arduino-Brushless - -static void adcStopWithDMA(void); -static void adcStartWithDMA(void); - -/** - * @brief ADC sync wait - * @retval void - */ -static __inline__ void ADCsync() __attribute__((always_inline, unused)); -static void ADCsync() { - while (ADC->STATUS.bit.SYNCBUSY == 1); //Just wait till the ADC is free -} + // --- Configure ADC module --- + ADC->CTRLA.bit.ENABLE = 0; + while (ADC->STATUS.bit.SYNCBUSY); + + ADC->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1; + ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV16 | ADC_CTRLB_RESSEL_12BIT; + ADC->CTRLB.bit.FREERUN = 0; + while (ADC->STATUS.bit.SYNCBUSY); + + ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[_pinA].ulADCChannelNumber; + // there must be a way to trigger more than one ADC conversion at a time. + // SO far I was not able to do it. + // ADC->INPUTCTRL.bit.INPUTSCAN = 1; // N = number_of_channels - 1 + // ADC->INPUTCTRL.bit.INPUTOFFSET = 0; + while (ADC->STATUS.bit.SYNCBUSY); + + // Enable event start + ADC->EVCTRL.bit.STARTEI = 1; + ADC->INTENSET.bit.RESRDY = 1; + NVIC_EnableIRQ(ADC_IRQn); + + // --- Configure Event System --- + uint8_t tcc_num = par->tccPinConfigurations[1]->tcc.tccn; + + // --- Enable event output on the PWM timer (important!) --- + Tcc* tcc = nullptr; + switch (tcc_num) { + case 0: tcc = TCC0; break; + case 1: tcc = TCC1; break; + case 2: tcc = TCC2; break; + default: tcc = TCC0; break; + } -// ADC DMA sequential free running (6) with Interrupts ///////////////// + // We are enabling the overflow/underflow event output + // This is not ideal as it triggers twice per PWM cycle + // So we need to keep track if we are in high-side or low-side current sense + if (tcc) { + tcc->CTRLA.bit.ENABLE = 0; + while (tcc->SYNCBUSY.bit.ENABLE); + tcc->EVCTRL.reg |= TCC_EVCTRL_OVFEO; + tcc->CTRLA.bit.ENABLE = 1; + while (tcc->SYNCBUSY.bit.ENABLE); + } -SAMDCurrentSenseADCDMA * SAMDCurrentSenseADCDMA::getHardwareAPIInstance() -{ - - return &instance; -} + // Configure the event channel to trigger on the TCC overflow + // and connect it to the ADC start event + uint8_t evgen = 0; + switch (tcc_num) { + case 0: evgen = EVSYS_ID_GEN_TCC0_OVF; break; + case 1: evgen = EVSYS_ID_GEN_TCC1_OVF; break; + case 2: evgen = EVSYS_ID_GEN_TCC2_OVF; break; + default: evgen = EVSYS_ID_GEN_TCC0_OVF; break; + } -SAMDCurrentSenseADCDMA::SAMDCurrentSenseADCDMA() -{ -} + PM->APBCMASK.reg |= PM_APBCMASK_EVSYS; + EVSYS->CHANNEL.reg = EVSYS_CHANNEL_CHANNEL(0) + | EVSYS_CHANNEL_EVGEN(evgen) + | EVSYS_CHANNEL_PATH_ASYNCHRONOUS; + EVSYS->USER.reg = EVSYS_USER_USER(EVSYS_ID_USER_ADC_START) + | EVSYS_USER_CHANNEL(1); -void SAMDCurrentSenseADCDMA::init(int pinA, int pinB, int pinC, int pinAREF, float voltageAREF, uint32_t adcBits, uint32_t channelDMA) -{ - this->pinA = pinA; - this->pinB = pinB; - this->pinC = pinC; - this->pinAREF = pinAREF; - this->channelDMA = channelDMA; - this->voltageAREF = voltageAREF; - this->maxCountsADC = 1 << adcBits; - countsToVolts = ( voltageAREF / maxCountsADC ); - - initPins(); - initADC(); - initDMA(); - startADCScan(); //so we have something to read next time we call readResults() + // Enable ADC + ADC->CTRLA.bit.ENABLE = 1; + while (ADC->STATUS.bit.SYNCBUSY); } -void SAMDCurrentSenseADCDMA::startADCScan(){ - adcToDMATransfer(adcBuffer + oneBeforeFirstAIN, BufferSize); - adcStartWithDMA(); -} - -bool SAMDCurrentSenseADCDMA::readResults(uint16_t & a, uint16_t & b, uint16_t & c){ - if(ADC->CTRLA.bit.ENABLE) - return false; - uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber; - uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber; - a = adcBuffer[ainA]; - b = adcBuffer[ainB]; - if(_isset(pinC)) - { - uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber; - c = adcBuffer[ainC]; +// ADC interrupt (switch between A, B, C) +void ADC_Handler() { + //digitalWrite(13,HIGH); + // check if we are in high-side or low-side current sense + is_high_side = !is_high_side; + if(is_high_side){ + ADC->INTFLAG.reg = ADC_INTFLAG_RESRDY; + //digitalWrite(13,LOW); + return; } - return true; -} - -float SAMDCurrentSenseADCDMA::toVolts(uint16_t counts) { - return counts * countsToVolts; -} - -void SAMDCurrentSenseADCDMA::initPins(){ + // read the result and switch to the next channel + if (ADC->INTFLAG.bit.RESRDY) { + uint16_t result = ADC->RESULT.reg; - if (pinAREF>=0) - pinMode(pinAREF, INPUT); - pinMode(pinA, INPUT); - pinMode(pinB, INPUT); - - uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber; - uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber; - firstAIN = min(ainA, ainB); - lastAIN = max(ainA, ainB); - if( _isset(pinC) ) - { - uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber; - pinMode(pinC, INPUT); - firstAIN = min(firstAIN, ainC); - lastAIN = max(lastAIN, ainC); + adc_raw[current_phase] = result; + if (current_phase == 0) { + ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[_pinB].ulADCChannelNumber; + current_phase = 1; + } else if (current_phase == 1) { + if (_pinC >= 0) { + ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[_pinC].ulADCChannelNumber; + current_phase = 2; + } else { + ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[_pinA].ulADCChannelNumber; + current_phase = 0; + } + } else { + ADC->INPUTCTRL.bit.MUXPOS = g_APinDescription[_pinA].ulADCChannelNumber; + current_phase = 0; + } + ADC->INTFLAG.reg = ADC_INTFLAG_RESRDY; } - - oneBeforeFirstAIN = firstAIN - 1; //hack to discard noisy first readout - BufferSize = lastAIN - oneBeforeFirstAIN + 1; - + //digitalWrite(13,LOW); } -void SAMDCurrentSenseADCDMA::initADC(){ - - analogRead(pinA); // do some pin init pinPeripheral() - analogRead(pinB); // do some pin init pinPeripheral() - analogRead(pinC); // do some pin init pinPeripheral() - - ADC->CTRLA.bit.ENABLE = 0x00; // Disable ADC - ADCsync(); - //ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_INTVCC0_Val; // 2.2297 V Supply VDDANA - ADC->INPUTCTRL.bit.GAIN = ADC_INPUTCTRL_GAIN_1X_Val; // Gain select as 1X - // ADC->INPUTCTRL.bit.GAIN = ADC_INPUTCTRL_GAIN_DIV2_Val; // default - if (pinAREF>=0) - ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_AREFA; - else - ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_INTVCC0; - ADCsync(); // ref 31.6.16 - - /* - Bits 19:16 – INPUTSCAN[3:0]: Number of Input Channels Included in Scan - This register gives the number of input sources included in the pin scan. The number of input sources included is - INPUTSCAN + 1. The input channels included are in the range from MUXPOS + INPUTOFFSET to MUXPOS + - INPUTOFFSET + INPUTSCAN. - The range of the scan mode must not exceed the number of input channels available on the device. - Bits 4:0 – MUXPOS[4:0]: Positive Mux Input Selection - These bits define the Mux selection for the positive ADC input. Table 32-14 shows the possible input selections. If - the internal bandgap voltage or temperature sensor input channel is selected, then the Sampling Time Length bit - group in the SamplingControl register must be written. - Table 32-14. Positive Mux Input Selection - MUXPOS[4:0] Group configuration Description - 0x00 PIN0 ADC AIN0 pin - 0x01 PIN1 ADC AIN1 pin - 0x02 PIN2 ADC AIN2 pin - 0x03 PIN3 ADC AIN3 pin - 0x04 PIN4 ADC AIN4 pin - 0x05 PIN5 ADC AIN5 pin - 0x06 PIN6 ADC AIN6 pin - 0x07 PIN7 ADC AIN7 pin - 0x08 PIN8 ADC AIN8 pin - 0x09 PIN9 ADC AIN9 pin - 0x0A PIN10 ADC AIN10 pin - 0x0B PIN11 ADC AIN11 pin - 0x0C PIN12 ADC AIN12 pin - 0x0D PIN13 ADC AIN13 pin - 0x0E PIN14 ADC AIN14 pin - 0x0F PIN15 ADC AIN15 pin - 0x10 PIN16 ADC AIN16 pin - 0x11 PIN17 ADC AIN17 pin - 0x12 PIN18 ADC AIN18 pin - 0x13 PIN19 ADC AIN19 pin - 0x14-0x17 Reserved - 0x18 TEMP Temperature reference - 0x19 BANDGAP Bandgap voltage - 0x1A SCALEDCOREVCC 1/4 scaled core supply - 0x1B SCALEDIOVCC 1/4 scaled I/O supply - 0x1C DAC DAC output - 0x1D-0x1F Reserved - */ - ADC->INPUTCTRL.bit.MUXPOS = oneBeforeFirstAIN; - ADCsync(); - ADC->INPUTCTRL.bit.INPUTSCAN = lastAIN; // so the adc will scan from oneBeforeFirstAIN to lastAIN (inclusive) - ADCsync(); - ADC->INPUTCTRL.bit.INPUTOFFSET = 0; //input scan cursor - ADCsync(); - ADC->AVGCTRL.reg = 0x00 ; //no averaging - ADC->SAMPCTRL.reg = 0x05; ; //sample length in 1/2 CLK_ADC cycles, see GCLK_ADC and ADC_CTRLB_PRESCALER_DIV16 - // according to the specsheet: f_GCLK_ADC ADC input clock frequency 48 MHz, so same as fCPU - ADCsync(); - ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV16 | ADC_CTRLB_FREERUN | ADC_CTRLB_RESSEL_12BIT; - ADCsync(); -} - -volatile dmacdescriptor wrb[12] __attribute__ ((aligned (16))); -void SAMDCurrentSenseADCDMA::initDMA() { - // probably on by default - PM->AHBMASK.reg |= PM_AHBMASK_DMAC ; - PM->APBBMASK.reg |= PM_APBBMASK_DMAC ; - NVIC_EnableIRQ( DMAC_IRQn ) ; - DMAC->BASEADDR.reg = (uint32_t)descriptor_section; - DMAC->WRBADDR.reg = (uint32_t)wrb; - DMAC->CTRL.reg = DMAC_CTRL_DMAENABLE | DMAC_CTRL_LVLEN(0xf); -} +// ------- API functions ------- +void* _configureADCLowSide(const void* driver_params, const int pinA, const int pinB, const int pinC) { -void SAMDCurrentSenseADCDMA::adcToDMATransfer(void *rxdata, uint32_t hwords) { + if(_isset(_pinA) || _isset(_pinB) || _isset(_pinC)) { + SIMPLEFOC_DEBUG("SAMD-CUR: ERR: Pins already in use for current sensing!"); + return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;; + } - DMAC->CHID.reg = DMAC_CHID_ID(channelDMA); - DMAC->CHCTRLA.reg &= ~DMAC_CHCTRLA_ENABLE; - DMAC->CHCTRLA.reg = DMAC_CHCTRLA_SWRST; - DMAC->SWTRIGCTRL.reg &= (uint32_t)(~(1 << channelDMA)); + // --- Configure ADC pins --- + if (_isset(pinA)) pinMode(pinA, INPUT); + if (_isset(pinB)) pinMode(pinB, INPUT); + if (_isset(pinC)) pinMode(pinC, INPUT); - DMAC->CHCTRLB.reg = DMAC_CHCTRLB_LVL(0) - | DMAC_CHCTRLB_TRIGSRC(ADC_DMAC_ID_RESRDY) - | DMAC_CHCTRLB_TRIGACT_BEAT; - DMAC->CHINTENSET.reg = DMAC_CHINTENSET_MASK ; // enable all 3 interrupts - descriptor.descaddr = 0; - descriptor.srcaddr = (uint32_t) &ADC->RESULT.reg; - descriptor.btcnt = hwords; - descriptor.dstaddr = (uint32_t)rxdata + hwords*2; // end address - descriptor.btctrl = DMAC_BTCTRL_BEATSIZE_HWORD | DMAC_BTCTRL_DSTINC | DMAC_BTCTRL_VALID; - memcpy(&descriptor_section[channelDMA],&descriptor, sizeof(dmacdescriptor)); - - // start channel - DMAC->CHID.reg = DMAC_CHID_ID(channelDMA); - DMAC->CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE; -} - + // save the pins for later use + // only one motor possible for now + _pinA = pinA; + _pinB = pinB; + _pinC = pinC; -int iii = 0; + GenericCurrentSenseParams* params = new GenericCurrentSenseParams { + .pins = { pinA, pinB, pinC }, + .adc_voltage_conv = (_SAMD21_ADC_VOLTAGE) / (_SAMD21_ADC_RESOLUTION), -void adcStopWithDMA(void){ - ADCsync(); - ADC->CTRLA.bit.ENABLE = 0x00; - // ADCsync(); - // if(iii++ % 1000 == 0) - // { - // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(a); - // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(" :: "); - // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(b); - // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(" :: "); - // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(c); - // SIMPLEFOC_SAMD_DEBUG_SERIAL.println("yo!"); - // } + }; + return params; +} -} +float _readADCVoltageLowSide(const int pin, const void* cs_params) { -void adcStartWithDMA(void){ - ADCsync(); - ADC->INPUTCTRL.bit.INPUTOFFSET = 0; - ADCsync(); - ADC->SWTRIG.bit.FLUSH = 1; - ADCsync(); - ADC->CTRLA.bit.ENABLE = 0x01; - ADCsync(); -} + // extract the ADC raw value for the given pin + float countsToVolts = ((GenericCurrentSenseParams*)cs_params)->adc_voltage_conv; -void DMAC_Handler() { - uint8_t active_channel; - active_channel = DMAC->INTPEND.reg & DMAC_INTPEND_ID_Msk; // get channel number - DMAC->CHID.reg = DMAC_CHID_ID(active_channel); - adcStopWithDMA(); - DMAC->CHINTFLAG.reg = DMAC_CHINTENCLR_TCMPL; // clear - DMAC->CHINTFLAG.reg = DMAC_CHINTENCLR_TERR; - DMAC->CHINTFLAG.reg = DMAC_CHINTENCLR_SUSP; + // read the value form the buffer + int i = 0; + for(auto p: ((GenericCurrentSenseParams*)cs_params)->pins) { + if (p == pin) return adc_raw[i] * countsToVolts; + i++; + } + return 0.0; // pin not available } +void* _driverSyncLowSide(void* driver_params, void* cs_params) { + + setupADCEventTriggerFromDriver((const SAMDHardwareDriverParams*)driver_params, (const GenericCurrentSenseParams*)cs_params); + return cs_params; +} -#endif \ No newline at end of file +#endif diff --git a/src/current_sense/hardware_specific/samd/samd21_mcu.h b/src/current_sense/hardware_specific/samd/samd21_mcu.h index e7d74426..1d323681 100644 --- a/src/current_sense/hardware_specific/samd/samd21_mcu.h +++ b/src/current_sense/hardware_specific/samd/samd21_mcu.h @@ -1,4 +1,6 @@ -#ifdef _SAMD21_ +#include "Arduino.h" + +#if defined(_SAMD21_) #ifndef CURRENT_SENSE_SAMD21_H #define CURRENT_SENSE_SAMD21_H @@ -8,59 +10,7 @@ #define SIMPLEFOC_SAMD_DEBUG_SERIAL Serial #endif -#include - typedef struct { - uint16_t btctrl; - uint16_t btcnt; - uint32_t srcaddr; - uint32_t dstaddr; - uint32_t descaddr; - } dmacdescriptor ; - - -// AREF pin is 42 - -class SAMDCurrentSenseADCDMA -{ - -public: - static SAMDCurrentSenseADCDMA * getHardwareAPIInstance(); - SAMDCurrentSenseADCDMA(); - void init(int pinA, int pinB, int pinC, int pinAREF = 42, float voltageAREF = 3.3, uint32_t adcBits = 12, uint32_t channelDMA = 3); - void startADCScan(); - bool readResults(uint16_t & a, uint16_t & b, uint16_t & c); - float toVolts(uint16_t counts); -private: - - void adcToDMATransfer(void *rxdata, uint32_t hwords); - - void initPins(); - void initADC(); - void initDMA(); - - uint32_t oneBeforeFirstAIN; // hack to discard first noisy readout - uint32_t firstAIN; - uint32_t lastAIN; - uint32_t BufferSize = 0; - - uint16_t adcBuffer[20]; - - - uint32_t pinA; - uint32_t pinB; - uint32_t pinC; - uint32_t pinAREF; - uint32_t channelDMA; // DMA channel - bool freeRunning; - - float voltageAREF; - float maxCountsADC; - float countsToVolts; - - dmacdescriptor descriptor_section[12] __attribute__ ((aligned (16))); - dmacdescriptor descriptor __attribute__ ((aligned (16))); - -}; +#include "../../hardware_api.h" #endif