6volatile uint32_t enc_left_cnt = 0;
7volatile uint32_t enc_right_cnt = 0;
8volatile uint8_t enc_left_wheel_dir = 0;
9volatile uint8_t enc_right_wheel_dir = 0;
17void triggerLeftEncoder()
22 enc_left_wheel_dir = digitalRead(_ela_pin);
25void triggerRightEncoder()
30 enc_right_wheel_dir = digitalRead(_era_pin);
33void setupEncoder(uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin)
41 pinMode(_ela_pin, INPUT_PULLDOWN);
42 pinMode(_elb_pin, INPUT_PULLDOWN);
43 pinMode(_era_pin, INPUT_PULLDOWN);
44 pinMode(_erb_pin, INPUT_PULLDOWN);
47 attachInterrupt(digitalPinToInterrupt(erb_pin), triggerRightEncoder, RISING);
48 attachInterrupt(digitalPinToInterrupt(elb_pin), triggerLeftEncoder, RISING);
73 return enc_left_wheel_dir;
77 return enc_right_wheel_dir;
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 resetRightEncoderCnt()
Set the right encoder tick count to 0.
void resetLeftEncoderCnt()
Set the left encoder tick count to 0.
uint32_t getEncoderLeftCnt()
Return number of encoder ticks from the left wheel.
uint32_t getEncoderRightCnt()
Return number of encoder ticks from the right wheel.