Go to the documentation of this file.
15 void setupEncoder(uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin);
40 #define WHEEL_DIR_FORWARD 1
45 #define WHEEL_DIR_BACKWARD 0
uint32_t getEncoderLeftCnt()
Return number of encoder ticks from the left wheel.
uint8_t getLeftWheelDir()
Determines if the left wheel is going forward or backwards.
uint8_t getRightWheelDir()
Determines if the right wheel is going forward or backwards.
void setupEncoder(uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin)
Initialize the wheel encoder.
void resetRightEncoderCnt()
Set the right encoder tick count to 0.
uint32_t getEncoderRightCnt()
Return number of encoder ticks from the right wheel.
void resetLeftEncoderCnt()
Set the left encoder tick count to 0.