TI RSLK Library 0.2.2
Loading...
Searching...
No Matches
Encoder.cpp
1#include <stdlib.h>
2#include "Energia.h"
3#include "Encoder.h"
4
5/* Variables used in the ISR should be volatile */
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;
10
11/* Pins used by the encoder */
12uint8_t _era_pin;
13uint8_t _erb_pin;
14uint8_t _ela_pin;
15uint8_t _elb_pin;
16
17void triggerLeftEncoder()
18{
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
25void triggerRightEncoder()
26{
27 enc_right_cnt++;
28
29 /* The wheel direction can be determined by the second encoder pin */
30 enc_right_wheel_dir = digitalRead(_era_pin);
31}
32
33void setupEncoder(uint8_t ela_pin, uint8_t elb_pin, uint8_t era_pin, uint8_t erb_pin)
34{
35 _era_pin = era_pin;
36 _erb_pin = erb_pin;
37 _ela_pin = ela_pin;
38 _elb_pin = elb_pin;
39
40 /* Encoder drives pins high during pulse so by default they should be pulled low */
41 pinMode(_ela_pin, INPUT_PULLDOWN);
42 pinMode(_elb_pin, INPUT_PULLDOWN);
43 pinMode(_era_pin, INPUT_PULLDOWN);
44 pinMode(_erb_pin, INPUT_PULLDOWN);
45
46 /* Only count the rising edge of the encoder */
47 attachInterrupt(digitalPinToInterrupt(erb_pin), triggerRightEncoder, RISING);
48 attachInterrupt(digitalPinToInterrupt(elb_pin), triggerLeftEncoder, RISING);
49}
50
52{
53 return enc_right_cnt;
54}
55
57{
58 return enc_left_cnt;
59}
60
62{
63 enc_left_cnt = 0;
64}
65
67{
68 enc_right_cnt = 0;
69}
70
72{
73 return enc_left_wheel_dir;
74}
76{
77 return enc_right_wheel_dir;
78}
uint8_t getLeftWheelDir()
Determines if the left wheel is going forward or backwards.
Definition Encoder.cpp:71
uint8_t getRightWheelDir()
Determines if the right wheel is going forward or backwards.
Definition Encoder.cpp:75
void resetRightEncoderCnt()
Set the right encoder tick count to 0.
Definition Encoder.cpp:66
void resetLeftEncoderCnt()
Set the left encoder tick count to 0.
Definition Encoder.cpp:61
uint32_t getEncoderLeftCnt()
Return number of encoder ticks from the left wheel.
Definition Encoder.cpp:56
uint32_t getEncoderRightCnt()
Return number of encoder ticks from the right wheel.
Definition Encoder.cpp:51