WPILib 2012
WPILibRoboticsLibraryforFRC
Encoder.h
00001 /*----------------------------------------------------------------------------*/
00002 /* Copyright (c) FIRST 2008. All Rights Reserved.                                                         */
00003 /* Open Source Software - may be modified and shared by FRC teams. The code   */
00004 /* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
00005 /*----------------------------------------------------------------------------*/
00006 
00007 #ifndef QUAD_ENCODER_H_
00008 #define QUAD_ENCODER_H_
00009 
00010 #include "ChipObject.h"
00011 #include "CounterBase.h"
00012 #include "SensorBase.h"
00013 #include "Counter.h"
00014 #include "PIDSource.h"
00015 
00016 class DigitalSource;
00017 
00027 class Encoder: public SensorBase, public CounterBase, public PIDSource
00028 {
00029 public:
00030         typedef enum {kDistance, kRate} PIDSourceParameter;
00031 
00032         Encoder(UINT32 aChannel, UINT32 bChannel, bool reverseDirection=false, EncodingType encodingType = k4X);
00033         Encoder(UINT8 aModuleNumber, UINT32 aChannel, UINT8 bModuleNumber, UINT32 _bChannel, bool reverseDirection=false, EncodingType encodingType = k4X);
00034         Encoder(DigitalSource *aSource, DigitalSource *bSource, bool reverseDirection=false, EncodingType encodingType = k4X);
00035         Encoder(DigitalSource &aSource, DigitalSource &bSource, bool reverseDirection=false, EncodingType encodingType = k4X);
00036         virtual ~Encoder();
00037 
00038         // CounterBase interface
00039         void Start();
00040         INT32 Get();
00041         INT32 GetRaw();
00042         void Reset();
00043         void Stop();
00044         double GetPeriod();
00045         void SetMaxPeriod(double maxPeriod);
00046         bool GetStopped();
00047         bool GetDirection();
00048         double GetDistance();
00049         double GetRate();
00050         void SetMinRate(double minRate);
00051         void SetDistancePerPulse(double distancePerPulse);
00052         void SetReverseDirection(bool reverseDirection);
00053 
00054         void SetPIDSourceParameter(PIDSourceParameter pidSource);
00055         double PIDGet();
00056 
00057 private:
00058         void InitEncoder(bool _reverseDirection, EncodingType encodingType);
00059         double DecodingScaleFactor();
00060 
00061         DigitalSource *m_aSource;               // the A phase of the quad encoder
00062         DigitalSource *m_bSource;               // the B phase of the quad encoder
00063         bool m_allocatedASource;                // was the A source allocated locally?
00064         bool m_allocatedBSource;                // was the B source allocated locally?
00065         tEncoder* m_encoder;
00066         UINT8 m_index;
00067         double m_distancePerPulse;              // distance of travel for each encoder tick
00068         Counter *m_counter;                             // Counter object for 1x and 2x encoding
00069         EncodingType m_encodingType;    // Encoding type
00070         PIDSourceParameter m_pidSource;// Encoder parameter that sources a PID controller
00071 };
00072 
00073 #endif
00074 
 All Classes Functions Variables