Teensy 3.1 Quadrature Encoder Speed with Multiple Encoders

Status
Not open for further replies.

BrianC

Well-known member
Hi all,

I need to be able to control the speeds (exactly) of 3 motors running at 12400rpm or 207 rotations per second. For this, I'm hoping to work with encoders that have 256 counts per revolution. That is, each motor will output 53000 counts per second. That means the teensy will need to read at 53khz for all three motors. In addition to this, I'm hoping to get PID control of each individual motor for it's speed with feedback from the encoders and run the teensy as an SPI slave. Will this be feasable/will it work at a reasonable rate? Will 3 encoder interrupts clash with each other?

thanks,
Brian
 
Can't say much for how 3 copies of the encoder library will interact, but just how tightly are you trying to control these three motors?

My thought would be to use the freqCount library to simplify the process, either through a 1 pulse per rotation sensor or by using one of the quadrature outputs if they are already part of the hardware. This would reduce the complexity of the interrupt process and still allow speed to be measured to 0.4% with a single sensor or 0.003% (depending on design) from the encoder. The encoders will give you direction and absolute position (assuming no missed counts and a known start) but unsure if they are required for your design. One fun part of using the encoder data would be that you could capture the speed changes within a single turn of the motor, which may be quite substantial for some basic DC motor designs.

In any case would expect a Teensy to be quite capable of running three PID loops to within the accuracy of your speed controller hardware (what resolution does it offer?) and system inertia, especially if you are running a fixed 12400 RPM and thus able to tweak your constants carefully for that speed. This is based on 96mhz meaning even if all three encoders trigger together you have ~3600 clock cycles to process the three interrupts before they change again . This is assuming that there will probably be missed counts while the maths happen, but that you are only worrying about speed, not absolute position.

If the aim is to run these motors and then stop them on a fixed rest position from a high speed then things would be far more interesting, and suddenly missed counts and algorithm tuning start to matter a lot more.
 
Thanks. Perhaps I should more clearly say what I'm trying to do.

This year, I've got an 3 wheeled omnidirectional robot that runs ridiculously fast with 14W motors. There were issues with the robot not facing forwards, even with PID control with an IMU. This was contributed from two main factors: wheel slip and non linear speed control (i.e. voltage isn't exactly proportional to speed especially under load). The issue of wheel slip will be eliminated with better wheels and acceleration, whilst ideally the issue with speed control will hopefully be eliminated by having encoder feedback to calculate speed. Hence, for the application, the motor won't be constantly going to 12400rpm but will certainly be changing speeds multiple times in one second. Responsiveness is crucial. As this is omnidirectional control, certain motors may be moving slowly at only a few rpm and hence 1 pulse per rotation may not be enough. The next one up is 256 counts per rotation so it seems like that's the most viable option.

The best option seems like to have a separate decoder chip that does the job of decoding. However, they all seem to be SPI? Since the teensy 3.1 only has one SPI port and it's already being used as a slave, I'll be unable to use SPI. I2C is out of question.
 
Ok, sorry you gave a fair number of clues there as to what you were trying to do but I missed them.

Is an interesting problem since you are trying to create a traction control system that can achieve a user defined path (I assume end point here is sustained performance right on the edge of the mechanically possible?).

Checking around using the usual subjects found Paul's encoder library page
http://www.pjrc.com/teensy/td_libs_Encoder.html
Which while mostly referring to his older boards does state that you can use any combination of T3 pins (all are interrupt capable), that the older Teensy two could cope with >100khz rate on the interrupts, and also gives a sample circuit to test high pulse chain rates.
See also his note on slightly increasing speed by removing dynamic allocation.

So best guess is that you can capture the data, next question would be coding the math to reduce this down and stream it out to the speed control hardware in usable form when the actual rate of computation falls as the number of interrupts increases. Teensy is a capable CPU that works in 32 bit math but doesn't have inbuilt floating point, and this problem may be trending into territory where a hardware floating point may make or break the overall useability of the system. Achieving reliably low latency will be vital to avoid hard to diagnose positive feedback loops that leave all three motors hunting wildly, which while probably fun to watch would be suboptimal. So most likely possible but would require careful thought in integer vs float math through the PID loop.

A hardware specific library that appears to only allow one channel use is:
http://forum.pjrc.com/threads/26803...Code-for-Teensy-3-x?highlight=encoder+library
Unsure if this is of use, but posting there may get you someone who knows more about parseing high speed encoder data. That said a three headed solution might trade cost and size for a more straightforward coding problem by only processing one motor per Teensy.

Hope at least some of the above is helpful.
 
There may be a solution implementing a state machine driven triple decoder.
There is a nice commented lib that explains that on http://www.buxtronix.net/2011/10/rot...-properly.html
This must be placed in in an regular timer driven IRQ.
First I would implement the IRQ and observe if there is no other system inherent IRQ that blocks it for more than 0.5...1µs.
The timer irq must run around 8..16 times the encoder step rate depending on bounce. Thus 0.5MHz rate is a good start. If the state machines run fast enough (basically three switch/case constructs) you may achive a system load under 50% using a 96MHz clock. Normally ~50% of the CPU is more than you need for general tasks, some PID, ...
A nice example for a tight and optimized implementation.
 
