TI RSLK Library  0.2.0
Encoder.cpp
1 #include <stdlib.h>
2 #include "Energia.h"
3 #include "Encoder.h"
4 
5 /* Variables used in the ISR should be volatile */
6 volatile uint32_t enc_left_cnt = 0;
7 volatile uint32_t enc_right_cnt = 0;
8 volatile uint8_t enc_left_wheel_dir = 0;
9 volatile uint8_t enc_right_wheel_dir = 0;
10 
11 /* Pins used by the encoder */
12 uint8_t _era_pin;
13 uint8_t _erb_pin;
14 uint8_t _ela_pin;
15 uint8_t _elb_pin;
16 
17 
18 void triggerLeftEncoder() {
19  enc_left_cnt++;
20 
21  /* The wheel direction can be determined by the second encoder pin */
22  enc_left_wheel_dir = digitalRead(_ela_pin);
23 }
24 
25 void triggerRightEncoder() {
26  enc_right_cnt++;
27 
28  /* The wheel direction can be determined by the second encoder pin */
29  enc_right_wheel_dir = digitalRead(_era_pin);
30 }
31 
32 void setupEncoder(uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin) {
33  _era_pin = era_pin;
34  _erb_pin = erb_pin;
35  _ela_pin = ela_pin;
36  _elb_pin = elb_pin;
37 
38  /* Encoder drives pins high during pulse so by default they should be pulled low */
39  pinMode(_ela_pin, INPUT_PULLDOWN );
40  pinMode(_elb_pin, INPUT_PULLDOWN );
41  pinMode(_era_pin, INPUT_PULLDOWN );
42  pinMode(_erb_pin, INPUT_PULLDOWN );
43 
44  /* Only count the rising edge of the encoder */
45  attachInterrupt(digitalPinToInterrupt(erb_pin),triggerRightEncoder,RISING);
46  attachInterrupt(digitalPinToInterrupt(elb_pin),triggerLeftEncoder,RISING);
47 }
48 
49 uint32_t getEncoderRightCnt() {
50  return enc_right_cnt;
51 }
52 
53 uint32_t getEncoderLeftCnt() {
54  return enc_left_cnt;
55 }
56 
58  enc_left_cnt = 0;
59 }
60 
62  enc_right_cnt = 0;
63 }
64 
65 uint8_t getLeftWheelDir() {
66  return enc_left_wheel_dir;
67 }
68 uint8_t getRightWheelDir() {
69  return enc_right_wheel_dir;
70 }
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
Encoder.h