That one's working fine! good job!
I bow to the master an with humble respect! You da man!
Seriously though, thank you. I will have to try playing around with the edge triggering because in my test, for very slow rotations of the motor, the index pulse fails to increment the index counter and thereby creates some seriously erroneous readings.
I have been attempting to use Channel2 as a clock to determine speed and I believe I finally got it.
The code below is from the initial program I posted (Reply #32) but with Channel2 enabled and set to TCLK4. I also added more remarks and cleaned it up a bit.
Index interrupts must be enabled for the speed portion to work.
/*
Quadrature Encoder with Marker via hardware
*/
volatile int z_Total=0;
volatile double TPR=0;
void setup() {
Serial.begin(115200);
delay(100);
// Setup Quadrature Encoder
REG_PMC_PCER0 = (1<<27)|(1<<28)|(1<<29); // activate clock for TC0,TC1,TC2
// select XC0 as clock source and set capture mode
REG_TC0_CMR0 = 5;
//Resets the count every index. Rem out the line above,
//and use the line below instead.
//REG_TC0_CMR0 = (1<<0)|(1<<2)|(1<<8)|(1<<10);
REG_TC0_CMR2 = (1<<0)|(1<<1); // Set to TCLK4
// activate quadrature encoder and position measure mode, no filters
REG_TC0_BMR = (1<<8)|(1<<9)|(1<<12);
// Enable the clock (CLKEN=1) and reset the counter (SWTRG=1)
REG_TC0_CCR0 = 5;
REG_TC0_CCR1 = 5;
REG_TC0_CCR2 = 5;
//Remark out these 4 lines to disable Index interrupts
REG_TC0_CMR1 = (1<<8); // Set rising edge of Z
REG_TC0_IER1=0b10000000; // enable interrupt on Z
REG_TC0_IDR1=0b01111111; // disable other interrupts
NVIC_EnableIRQ(TC1_IRQn);
}
void loop() {
//REG_TC0_CV0 Stores count from encoder
Serial.println(REG_TC0_CV0);
//REG_TC0_CV1 Stores count from index if interrupts are off
//if interrupts are on, CV1 will always reset every cycle to zero.
if (REG_TC0_CV1 == 0)
{
Serial.print(z_Total);
Serial.println(" -With Int");
}
else
{
Serial.print(REG_TC0_CV1);
Serial.println(" -No Int");
}
//TPR holds the quantity of ticks every Index. Index interrupts must be on.
//TCLK4 is set so 128 is the divisor.
Serial.print((F_CPU/128/TPR)*60);Serial.println(" RPM");
Serial.println("-------");
delay(500);
}
void TC1_Handler() {
//This won't fire unless the Index interrupt is enabled above
z_Total++;
long dummy=REG_TC0_SR1; // vital - reading this clears some flag
// otherwise you get infinite interrupts
TPR=REG_TC0_CV2; //Store ticks
REG_TC0_CCR2 = 4; //Reset counter
}
OK sorry to bring up a dieing thread but...
I am about to wire up my arduino DUE to my table and i want to make sure i am getting this right. So from the Encoder i have 3.3v in (where 5v should be) and gnd connected. i take channel A+, B+, and Z+ and connect them directly to 2,13,A6 respectively. (my encoder has A-,B-, Z- aswell).
than i can upload the below code straight from arduino 1.5._?
/*
Quadrature Encoder with Marker via hardware
*/
volatile int z_Total=0;
volatile double TPR=0;
void setup() {
Serial.begin(115200);
delay(100);
// Setup Quadrature Encoder
REG_PMC_PCER0 = (1<<27)|(1<<28)|(1<<29); // activate clock for TC0,TC1,TC2
// select XC0 as clock source and set capture mode
REG_TC0_CMR0 = 5;
//Resets the count every index. Rem out the line above,
//and use the line below instead.
//REG_TC0_CMR0 = (1<<0)|(1<<2)|(1<<8)|(1<<10);
REG_TC0_CMR2 = (1<<0)|(1<<1); // Set to TCLK4
// activate quadrature encoder and position measure mode, no filters
REG_TC0_BMR = (1<<8)|(1<<9)|(1<<12);
// Enable the clock (CLKEN=1) and reset the counter (SWTRG=1)
REG_TC0_CCR0 = 5;
REG_TC0_CCR1 = 5;
REG_TC0_CCR2 = 5;
//Remark out these 4 lines to disable Index interrupts
REG_TC0_CMR1 = (1<<8); // Set rising edge of Z
REG_TC0_IER1=0b10000000; // enable interrupt on Z
REG_TC0_IDR1=0b01111111; // disable other interrupts
NVIC_EnableIRQ(TC1_IRQn);
}
void loop() {
//REG_TC0_CV0 Stores count from encoder
Serial.println(REG_TC0_CV0);
//REG_TC0_CV1 Stores count from index if interrupts are off
//if interrupts are on, CV1 will always reset every cycle to zero.
if (REG_TC0_CV1 == 0)
{
Serial.print(z_Total);
Serial.println(" -With Int");
}
else
{
Serial.print(REG_TC0_CV1);
Serial.println(" -No Int");
}
//TPR holds the quantity of ticks every Index. Index interrupts must be on.
//TCLK4 is set so 128 is the divisor.
Serial.print((F_CPU/128/TPR)*60);Serial.println(" RPM");
Serial.println("-------");
delay(500);
}
void TC1_Handler() {
//This won't fire unless the Index interrupt is enabled above
z_Total++;
long dummy=REG_TC0_SR1; // vital - reading this clears some flag
// otherwise you get infinite interrupts
TPR=REG_TC0_CV2; //Store ticks
REG_TC0_CCR2 = 4; //Reset counter
}
Code-wise you're correct with the pin numbers. Not sure about voltage because you didn't mention what encoder you're using.
I used an encoder with A+, A-, B+, B-, Z+, Z- and ran it into a Maxim MAX3096 422 receiver. This allowed me to run the encoder with 24vdc and interface it to the DUE 3.3v. It also gives great noise immunity.
Just an update, hardware wise it works!! the 5v encoder works just fine at 3.3v, i am getting some feedback.
The code works OK (havent verifyed . it gives me number of pulses for what i see correctly. i am thinking of hooking up my O-Scope and verifying it.
I dont know much about working directly with registers, but what type of data is REG_TC0_CV0? i am looking to use it in a PID loop. and how do i manualy reset it to 0? I have "home" switchs on my machine that i want to make 0,0.
CV0 stores the current pulse count from A&B. The code your using is currently set to reset this value every Z. If you would like it to accumulate without resetting every rotation, read post #39 and reverse the code.
As for using your home switch, there might be a hardware method of tying that input to the counter but I'm not sure.
I would probably create an interrupt routine for that input and in the routine use "REG_TC0_CCR0 = 4;" This does a software trigger and will reset CV0 once your have reversed the modification done in post #39. (Info located at 37.7.3 in the ARM docs)
well modified the code... eliminated the z interup stuff. and allowed the counter to continuity count up. what type of data is CV0 + CV1. i still havent hooked up my o-scope to verify everything. but everytime the index pulse comes in the counter is going up 999, so i have strong feelings that its working.
thank you everyone for the wonderfull code. you should button it up as a library. define the library as with z axis. alow them to reset the counter. etc.
but the biggest thing is thank you all, this is a very wonderfull comuinity and always has been.
Its a six month old thread, but I wanted to try digging it back up...
I have the code working in post #32 and post #42 - thank you.
Reading the SAM3X manual (http://www.atmel.com/Images/doc11057.pdf) page 891 section 37.6.14.5, it looks like this can be put into a Speed Measurement Mode rather than a Position Measurement Mode, allowing you to grab the speed directly, rather than having to calculate it (e.g. in theory it should give an answer similar to post #42 except more work is offloaded and I suspect no interrupts are required).
However, this is not my area of expertise; I've tried to understand the code so far combined with the docs, but have got well and truly lost. What I have so far is;
/*
Quadrature Encoder with Marker via hardware
*/
void setup() {
Serial.begin(9600);
delay(10);
// Setup Quadrature Encoder
// http://www.atmel.com/Images/doc11057.pdf
// Speed measurement is p891
// Activate clock for TC0,TC1,TC2
REG_PMC_PCER0 = (1<<27)|(1<<28)|(1<<29);
// Page 895 (Enable features)
REG_TC0_BMR = TC_BMR_QDEN
| TC_BMR_SPEEDEN;
// Page 891,
REG_TC0_CMR2 = TC_CMR_TCCLKS_TIMER_CLOCK2
| TC_CMR_WAVE
| TC_CMR_ACPA_TOGGLE
| TC_CMR_WAVSEL_UPDOWN;
//Page 904
REG_TC0_CMR0 = TC_CMR_ABETRG
| TC_CMR_LDRA_RISING
| TC_CMR_LDRB_RISING
| TC_CMR_ETRGEDG_RISING;
// Enable the clock (CLKEN=1) and reset the counter (SWTRG=1)
REG_TC0_CCR0 = TC_CCR_CLKEN | TC_CCR_SWTRG;
REG_TC0_CCR1 = TC_CCR_CLKEN | TC_CCR_SWTRG;
REG_TC0_CCR2 = TC_CCR_CLKEN | TC_CCR_SWTRG;
}
void loop() {
Serial.print(REG_TC0_CV0);
Serial.print(", ");
Serial.print(REG_TC0_CV1);
Serial.print(", ");
Serial.print(REG_TC0_CV2);
Serial.println();
Serial.print(" ");
Serial.print(REG_TC0_CMR0);
Serial.print(", ");
Serial.print(REG_TC0_RA0);
Serial.println();
delay(1000);
}
If you try this example, and turn the encoder, things "tick", but the all important "speed" is doing nothing.
1282, 6527, 1565282450
328960, 0
2388, 6531, 1576160954
328960, 0
6496, 6533, 1587038366
328960, 0
6496, 6533, 1597916870
328960, 0
As I mentioned, I don't really know what I am doing; a combination of Google, manuals and educated guesses have got me this far, but I am obviously doing something plain wrong!
If any one has this Speed Measurement working, I would be interested to know.
Thanks
bungle99
Using DUE
How do I use 02 encoders?
If possible with the pins too.
I'm a newbie at this. :~ :~ :~
O2 encoder?
I'm not sure what was meant by the "O2 Encoder" either. However, if this is some form / make of quadrature encoder, then I can confirm that the code in post #32 and post #42 work out of the box (including the pin assignments). However, I'd recommend reading the whole thread as there are some interesting nuggets on how to alter the code to do specific tasks.
If anyone has any ideas on enabling the hardware "speed measure" mode, that would be appreciated as I'm still stumped after a good few hours of playing!
Have you tried enabling the interrupts?
You also need to enter a timebase value before it will start counting (see 37.6.14.1 in the Arm Doc and also 37.6.14.5)
It's been awhile since I went through this. Hope it helps.
Many thanks for the feedback.
I don't think interrupts should need to be enabled for this particular feature; the data sheet implies that Speed can be calculated "passively".
The timebase is the bit I think might be awry. Staring at the data sheet again now
I've got this working. There were two big mistakes (and some minor things) in my original code
- In the input, I needed to use WAVESL_*_RC (note the RC) to trigger the calcs
- I needed to pass in a suitable value (based on the clock) to REG_TC0_RC2 to define the "sample period"
The code's a mess; let me tidy it up and I will repost it.
This example uses the Due's hardware to decode a Quadrature Encoder input to determine speed.
No interrupts required. Can deal with higher speeds due to being a hardware based solution.
Most other samples in this thread are Position based, whereas this is Speed based. If you want position, then you need to look at Post #32. Calculating speed is a little harder; for example, see post #42 that does this using Position and an interrupt to give some concept of time. However, I believe this example simplifies things and improves the speed calculation by using the hardware for its calc (e.g. no need to wait for an Index interrupt to fire).
Many thanks to @Designservicecorp (notably post #32 and post #42) that gave me the base to work from.
See code for notes / comments.
Has had some basic testing, but YMMV. Don't blame me if it blows something up!
/*
** Quadrature Encoder on Arduino Due in "Speed Mode"
** Will not work on other Arduino types because of a specific hardware requirement.
**
** @bungle99 / 2014-02-28
**
** Many thanks to @Designservicecorp (notably post #32 and post #42) that gave me the base to work from.
**
** Uses *hardware* to do the heavy lifting of interpreting the Encoder output, which gives it significant
** advantage over other Arduino's for this use case. Eg many people have reported their Unos maxing out
** or skipping counts when interpretting high RPMs, whereas people using the Due in hardware mode have
** reported better success with high RPMs.
**
** This particular example puts the hardware into "Speed" mode, whereas other examples in this thread use
** "Position" mode (see posts 32, 42). The one example in the thread that attempts Speed calcs uses Position
** Mode and uses an interrupt on the Z Index axis to manually apply a time period (needed to caculate speed)
** on each rotation.
**
** This code below has been used in tests (using Lego NXT and a gear train for driving / comparison) to
** ~3,500 RPM with a 1,024 PPR Encoder (4 x 1,024 Edges). The Arduino didn't seem to struggle and the
** numbers (eg RPM) matched fairly closely with the Lego (eg as a sanity check, the calcs in the code look
** correct).
**
** I bought one of these encoders, which seems ok;
**
** * http://proto-pic.co.uk/rotary-encoder-1024-p-r-quadrature/
**
** Great service from proto-pic. The encoder specs are officially
**
** * http://dlnmh9ip6v2uc.cloudfront.net/datasheets/Robotics/E6B2Encoders.pdf
**
** But look an awful lot like this one too (which is easier to read)
**
** * http://www.ia.omron.com/product/item/e6b27032r/index.html
**
** Note that this Encoder is rated at 5V min. I've successully powered it off the 5V Arduino pin header,
** and it doesn't work off the 3.3V one. At 5V, the outputs need to be run through some resistors to bring
** them into tolerance of the Arduino inputs.
**
** The inputs are 2 and 13 (and optionally A6 for the index).
**
** The test hardware (some Lego NXT servos and gear train) was unable to turn any faster (more gears
** stalled the servos) - eg the Arduino Due was not the limiting factor. At this speed, the Due Hardware
** is dealing with approx 238,000 edges per second.
**
** This example offloads the speed calculation onto the hardware, meaning no interrupt is required.
** In addition, the index is not required either, so it allows speeds to be seen even for rotations that
** don't pass the index marker (for example, slow rotations needing a speed before a complete rotation).
** That said, index is available if you want it and the docs suggest you can still use it (and others) as
** interrupt if you wish.
**
** NB There appears to be a myriad of features on the Chip that have not been touched. Eg you can still add
** interrupts to this code to do other things; eg passing the Z index, direction changes. There are also
** filters available if your encoder suffers from noise (eg vibrations). All this is available to play with
** another day :)
**
** Code appears to work, but no guarantees. Understand it. Test it. Feedback to the group. YMMV. Don't blame
** me if it doesn't work or expolodes!
*/
const int ENCODER_EDGES_PER_ROTATION = 1024 * 4; // this depends on your encoder
const int ENCODER_SAMPLES_PER_SECOND = 10; // this will need to be tuned depending on your use case...
const int LOOP_DELAY_MS = 1 * 1000; // ... as will this (see comments in main code)
void setup() {
Serial.begin(115200);
delay(10);
// Setup Quadrature Encoder
// http://www.atmel.com/Images/doc11057.pdf
// Section 37 p869
// Section 37.6.14 p885
// Section 37.6.14.2 p890 Position and Rotation Measurement
// Section 37.6.14.5 p891 Speed Measurement (what this is about)
REG_PMC_PCER0 = PMC_PCER0_PID27
| PMC_PCER0_PID28
| PMC_PCER0_PID29;
// Setup a channel in waveform mode (eg an input into the encoder to trigger the time based sampling)
// Note some of the choices here impact calculations below and if you change them, you need to change
// the next section to suit.
// Section 37.7.11 p906 (also refer to Section 37.6.14.5 p891 for detail of what to set)
REG_TC0_CMR2 = TC_CMR_TCCLKS_TIMER_CLOCK4
| TC_CMR_WAVE
| TC_CMR_ACPC_TOGGLE
| TC_CMR_WAVSEL_UP_RC;
// Now define the sample period, using the clock chosen above as the basis
// Note that REG_TC0_CMR2 above is using CLOCK4; this is an 128 divisor. You need to change the
// divisor below if you change the clock above. You could change the input clock and the RC mode to
// suit your app (eg how many pulses are you expecting - depends on encoder type
// and slowest/normal/fastest rotation speed and what you want to do with the result).
// Section 37.6.14.5 p891 notes you need to set this up, otherwise 0 comes out all the time :-)
REG_TC0_RC2 = F_CPU / 128 / ENCODER_SAMPLES_PER_SECOND;
// Setup a channel in capture mode
// Section 37.7.10 p904 (also refer to Section 37.6.14.5 p891 for detail of what to set)
REG_TC0_CMR0 = TC_CMR_ABETRG
| TC_CMR_LDRA_EDGE
| TC_CMR_LDRB_EDGE
| TC_CMR_ETRGEDG_EDGE
| TC_CMR_CPCTRG;
// Enable features, noting Speed not Position is chosen
// Section 37.7.2 p895 (also refer to Section 37.6.14.5 p891 for detail of what to set)
REG_TC0_BMR = TC_BMR_QDEN
| TC_BMR_SPEEDEN
| TC_BMR_EDGPHA;
// Set everything going
REG_TC0_CCR0 = TC_CCR_CLKEN | TC_CCR_SWTRG;
REG_TC0_CCR1 = TC_CCR_CLKEN | TC_CCR_SWTRG;
REG_TC0_CCR2 = TC_CCR_CLKEN | TC_CCR_SWTRG;
}
void loop() {
int iIndexCount = REG_TC0_CV1; // Don't need this, but manual notes its available
int iSpeedPPP = REG_TC0_RA0; // This is what we're really after (speed in Pulses Per sample Period)
// which we can convert to rps or rpm easily
double dSpeedRPS = ((iSpeedPPP / (ENCODER_EDGES_PER_ROTATION * 1.0)) * ENCODER_SAMPLES_PER_SECOND);
double dSpeedRPM = dSpeedRPS * 60;
Serial.print("Speed ppp: ");
Serial.print(iSpeedPPP);
Serial.print(", ");
Serial.print("Speed rps: ");
Serial.print(dSpeedRPS);
Serial.print(", ");
Serial.print("Speed rpm: ");
Serial.print(dSpeedRPM);
Serial.print(", ");
Serial.print("Indexes: ");
Serial.print(iIndexCount);
Serial.print(". ");
Serial.println();
// Slow down the main loop noting the Encoder can update independently in the background (we're
// effectively polling it to find out the latest and greatest info on each loop around).
delay(LOOP_DELAY_MS);
}
Example output should look something like
// note 3,500 rpm
Speed ppp: 0, Speed rps: 0.00, Speed rpm: 0.00, Indexes: 0.
Speed ppp: -24351, Speed rps: -59.45, Speed rpm: -3567.04, Indexes: -52.
Speed ppp: -25007, Speed rps: -61.05, Speed rpm: -3663.13, Indexes: -113.
// snip
Speed ppp: -672, Speed rps: -1.64, Speed rpm: -98.44, Indexes: 61.
Speed ppp: -693, Speed rps: -1.69, Speed rpm: -101.51, Indexes: 59.
// snip - note direction change (+ve rpm)
Speed ppp: 1355, Speed rps: 3.31, Speed rpm: 198.49, Indexes: 63.
Speed ppp: 1344, Speed rps: 3.28, Speed rpm: 196.87, Indexes: 66.
Rgnazar:
Using DUE
How do I use 02 encoders?
If possible with the pins too.
I'm a newbie at this. :~ :~ :~
I have a project to manage a telescope with Arduino.
I need to read 4 encoders.
2 encoder are the axes of the telescope (slow). I managed to read using this library (Encoder Library, for Measuring Quadarature Encoded Position or Rotation Signals).
2 encoder on the motor shaft are (fast). I have lost these encoder ticks.
I do not understand almost anything to arduino low level programming.
Please, someone would be possible for a complete example, with the pins to be used ...
Well from what I understand is to use Encoder1A Encoder1B on pin 2 and pin 13.
And the second encoder which pin do I use?
Thanks for any help.
More information: (Pt-Br)
http://www.cosmobrain.com.br/cosmoforum/viewtopic.php?f=32&t=19190&sid=19398e95634d9f04a70536c6536305b0
Designservicecorp:
I have been attempting to use Channel2 as a clock to determine speed and I believe I finally got it.The code below is from the initial program I posted (Reply #32) but with Channel2 enabled and set to TCLK4. I also added more remarks and cleaned it up a bit.
Index interrupts must be enabled for the speed portion to work.
/*
Quadrature Encoder with Marker via hardware
*/
volatile int z_Total=0;
volatile double TPR=0;
void setup() {
Serial.begin(115200);
delay(100);
// Setup Quadrature Encoder
REG_PMC_PCER0 = (1<<27)|(1<<28)|(1<<29); // activate clock for TC0,TC1,TC2
// select XC0 as clock source and set capture mode
REG_TC0_CMR0 = 5;
//Resets the count every index. Rem out the line above,
//and use the line below instead.
//REG_TC0_CMR0 = (1<<0)|(1<<2)|(1<<8)|(1<<10);
REG_TC0_CMR2 = (1<<0)|(1<<1); // Set to TCLK4
// activate quadrature encoder and position measure mode, no filters
REG_TC0_BMR = (1<<8)|(1<<9)|(1<<12);
// Enable the clock (CLKEN=1) and reset the counter (SWTRG=1)
REG_TC0_CCR0 = 5;
REG_TC0_CCR1 = 5;
REG_TC0_CCR2 = 5;
//Remark out these 4 lines to disable Index interrupts
REG_TC0_CMR1 = (1<<8); // Set rising edge of Z
REG_TC0_IER1=0b10000000; // enable interrupt on Z
REG_TC0_IDR1=0b01111111; // disable other interrupts
NVIC_EnableIRQ(TC1_IRQn);
}
void loop() {
//REG_TC0_CV0 Stores count from encoder
Serial.println(REG_TC0_CV0);
//REG_TC0_CV1 Stores count from index if interrupts are off
//if interrupts are on, CV1 will always reset every cycle to zero.
if (REG_TC0_CV1 == 0)
{
Serial.print(z_Total);
Serial.println(" -With Int");
}
else
{
Serial.print(REG_TC0_CV1);
Serial.println(" -No Int");
}
//TPR holds the quantity of ticks every Index. Index interrupts must be on.
//TCLK4 is set so 128 is the divisor.
Serial.print((F_CPU/128/TPR)*60);Serial.println(" RPM");
Serial.println("-------");
delay(500);
}
void TC1_Handler() {
//This won't fire unless the Index interrupt is enabled above
z_Total++;
long dummy=REG_TC0_SR1; // vital - reading this clears some flag
// otherwise you get infinite interrupts
TPR=REG_TC0_CV2; //Store ticks
REG_TC0_CCR2 = 4; //Reset counter
}
Hi, good job here!! I just have a question, the F_CPU variable is already defined? If it is not, what is the value of that parameter?
F_CPU is the Frequency of the CPU.
In this case (DUE) it would equal 84000000 ( or 84MHZ)
Hi Everyone,
My name is Jasonrao and this is my first time posting a comment on Arduino Due forum. This is to acknowledge that I have successfully configured Quadrature encoder (Avago Incremental Quadrature encoder with 500 CPR) by using the hardware Quadrature Encoder on Due. At the moment, I am having some difficulties in configuring another similar encoder on Due. In other words, I am trying to connect 2 quadrature encoders with 4 channels in total. As I know, Due hardware for capture and compare mode can support for only one encoder. By default, PWM Pin 2 and Pin 13 have been reserved for this purpose.
Can anyone help me with the codes to configure my second encoder on Arduino Due?
Many thanks,
Jasonrao