Go Down

Topic: Using the Hardware Quadrature Encoder Channel on the DUE (Read 66420 times) previous topic - next topic

dougcl

Ah, yes I could just accumulate a counter in a larger integer and do a carry at the overflow.

I just need a delta count though. So reset at plus or minus 32K works great for me.

I admit to using the SAM3S datasheet
http://ww1.microchip.com/downloads/en/DeviceDoc/Atmel-6500-32-bit-Cortex-M3-Microcontroller-SAM3S4-SAM3S2-SAM3S1_Datasheet.pdf

which shows the FILTER bit on page 768.

• FILTER:
0 = IDX,PHA, PHB input pins are not filtered.
1 = IDX,PHA, PHB input pins are filtered using MAXFILT value.

Looks like SAM3X is different. I suspect that it has no effect (except perhaps to disable), because the SAM3S datasheet also says that the filter is enabled when QDEC is enabled.

Regarding reset to avoid overflow using
TC0->TC_CHANNEL[0].TC_CCR = TC_CCR_SWTRG | TC_CCR_CLKEN;

It seems that the reset does indeed work, but the counter value of zero is not active until the encoder has been touched again. At least I think that's what is happening.

ard_newbie

Looks like SAM3X is different. I suspect that it has no effect (except perhaps to disable), because the SAM3S datasheet also says that the filter is enabled when QDEC is enabled.

If you look at Sam3x, Sam4 or Sam7 datasheets, the quadrature decoders are all the same, FILTER bit is missing in the documentation BUT present in the header files, therefore IMO the right version of TC_BMR register is in Sam3s datasheet and the same for all Sam versions.

Val69-Fr

Hello,

To begin, I don't have much knowledge in Aurduino DUE.

I bought an arduino DUE in order to get the speed of 2 RENISHAW Atom quadrature encoders with a Lowest recommended counter input frequency of 25MHz.
https://www.renishaw.com/en/atom-incremental-encoder-system-with-rtlf-linear-scale--24183

First of all, I read the various datasheet and previous post to understand what you did.

However, I wish in my case connect on the same arduino DUE my 2 encoders (without index) to know their speed (negative or positive) and save them or print them on serial port. Is that possible with DUE ?

Thanks in advance

ard_newbie

You can use both quadrature decoder QDEC0 and QDEC1 at the same time, for speed or position measurement of rotary quadrature encoders.

Two hardware quadrature decoder QDEC0 and QDEC1:
QDEC0:
Timer Counter 0 channel 0 / TIOA and TIOB of channel 0
PHA  TIOA0       =   pin 2
PHB  TIOB0       =   pin 13

Timer Counter 0 channel 1 / TIOB of channel 1
INDEX  TIOB1   =   pin A6

QDEC1:
Timer Counter 2 channel 0 / TIOA and TIOB of channel 0
PHA  TIOA6      =   pin 5
PHB  TIOB6       =   pin 4

Timer Counter 2 channel 1 / TIOB of channel 1
INDEX  TIOB7   =   pin 10


A minimal example sketch for speed measurement with QDEC1 (For QDEC0, replace TC2 accordingly):

Code: [Select]

/***************************************************************************************************/
/*                          QDEC Speed mode by polling in loop()                                   */
/***************************************************************************************************/

/*
  In speed mode, the results are accumulated within the time base (100 ms in this example).
  Every 100 ms, we get an edge that is connected internally thru TIOA8 to TC6. Depending on the user
  application and the requirement, the user must modify the time base with respect to their speed range.
  For example, if the application requires low speed measurement, the time base can be increased to get
  the fine results. For higher speed measurement, the user must choose the lesser time base so that the
  number of pulses counted does not overflow beyond the channel 0 counter (32-bit). If this is not taken
  care, the results may be inaccurate.
*/
const uint32_t ENCODER_CPR = 150;                            // Cycles per revolution; this depends on your encoder
const uint32_t ENCODER_EDGES_PER_ROTATION = ENCODER_CPR * 4; // PPR = CPR * 4
const uint32_t ENCODER_SAMPLES_PER_SECOND = 10;              // this will need to be tuned depending on your use case...
const uint32_t LOOP_DELAY_MS = 1 * 100;                     // ... as will this

