Krishna Kaushal Panduru / QuadratureEncoder
Revision:
0:6b30097d9a45
Child:
1:52fba054be6c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/quadratureEncoder.cpp	Fri Jul 22 13:03:39 2011 +0000
@@ -0,0 +1,131 @@
+/*
+name:                encoder.h
+date:                04-june-2011
+header description:  contains functions and external variables to interface quadrature encoder
+compiler-library:    the mbed library interface is used on the whole..
+compatability:       can also be compatable with generalised code with diffrerent hardware and software
+hardware dependency: works on rover 5 model platform interfaced with mbed controller
+
+indentation:         <mbed default intendation - 4 spaces>
+resources:          http://www.sparkfun.com/products/10336
+                    http://letsmakerobots.com/node/24031
+                    http://www.sparkfun.com/datasheets/Robotics/Rover%205%20Introduction.pdf
+            */
+#include "mbed.h"
+#include "quadratureEncoder.h"
+//gets a bit position by shifting 1
+#define Abit   0
+#define Bbit   1
+
+#define _BV(x) (1 << x)
+
+// sbi sets a particular bit and cbi clears the bit (target byte-word, bit position)
+#define sbi(y,x) y|=_BV(x)
+#define cbi(y,x) y&=~_BV(x)
+
+quadratureEncoder::quadratureEncoder(PinName pinA, PinName pinB):
+_pinA(pinA), _pinB(pinB){
+    _pinA.rise(this, &quadratureEncoder::ARise);
+    _pinA.fall(this, &quadratureEncoder::AFall);
+    _pinB.rise(this, &quadratureEncoder::BRise);
+    _pinB.fall(this, &quadratureEncoder::BFall);
+    
+    _oldState = 0x00;
+    _nowState = 0x00;
+    _moved = 0;
+    _count = 0;
+}
+
+////////////////////////////////////////////////////////////////////////////////////////
+int quadratureEncoder::getCount() {
+    int outp = _count;
+    _count = 0;
+    return outp;
+}
+
+void quadratureEncoder::resetCount() {
+    _count = 0;
+}
+
+void quadratureEncoder::setCount(int setCounter) {
+    _count = setCounter;
+}
+
+
+
+////////////////////////////////////////////////////////////////////////////////////////
+void quadratureEncoder::resetMoved() {
+    _moved = 0;
+}
+
+void quadratureEncoder::setMoved(int setMover) {
+    _moved = setMover;
+}
+
+int quadratureEncoder::getMoved() {
+    return _moved;
+}
+
+////////////////////////////////////////////////////////////////////////////////////////
+char quadratureEncoder::saveState(char nowS) {
+    return nowS;
+}
+
+char quadratureEncoder::getBit(char bitP, char targB) {
+    targB = targB & _BV(bitP);
+    if (targB == 0)
+        return 0;
+    else
+        return 1;
+}
+
+
+/*
+function:   the following 8 functions are ISR called by rise and fall of 4 pins
+input:      none (interupt called)
+output:     none
+functioning:interrupts are called when the pin change occours
+            sets or clears the respective bit
+            checks the previous state and increments respective direction
+            restores new state value into old state
+            increments a count value for processing    */
+void quadratureEncoder::ARise() {
+    sbi(_nowState,Abit);
+    if (getBit(Bbit,_oldState)==0 && getBit(Abit,_oldState)==0)
+        _moved++;
+    else if (getBit(Bbit,_oldState)==0 && getBit(Abit,_oldState)==1)
+        _moved--;
+    _oldState = saveState(_nowState);
+    _count++;
+}
+
+void quadratureEncoder::AFall() {
+    cbi(_nowState, Abit);
+    if (getBit(Bbit,_oldState)==1 && getBit(Abit,_oldState)==1)
+        _moved++;
+    else if (getBit(Bbit,_oldState)==1 && getBit(Abit,_oldState)==0)
+        _moved--;
+    _oldState = saveState(_nowState);
+    _count++;
+}
+
+void quadratureEncoder::BRise() {
+    sbi(_nowState,Bbit);
+    if (getBit(Bbit,_oldState)==1 && getBit(Abit,_oldState)==0)
+        _moved++;
+    else if (getBit(Bbit,_oldState)==0 && getBit(Abit,_oldState)==0)
+        _moved--;
+    _oldState = saveState(_nowState);
+    _count++;
+}
+
+void quadratureEncoder::BFall() {
+    cbi(_nowState, Bbit);
+    if (getBit(Bbit,_oldState)==0 && getBit(Abit,_oldState)==1)
+        _moved++;
+    else if (getBit(Bbit,_oldState)==1 && getBit(Abit,_oldState)==1)
+        _moved--;
+    _oldState = saveState(_nowState);
+    _count++;
+}
+