|
Now that my wheel encoders are working correctly (Part 1 and Part 2), I
began working on the firmware to use them in a maze runner. The encoder
generates pulses as the wheel rotates and it's up to your micro-controller to
capture these pulses and do something useful with them, such as driving
straight and making precision turns.
Certain considerations are nessecary to use the encoders properly. If you plan
on feeding the encoders output directly into the micro, try to use I/O pins that
will generate an edge-triggered interrupt and use interrupt service routines to
count the pulses. Another option would be to use the hardware counters that most
microcontrollers have to do the counting and use firmware to clear and read these
counters. In either case the intent is to not miss any pulses while the micro is
busy with other tasks. You could try using software polling routines, where the
micro reads the encoders inputs as part of your program loops, but there's always
a chance some pulses will get missed.
My application uses an Atmel AVR8535 to monitor the encoders, so I used the external
interrupt pins PD2 and PD3. They are programmed to generate an interrupt on a
leading edge change, so every time the encoder signals goes high an interrupt will
be generated to inform the micro of the encoder pulse. Each pin has it's own
interrupt vector with a corresponding interrupt service handler that simply
increments one of the micro's registers that I use as an encoder counter (a variable).
There's one for the left side and one for the right, and the ISR looks like this:
;****************************************************************
; Int0 - Here for interrupts from the left encoder *
;****************************************************************
Int0isr:
in ISRInt0,sreg ;save status register
inc Lencoder ;inc encoder counter
out sreg,ISRInt0 ;restore status register
reti
It's up to the main program loop to monitor the values in these registers and
control what the robot does. The next thing was to work on a 90° turn, so I made
a test routine that would issue 4 right turn commands in a row, so I could see how
well the encoders could control the turns. With 4 turns like that the robot should
spin in a circle and end up exactly where it started, no more, no less. The gearing
between the gear with the reflective strips and the output wheel in my servos is 9
to 1 and with 4 reflective strips I should get 36 pulses for each full rotation of
the wheel, or 9 for each quarter turn. The routine to execute the turn would look
something like the following example:
DoSpinRight(){
ClearEncoders //start with 0 and look for 20
LeftMotorForward
RightMotorBackward //start the spin
while (Lencoder + Rencoder <> 20) ; //the interrupts will inc the counters
//so just loop here till the turn is done
StopMotors
}
The reason I look for a value of 20 is that both encoders are incrementing, and if
each wheel goes a quarter turn or 9 pulses, then the sum of the 2 encoders would be
18. Due to start and stop pulses, and not knowing where the reflective strips are
when the motors actually start, I found that 10 was actually a better value to look
for to get an accurate turn. The routine seemed to work well and the robot turning
to within 5-10 degrees of the starting point. Then the next day I put fresh batteries
in and the turns were way off, with almost an extra 90 degrees added to the completed
circle.
The first thing I tried was to display the values of the encoders as each turn was
executed, by storing the values and sending them to the LCD display, when the test
was completed. The results were typically 10's and 11's for all 4 turns and both
encoders. This told me the encoders were working correctly, but something was
effecting the turns depending on the battery strength.
It finally occurred to me that I wasn't accounting for momentum as the motors started
and stopped. Yes the correct value was reached, and then the stop command issued, but
how much farther did the motor spin after that? I changed my test routines to wait
400ms after the stop command was issued before retrieving the encoder values. Now I
was getting typical values of 15 or 16 and as the batteries got weaker the motors
didn't overshoot so much and I would get values closer to 10.
The only way to fix this was to slow the motors down. Since I was using hacked servos
with the original controller boards, there was no way to directly control their speed.
Ok well actually there was. I had read an article on hacking these very servos (S3003)
to control their speed by varying the PWM signal. Seemed like a good time to try the
hack so I did, and had good success with it and I'll cover this modification in a
future article. Now with the ability to control the motor speed I simply slowed down
the motors on a turn and saw a vast improvement in repeatable turning. Now all my
turns use the encoders and the results have been quite good.
|