void setup() {

  Serial.begin(250000);

  PMC->PMC_PCER1 = PMC_PCER1_PID33                  // TC6 power ON ; Timer counter 2 channel 0 is TC6
                   | PMC_PCER1_PID34                // TC7 power ON ; Timer counter 2 channel 1 is TC7
                   | PMC_PCER1_PID35;               // TC8 power ON ; Timer counter 2 channel 2 is TC8

  // TC8 in waveform mode
  TC2->TC_CHANNEL[2].TC_CMR = TC_CMR_TCCLKS_TIMER_CLOCK1  // Select Mck/2
                              | TC_CMR_WAVE               // Waveform mode
                              | TC_CMR_ACPC_TOGGLE        // Toggle TIOA of TC2 (TIOA8) on RC compare match
                              | TC_CMR_WAVSEL_UP_RC;      // UP mode with automatic trigger on RC Compare match

  TC2->TC_CHANNEL[2].TC_RC = F_CPU / 2 / ENCODER_SAMPLES_PER_SECOND;  // F_CPU = 84 MHz
  // Final TC frequency is 84 MHz/2/TC_RC

  // TC6 in capture mode
  // Timer Counter 2 channel 0 is internally clocked by TIOA8
  TC2->TC_CHANNEL[0].TC_CMR = TC_CMR_ABETRG               // TIOA8 is used as an external trigger.
                              | TC_CMR_TCCLKS_XC0         // External clock selected
                              | TC_CMR_LDRA_EDGE          // RA loading on each edge of TIOA6
                              | TC_CMR_ETRGEDG_RISING     // External TC trigger by edge selection of TIOA8
                              | TC_CMR_CPCTRG;            // RC Compare match resets the counter and starts the counter clock

  TC2->TC_BMR = TC_BMR_QDEN                               // Enable QDEC (filter, edge detection and quadrature decoding)
                | TC_BMR_SPEEDEN                          // Enable the speed measure on channel 0, the time base being provided by channel 2.
                | TC_BMR_EDGPHA                           // Edges are detected on both PHA and PHB
                | TC_BMR_SWAP                             // Swap PHA and PHB if necessary
                | TC_BMR_MAXFILT(1);                      // Pulses with a period shorter than MAXFILT+1 peripheral clock cycles are discarded

  TC2->TC_CHANNEL[0].TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG;
  TC2->TC_CHANNEL[1].TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG;
  TC2->TC_CHANNEL[2].TC_CCR = TC_CCR_CLKEN | TC_CCR_SWTRG;

}

void loop() {
  double dSpeedRPS, dSpeedRPM;
  int32_t __dSpeedRPM;
  int32_t iSpeedPPP;

  iSpeedPPP = TC2->TC_CHANNEL[0].TC_RA;

  dSpeedRPS = ((iSpeedPPP / (ENCODER_EDGES_PER_ROTATION * 1.0)) * ENCODER_SAMPLES_PER_SECOND);
  dSpeedRPM =  dSpeedRPS * 60;
  __dSpeedRPM = (int32_t) dSpeedRPM;

  printf(
    " Speed rpm: %d \n",
    __dSpeedRPM
  );
  delay(LOOP_DELAY_MS);
}



Your encoders doc is unclear to me, Your encoders seem to run either as linear or rotary encoders. If they are used as rotary encoders, the speed measurement code is relevant, providing you know the number of pulses per revolution. For a linear use, search the code for Position measurement (an example in this thread, reply #87).

The DUE is 3.3V compliant, be careful with the voltage of the encoders output signals.

The "Master" clock of the DUE Timer Counters is 42 MHz (84 MHz/2).

Go Up