TI RSLK Library  0.2.0
Encoder.h
Go to the documentation of this file.
1 
2 #include <stdint.h>
3 
4 #ifndef Encoder_h
5 #define Encoder_h
6 
15 void setupEncoder(uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin);
16 
21 uint32_t getEncoderLeftCnt();
22 
27 uint32_t getEncoderRightCnt();
28 
31 void resetLeftEncoderCnt();
32 
36 
40 #define WHEEL_DIR_FORWARD 1
41 
45 #define WHEEL_DIR_BACKWARD 0
46 
51 uint8_t getLeftWheelDir();
52 
57 uint8_t getRightWheelDir();
58 
59 #endif
getEncoderLeftCnt
uint32_t getEncoderLeftCnt()
Return number of encoder ticks from the left wheel.
Definition: Encoder.cpp:53
getLeftWheelDir
uint8_t getLeftWheelDir()
Determines if the left wheel is going forward or backwards.
Definition: Encoder.cpp:65
getRightWheelDir
uint8_t getRightWheelDir()
Determines if the right wheel is going forward or backwards.
Definition: Encoder.cpp:68
setupEncoder
void setupEncoder(uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin)
Initialize the wheel encoder.
Definition: Encoder.cpp:32
resetRightEncoderCnt
void resetRightEncoderCnt()
Set the right encoder tick count to 0.
Definition: Encoder.cpp:61
getEncoderRightCnt
uint32_t getEncoderRightCnt()
Return number of encoder ticks from the right wheel.
Definition: Encoder.cpp:49
resetLeftEncoderCnt
void resetLeftEncoderCnt()
Set the left encoder tick count to 0.
Definition: Encoder.cpp:57