Thanks guys. Unfortunately, having more Teensies is not really an option, as the current robot already has 4 Teensy 3.1s, each dedicated to their own specific tasks that actually require quite a lot of processing. There is no more space on the pcb for more. My experience with i2c is that it's actually quite slow, and is limited by the slowest device.

Regarding the state machine driven decoder, are you suggesting to set up timer interrupts (IRQ) at 0.5mhz (for a start) to trigger poles for all 3 encoders? This seems to be a viable option. However, I wonder if the state machine will actually run that fast. Effectively, to leave 50% of time for other tasks (such as PID), at 0.5mhz, the polling would have to finish all within just 1us. This seems like a risky but possible solution.

Perhaps I should first write a program and test using this method and see how fast it runs? This is assuming that polling is the same speed without encoders attached (I haven't bought the motors/encoders yet). I'm still at planning stage.
 
Dear all,

I'm working on a similar project where I need to read out 3 encoders which generate pulse rates of about 50-100 kHz each. I found a very simple, quick and robust algorithm here: http://www.mikrocontroller.net/articles/Drehgeber (german). I adapted the published code (see below) and made a few very promising experiments with it.
For testing in used the following setup:

setup.jpg

The stepper is driven with a constant speed of 1.25 rev/sec so that the attached encoder (40000 pulses/rev) generates a pulse rate of about 50000 pulses per second. The quadrature signal is processed in the simple timer interrupt "isrEncoderRead()" which is called every 10µs (100kHz). I measured the time the ISR takes and got about 400ns for reading one encoder. This time includes two digitalWriteFast() calls required for the time measurement only. It's worth to note that the ISR generates only a small load of 0.4µs/10µs = 4% which is pretty impressive. Extending the ISR to more encoders is straight forward and will add about 300ns for each encoder.

To verify that it counts correctly I run the motor and catch the zero pulse of the encoder in an ISR. If the program sees all 40000 pulses per rev the counter value at the n_th zero pulse should be n x 40000 + some constant. If it misses pulses the value will drift over time. Here the result of the measurement.

result.JPG

And here the used code. Maybe that helps someone.

Best regards
Lutz




Code:
#include "IntervalTimer.h";

IntervalTimer EncoderTimer;
IntervalTimer MotorTimer;

volatile int revolutions=-1;

#define A 1
#define B 0
#define Z 2
#define SCOPE 4
#define MOTOR 5
#define LED 13


void setup()
{
	pinMode(A, INPUT);		// Encoder Phase A
	pinMode(B, INPUT);		// Encoder Phase B
	pinMode(Z, INPUT);		// Encoder Zero
	pinMode(SCOPE, OUTPUT);	// Scope pin
	pinMode(MOTOR, OUTPUT);	// Motor Step
	pinMode(LED, OUTPUT);	// LED

	EncoderTimer.begin(isrEncoderRead, 10);		// 100kHz sampling rate
	attachInterrupt(Z, isrEncoderZero, RISING);            // Encoder zero 
	MotorTimer.begin(isrMotor, 1000);			       // 800 stp/rev, 1 kHz pulserate -> 1.25 revs per second -> 1.25 x 40000 = 50'000 encoder steps per second


	Serial.begin(0);
}



// Encoder Sampling ISR ---------------------------------------
// Original code by   http://www.mikrocontroller.net/articles/Drehgeber

volatile int enc_value;
static int last;

void isrEncoderRead(void)
{
	digitalWriteFast(SCOPE, HIGH);

	int current = 0;
	int diff;
		
	if (digitalReadFast(0))	current = 3;
	if (digitalReadFast(1))	current ^= 1;
	diff = last - current;

	if (diff & 1)
	{
		last = current;					
		enc_value += (diff & 2) - 1; 
	}
	
digitalWriteFast(SCOPE, LOW);
}


// Encoder Zero ISR --------------------------------------------


volatile int zero;

void isrEncoderZero()
{
	zero = enc_value;
	revolutions++;

	digitalWriteFast(13, !digitalReadFast(13)); // toggle LED at each zero pulse
}


void isrMotor()
{
	digitalWriteFast(MOTOR, HIGH);
	delayMicroseconds(1);
	digitalWriteFast(MOTOR, LOW);
}

int lastrev = 0; 

void loop()
{
	if (millis() % 100 == 0 && lastrev != revolutions)
	{
		lastrev = revolutions;
		Serial.printf("Revs: %3d | Zero at: %6d cts | Count: %d cts\n", revolutions, zero-(revolutions*40000), enc_value);
	}
}
}
 
Last edited:
Hi,
Thanks! I believe the thread is now really based here. There are a few others that also are attempting a mix of software and hardware decoding at >=50kHz.

Perhaps this would be of use to them.
Brian
 
Status
Not open for further replies.
Back
Top