Resources » Pololu AVR C/C++ Library User's Guide » 6. Functional Overview and Example programs »6.l. Pololu Wheel Encoder functionsThe PololuWheelEncoders class and the associated C functions provide an easy interface for using the Pololu Wheel Encoders, which allow a robot to know exactly how far its motors have turned at any point in time. Note that this library should work with all standard quadrature encoders, not just the Pololu Wheel Encoders. This section of the library makes uses of pin-change interrupts to quickly detect and record each transition on the encoder. Interrupt vectors for PCINT0, PCINT1, PCINT2 will be defined if functions from this library are used, even if the pins selected are all on a single port, so this section of the library will conflict with any other uses of these interrupts. The interrupt service routine (ISR) will take about 20-30 us. If you need better control of the interrupts used, or you want to write a more efficient ISR, you can copy the library code from PololuWheelEncoders.cpp into your own project and modify it as necessary. Complete documentation of this library’s methods can be found in Section 18 of the Pololu AVR Library Command Reference. Usage NotesThe two sensors A and B on the encoder board go through a four-step cycle as each tooth of the wheel passes by, for a total of 48 counts per revolution. This corresponds to about 3 mm for each count, though you will have to calibrate values for your own robot to get a precise measure of distance. Normally, there will be at least 1 ms between counts, which gives the ISR plenty of time to finish one count before the next one occurs. This is very important, because if two counts occur quickly enough, the ISR will not be able to determine the direction of rotation. In this case, an error can be detected by the functions encoders_check_error_m1() or encoders_check_error_m2(). An error like this either corresponds to a miscalibration of the encoder or a timing issue with the software. For example, if interrupts are disabled for several ms while the wheels are spinning quickly, errors will probably occur. Usage ExamplesThis library comes with one example program in 1. wheel_encoders1
#include <pololu/orangutan.h>
#include <avr/interrupt.h>
int main()
{
encoders_init(16,17,18,19); // the Arduino numbers for ports PC2 - PC5
while(1)
{
lcd_goto_xy(0,0);
print_long(encoders_get_counts_m1());
print(" ");
lcd_goto_xy(4,0);
print_long(encoders_get_counts_m2());
print(" ");
if(encoders_check_error_m1())
{
lcd_goto_xy(0,1);
print("Error 1");
}
if(encoders_check_error_m2())
{
lcd_goto_xy(0,1);
print("Error 2");
}
delay_ms(50);
}
}
|
|
Log In
|
Wish Lists
|
BIG Order Form
|
Shopping Cart
US toll free: 1-877-7-POLOLU ~
(702) 262-6648 |
|||||||||||||
| Catalog | Forum | Resources | Distributors | Ordering | About | Contact | ||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|