-
Notifications
You must be signed in to change notification settings - Fork 19
/
Encoder.cpp
106 lines (93 loc) · 2.79 KB
/
Encoder.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
/*
****************************************************************************
* Copyright (c) 2015 Dark Guan <[email protected]> *
* This file is part of Ananas. *
* *
* Ananas is free software: you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation, either version 3 of the License, or *
* (at your option) any later version. *
* *
* Ananas is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with Ananas. If not, see <http://www.gnu.org/licenses/>. *
****************************************************************************
*/
/*
* Encoder.cpp
*
* Created on: 2015年12月14日
* Author: Dark
*/
#include "arduino.h"
#include "Ananas.h"
//encoder use interrupt
long encodercount;
volatile bool stateA;
volatile bool stateB;
bool inverseCountDir;
uint8_t increment;
void counter1_C();
void counter2_C();
void initialEncoder() {
//set all the pins
pinMode(ENCODER_A, INPUT);
pinMode(ENCODER_A, INPUT);
//use the pull-up resistor
digitalWrite(ENCODER_A, HIGH);
digitalWrite(ENCODER_B, HIGH);
//CHANGE
attachInterrupt(0, counter1_C, CHANGE); //为A 相添加中断
attachInterrupt(1, counter2_C, CHANGE); //为B 相添加中断
encodercount = 0;
//TODO add EEPROM settings
inverseCountDir = INV_COUNT_DIR;
if (inverseCountDir) {
increment = 1;
} else {
increment = -1;
}
}
//change the count dir
void changeDir() {
inverseCountDir = !inverseCountDir;
if (inverseCountDir) {
increment = 1;
} else {
increment = -1;
}
}
//CHNANGE
void counter1_C() {
noInterrupts();
stateA = digitalRead(ENCODER_A);
stateB = digitalRead(ENCODER_B);
if (stateA ^ stateB) //state is not same then
{
encodercount += increment;
} else {
encodercount -= increment;
}
interrupts();
}
void counter2_C() {
noInterrupts();
stateA = digitalRead(ENCODER_A);
stateB = digitalRead(ENCODER_B);
if (!(stateA ^ stateB)) {
encodercount += increment;
} else {
encodercount -= increment;
}
interrupts();
}
float getPosition() {
return float(encodercount / float(ENCODER_COUNTS_PER_UNIT));
}
long getEncodercount() {
return encodercount;
}