001    /*----------------------------------------------------------------------------*/
002    /* Copyright (c) FIRST 2008-2012. All Rights Reserved.                        */
003    /* Open Source Software - may be modified and shared by FRC teams. The code   */
004    /* must be accompanied by the FIRST BSD license file in the root directory of */
005    /* the project.                                                               */
006    /*----------------------------------------------------------------------------*/
007    package edu.wpi.first.wpilibj;
008    
009    import edu.wpi.first.wpilibj.communication.UsageReporting;
010    import edu.wpi.first.wpilibj.fpga.tEncoder;
011    import edu.wpi.first.wpilibj.livewindow.LiveWindow;
012    import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
013    import edu.wpi.first.wpilibj.parsing.ISensor;
014    import edu.wpi.first.wpilibj.tables.ITable;
015    import edu.wpi.first.wpilibj.util.AllocationException;
016    import edu.wpi.first.wpilibj.util.BoundaryException;
017    import edu.wpi.first.wpilibj.util.CheckedAllocationException;
018    
019    /**
020     * Class to read quad encoders.
021     * Quadrature encoders are devices that count shaft rotation and can sense direction. The output of
022     * the QuadEncoder class is an integer that can count either up or down, and can go negative for
023     * reverse direction counting. When creating QuadEncoders, a direction is supplied that changes the
024     * sense of the output to make code more readable if the encoder is mounted such that forward movement
025     * generates negative values. Quadrature encoders have two digital outputs, an A Channel and a B Channel
026     * that are out of phase with each other to allow the FPGA to do direction sensing.
027     */
028    public class Encoder extends SensorBase implements CounterBase, PIDSource, ISensor, LiveWindowSendable {
029    
030        static Resource quadEncoders = new Resource(tEncoder.kNumSystems);
031        /**
032         * The a source
033         */
034        protected DigitalSource m_aSource;          // the A phase of the quad encoder
035        /**
036         * The b source
037         */
038        protected DigitalSource m_bSource;          // the B phase of the quad encoder
039        /**
040         * The index source
041         */
042        protected DigitalSource m_indexSource = null; //Index on some encoders
043        private tEncoder m_encoder;
044        private int m_index;
045        private double m_distancePerPulse;          // distance of travel for each encoder tick
046        private Counter m_counter;                          // Counter object for 1x and 2x encoding
047        private EncodingType m_encodingType = EncodingType.k4X;
048        private boolean m_allocatedA;
049        private boolean m_allocatedB;
050        private boolean m_allocatedI;
051        private PIDSourceParameter m_pidSource;
052    
053        /**
054         * Common initialization code for Encoders.
055         * This code allocates resources for Encoders and is common to all constructors.
056         * @param reverseDirection If true, counts down instead of up (this is all relative)
057         * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
058         * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
059         * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
060         * a counter object will be used and the returned value will either exactly match the spec'd count
061         * or be double (2x) the spec'd count.
062         */
063        private void initEncoder(boolean reverseDirection) {
064            switch (m_encodingType.value) {
065                case EncodingType.k4X_val:
066                    try {
067                        m_index = quadEncoders.allocate();
068                    } catch (CheckedAllocationException e) {
069                        throw new AllocationException("There are no encoders left to allocate");
070                    }
071                    m_encoder = new tEncoder(m_index);
072                    m_encoder.writeConfig_ASource_Module(m_aSource.getModuleForRouting());
073                    m_encoder.writeConfig_ASource_Channel(m_aSource.getChannelForRouting());
074                    m_encoder.writeConfig_ASource_AnalogTrigger(m_aSource.getAnalogTriggerForRouting());
075                    m_encoder.writeConfig_BSource_Module(m_bSource.getModuleForRouting());
076                    m_encoder.writeConfig_BSource_Channel(m_bSource.getChannelForRouting());
077                    m_encoder.writeConfig_BSource_AnalogTrigger(m_bSource.getAnalogTriggerForRouting());
078                    m_encoder.strobeReset();
079                    m_encoder.writeConfig_Reverse(reverseDirection);
080                    m_encoder.writeTimerConfig_AverageSize(1);
081                    if (m_indexSource != null) {
082                        m_encoder.writeConfig_IndexSource_Module(m_indexSource.getModuleForRouting());
083                        m_encoder.writeConfig_IndexSource_Channel(m_indexSource.getChannelForRouting());
084                        m_encoder.writeConfig_IndexSource_AnalogTrigger(m_indexSource.getAnalogTriggerForRouting());
085                        m_encoder.writeConfig_IndexActiveHigh(true);
086                    }
087                    m_counter = null;
088                    break;
089                case EncodingType.k2X_val:
090                case EncodingType.k1X_val:
091                    m_counter = new Counter(m_encodingType, m_aSource, m_bSource, reverseDirection);
092                    break;
093            }
094            m_distancePerPulse = 1.0;
095    
096            UsageReporting.report(UsageReporting.kResourceType_Encoder, m_index, m_encodingType.value);
097            LiveWindow.addSensor("Encoder", m_aSource.getModuleForRouting(), m_aSource.getChannelForRouting(), this);
098        }
099    
100        /**
101         * Encoder constructor.
102         * Construct a Encoder given a and b modules and channels fully specified.
103         * @param aSlot The a channel digital input module.
104         * @param aChannel The a channel digital input channel.
105         * @param bSlot The b channel digital input module.
106         * @param bChannel The b channel digital input channel.
107         * @param reverseDirection represents the orientation of the encoder and inverts the output values
108         * if necessary so forward represents positive values.
109         */
110        public Encoder(final int aSlot, final int aChannel,
111                final int bSlot, final int bChannel,
112                boolean reverseDirection) {
113            m_allocatedA = true;
114            m_allocatedB = true;
115            m_allocatedI = false;
116            m_aSource = new DigitalInput(aSlot, aChannel);
117            m_bSource = new DigitalInput(bSlot, bChannel);
118            initEncoder(reverseDirection);
119        }
120    
121        /**
122         * Encoder constructor.
123         * Construct a Encoder given a and b modules and channels fully specified.
124         * @param aSlot The a channel digital input module.
125         * @param aChannel The a channel digital input channel.
126         * @param bSlot The b channel digital input module.
127         * @param bChannel The b channel digital input channel.
128         */
129        public Encoder(final int aSlot, final int aChannel,
130                final int bSlot, final int bChannel) {
131            this(aSlot, aChannel, bSlot, bChannel, false);
132        }
133    
134        /**
135         * Encoder constructor.
136         * Construct a Encoder given a and b modules and channels fully specified.
137         * @param aSlot The a channel digital input module.
138         * @param aChannel The a channel digital input channel.
139         * @param bSlot The b channel digital input module.
140         * @param bChannel The b channel digital input channel.
141         * @param reverseDirection represents the orientation of the encoder and inverts the output values
142         * if necessary so forward represents positive values.
143         * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
144         * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
145         * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
146         * a counter object will be used and the returned value will either exactly match the spec'd count
147         * or be double (2x) the spec'd count.
148         */
149        public Encoder(final int aSlot, final int aChannel,
150                final int bSlot, final int bChannel,
151                boolean reverseDirection, final EncodingType encodingType) {
152            m_allocatedA = true;
153            m_allocatedB = true;
154            m_allocatedI = false;
155            m_aSource = new DigitalInput(aSlot, aChannel);
156            m_bSource = new DigitalInput(bSlot, bChannel);
157            if (encodingType == null)
158                throw new NullPointerException("Given encoding type was null");
159            m_encodingType = encodingType;
160            initEncoder(reverseDirection);
161        }
162    
163        /**
164         * Encoder constructor.
165         * Construct a Encoder given a and b modules and channels fully specified.
166         * Using the index pulse forces 4x encoding.
167         * @param aSlot The a channel digital input module.
168         * @param aChannel The a channel digital input channel.
169         * @param bSlot The b channel digital input module.
170         * @param bChannel The b channel digital input channel.
171         * @param indexSlot The index channel digital input module.
172         * @param indexChannel The index channel digital input channel.
173         * @param reverseDirection represents the orientation of the encoder and inverts the output values
174         * if necessary so forward represents positive values.
175         */
176        public Encoder(final int aSlot, final int aChannel,
177                final int bSlot, final int bChannel, final int indexSlot,
178                final int indexChannel,
179                boolean reverseDirection) {
180            m_allocatedA = true;
181            m_allocatedB = true;
182            m_allocatedI = true;
183            m_aSource = new DigitalInput(aSlot, aChannel);
184            m_bSource = new DigitalInput(bSlot, bChannel);
185            m_indexSource = new DigitalInput(indexSlot, indexChannel);
186            initEncoder(reverseDirection);
187        }
188    
189        /**
190         * Encoder constructor.
191         * Construct a Encoder given a and b modules and channels fully specified.
192         * Using the index pulse forces 4x encoding.
193         * @param aSlot The a channel digital input module.
194         * @param aChannel The a channel digital input channel.
195         * @param bSlot The b channel digital input module.
196         * @param bChannel The b channel digital input channel.
197         * @param indexSlot The index channel digital input module.
198         * @param indexChannel The index channel digital input channel.
199         */
200        public Encoder(final int aSlot, final int aChannel,
201                final int bSlot, final int bChannel, final int indexSlot,
202                final int indexChannel) {
203            this(aSlot, aChannel, bSlot, bChannel, indexSlot, indexChannel, false);
204        }
205    
206        /**
207         * Encoder constructor.
208         * Construct a Encoder given a and b channels assuming the default module.
209         * @param aChannel The a channel digital input channel.
210         * @param bChannel The b channel digital input channel.
211         * @param reverseDirection represents the orientation of the encoder and inverts the output values
212         * if necessary so forward represents positive values.
213         */
214        public Encoder(final int aChannel, final int bChannel, boolean reverseDirection) {
215            m_allocatedA = true;
216            m_allocatedB = true;
217            m_allocatedI = false;
218            m_aSource = new DigitalInput(aChannel);
219            m_bSource = new DigitalInput(bChannel);
220            initEncoder(reverseDirection);
221        }
222    
223        /**
224         * Encoder constructor.
225         * Construct a Encoder given a and b channels assuming the default module.
226         * @param aChannel The a channel digital input channel.
227         * @param bChannel The b channel digital input channel.
228         */
229        public Encoder(final int aChannel, final int bChannel) {
230            this(aChannel, bChannel, false);
231        }
232    
233        /**
234         * Encoder constructor.
235         * Construct a Encoder given a and b channels assuming the default module.
236         * @param aChannel The a channel digital input channel.
237         * @param bChannel The b channel digital input channel.
238         * @param reverseDirection represents the orientation of the encoder and inverts the output values
239         * if necessary so forward represents positive values.
240         * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
241         * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
242         * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
243         * a counter object will be used and the returned value will either exactly match the spec'd count
244         * or be double (2x) the spec'd count.
245         */
246        public Encoder(final int aChannel, final int bChannel, boolean reverseDirection, final EncodingType encodingType) {
247            m_allocatedA = true;
248            m_allocatedB = true;
249            m_allocatedI = false;
250            if (encodingType == null)
251                throw new NullPointerException("Given encoding type was null");
252            m_encodingType = encodingType;
253            m_aSource = new DigitalInput(aChannel);
254            m_bSource = new DigitalInput(bChannel);
255            initEncoder(reverseDirection);
256        }
257    
258        /**
259         * Encoder constructor.
260         * Construct a Encoder given a and b channels assuming the default module.
261         * Using an index pulse forces 4x encoding
262         * @param aChannel The a channel digital input channel.
263         * @param bChannel The b channel digital input channel.
264         * @param indexChannel The index channel digital input channel.
265         * @param reverseDirection represents the orientation of the encoder and inverts the output values
266         * if necessary so forward represents positive values.
267         */
268        public Encoder(final int aChannel, final int bChannel, final int indexChannel, boolean reverseDirection) {
269            m_allocatedA = true;
270            m_allocatedB = true;
271            m_allocatedI = true;
272            m_aSource = new DigitalInput(aChannel);
273            m_bSource = new DigitalInput(bChannel);
274            m_indexSource = new DigitalInput(indexChannel);
275            initEncoder(reverseDirection);
276        }
277    
278        /**
279         * Encoder constructor.
280         * Construct a Encoder given a and b channels assuming the default module.
281         * Using an index pulse forces 4x encoding
282         * @param aChannel The a channel digital input channel.
283         * @param bChannel The b channel digital input channel.
284         * @param indexChannel The index channel digital input channel.
285         */
286        public Encoder(final int aChannel, final int bChannel, final int indexChannel) {
287            this(aChannel, bChannel, indexChannel, false);
288        }
289    
290        /**
291         * Encoder constructor.
292         * Construct a Encoder given a and b channels as digital inputs. This is used in the case
293         * where the digital inputs are shared. The Encoder class will not allocate the digital inputs
294         * and assume that they already are counted.
295         * @param aSource The source that should be used for the a channel.
296         * @param bSource the source that should be used for the b channel.
297         * @param reverseDirection represents the orientation of the encoder and inverts the output values
298         * if necessary so forward represents positive values.
299         */
300        public Encoder(DigitalSource aSource, DigitalSource bSource, boolean reverseDirection) {
301            m_allocatedA = false;
302            m_allocatedB = false;
303            m_allocatedI = false;
304            if (aSource == null)
305                throw new NullPointerException("Digital Source A was null");
306            m_aSource = aSource;
307            if (bSource == null)
308                throw new NullPointerException("Digital Source B was null");
309            m_bSource = bSource;
310            initEncoder(reverseDirection);
311        }
312    
313        /**
314         * Encoder constructor.
315         * Construct a Encoder given a and b channels as digital inputs. This is used in the case
316         * where the digital inputs are shared. The Encoder class will not allocate the digital inputs
317         * and assume that they already are counted.
318         * @param aSource The source that should be used for the a channel.
319         * @param bSource the source that should be used for the b channel.
320         */
321        public Encoder(DigitalSource aSource, DigitalSource bSource) {
322            this(aSource, bSource, false);
323        }
324    
325        /**
326         * Encoder constructor.
327         * Construct a Encoder given a and b channels as digital inputs. This is used in the case
328         * where the digital inputs are shared. The Encoder class will not allocate the digital inputs
329         * and assume that they already are counted.
330         * @param aSource The source that should be used for the a channel.
331         * @param bSource the source that should be used for the b channel.
332         * @param reverseDirection represents the orientation of the encoder and inverts the output values
333         * if necessary so forward represents positive values.
334         * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
335         * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
336         * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
337         * a counter object will be used and the returned value will either exactly match the spec'd count
338         * or be double (2x) the spec'd count.
339         */
340        public Encoder(DigitalSource aSource, DigitalSource bSource, boolean reverseDirection, final EncodingType encodingType) {
341            m_allocatedA = false;
342            m_allocatedB = false;
343            m_allocatedI = false;
344            if (encodingType == null)
345                throw new NullPointerException("Given encoding type was null");
346            m_encodingType = encodingType;
347            if (aSource == null)
348                throw new NullPointerException("Digital Source A was null");
349            m_aSource = aSource;
350            if (bSource == null)
351                throw new NullPointerException("Digital Source B was null");
352            m_aSource = aSource;
353            m_bSource = bSource;
354            initEncoder(reverseDirection);
355        }
356    
357        /**
358         * Encoder constructor.
359         * Construct a Encoder given a and b channels as digital inputs. This is used in the case
360         * where the digital inputs are shared. The Encoder class will not allocate the digital inputs
361         * and assume that they already are counted.
362         * @param aSource The source that should be used for the a channel.
363         * @param bSource the source that should be used for the b channel.
364         * @param indexSource the source that should be used for the index channel.
365         * @param reverseDirection represents the orientation of the encoder and inverts the output values
366         * if necessary so forward represents positive values.
367         */
368        public Encoder(DigitalSource aSource, DigitalSource bSource,
369                DigitalSource indexSource, boolean reverseDirection) {
370            m_allocatedA = false;
371            m_allocatedB = false;
372            m_allocatedI = false;
373            if (aSource == null)
374                throw new NullPointerException("Digital Source A was null");
375            m_aSource = aSource;
376            if (bSource == null)
377                throw new NullPointerException("Digital Source B was null");
378            m_aSource = aSource;
379            m_bSource = bSource;
380            m_indexSource = indexSource;
381            initEncoder(reverseDirection);
382        }
383    
384        /**
385         * Encoder constructor.
386         * Construct a Encoder given a and b channels as digital inputs. This is used in the case
387         * where the digital inputs are shared. The Encoder class will not allocate the digital inputs
388         * and assume that they already are counted.
389         * @param aSource The source that should be used for the a channel.
390         * @param bSource the source that should be used for the b channel.
391         * @param indexSource the source that should be used for the index channel.
392         */
393        public Encoder(DigitalSource aSource, DigitalSource bSource,
394                DigitalSource indexSource) {
395            this(aSource, bSource, indexSource, false);
396        }
397    
398        public void free() {
399            if (m_aSource != null && m_allocatedA) {
400                m_aSource.free();
401                m_allocatedA = false;
402            }
403            if (m_bSource != null && m_allocatedB) {
404                m_bSource.free();
405                m_allocatedB = false;
406            }
407            if (m_indexSource != null && m_allocatedI) {
408                m_indexSource.free();
409                m_allocatedI = false;
410            }
411    
412            m_aSource = null;
413            m_bSource = null;
414            m_indexSource = null;
415            if (m_counter != null) {
416                m_counter.free();
417                m_counter = null;
418            } else {
419                m_encoder.Release();
420                quadEncoders.free(m_index);
421                m_encoder = null;
422            }
423        }
424    
425        /**
426         * Start the Encoder.
427         * Starts counting pulses on the Encoder device.
428         */
429        public void start() {
430            if (m_counter != null) {
431                m_counter.start();
432            } else {
433                m_encoder.writeConfig_Enable(true);
434            }
435        }
436    
437        /**
438         * Stops counting pulses on the Encoder device. The value is not changed.
439         */
440        public void stop() {
441            if (m_counter != null) {
442                m_counter.stop();
443            } else {
444                m_encoder.writeConfig_Enable(false);
445            }
446        }
447    
448        /**
449         * Gets the raw value from the encoder.
450         * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
451         * factor.
452         * @return Current raw count from the encoder
453         */
454        public int getRaw() {
455            int value;
456            if (m_counter != null) {
457                value = m_counter.get();
458            } else {
459                value = m_encoder.readOutput_Value();
460            }
461            return value;
462        }
463    
464        /**
465         * Gets the current count.
466         * Returns the current count on the Encoder.
467         * This method compensates for the decoding type.
468         *
469         * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale factor.
470         */
471        public int get() {
472            return (int) (getRaw() * decodingScaleFactor());
473        }
474    
475        /**
476         * Reset the Encoder distance to zero.
477         * Resets the current count to zero on the encoder.
478         */
479        public void reset() {
480            if (m_counter != null) {
481                m_counter.reset();
482            } else {
483                m_encoder.strobeReset();
484            }
485        }
486    
487        /**
488         * Returns the period of the most recent pulse.
489         * Returns the period of the most recent Encoder pulse in seconds.
490         * This method compensates for the decoding type.
491         *
492         * @deprecated Use getRate() in favor of this method.  This returns unscaled periods and getRate() scales using value from setDistancePerPulse().
493         *
494         * @return Period in seconds of the most recent pulse.
495         */
496        public double getPeriod() {
497            double measuredPeriod;
498            if (m_counter != null) {
499                measuredPeriod = m_counter.getPeriod();
500            } else {
501                double value;
502                if (m_encoder.readTimerOutput_Stalled()) {
503                    return Double.POSITIVE_INFINITY;
504                } else {
505                    // output.Period is a fixed point number that counts by 2 (24 bits, 25 integer bits),
506                    // but tEncoder.readTimerOutput_Period() handles integer shift already
507                    value = (double)m_encoder.readTimerOutput_Period() / (double) m_encoder.readTimerOutput_Count();
508                }
509                measuredPeriod = value * 1.0e-6;
510            }
511            return measuredPeriod / decodingScaleFactor();
512        }
513    
514        /**
515         * Sets the maximum period for stopped detection.
516         * Sets the value that represents the maximum period of the Encoder before it will assume
517         * that the attached device is stopped. This timeout allows users to determine if the wheels or
518         * other shaft has stopped rotating.
519         * This method compensates for the decoding type.
520         *
521         *
522         * @param maxPeriod The maximum time between rising and falling edges before the FPGA will
523         * report the device stopped. This is expressed in seconds.
524         */
525        public void setMaxPeriod(double maxPeriod) {
526            if (m_counter != null) {
527                m_counter.setMaxPeriod(maxPeriod * decodingScaleFactor());
528            } else {
529                m_encoder.writeTimerConfig_StallPeriod((int) (maxPeriod * 1.0e6 * decodingScaleFactor()));
530            }
531        }
532    
533        /**
534         * Determine if the encoder is stopped.
535         * Using the MaxPeriod value, a boolean is returned that is true if the encoder is considered
536         * stopped and false if it is still moving. A stopped encoder is one where the most recent pulse
537         * width exceeds the MaxPeriod.
538         * @return True if the encoder is considered stopped.
539         */
540        public boolean getStopped() {
541            if (m_counter != null) {
542                return m_counter.getStopped();
543            } else {
544                boolean value = m_encoder.readTimerOutput_Stalled() != false;
545                return value;
546            }
547        }
548    
549        /**
550         * The last direction the encoder value changed.
551         * @return The last direction the encoder value changed.
552         */
553        public boolean getDirection() {
554            if (m_counter != null) {
555                return m_counter.getDirection();
556            } else {
557                boolean value = m_encoder.readOutput_Direction();
558                return value;
559            }
560        }
561    
562        /**
563         * The scale needed to convert a raw counter value into a number of encoder pulses.
564         */
565        private double decodingScaleFactor() {
566            switch (m_encodingType.value) {
567                case EncodingType.k1X_val:
568                    return 1.0;
569                case EncodingType.k2X_val:
570                    return 0.5;
571                case EncodingType.k4X_val:
572                    return 0.25;
573                default:
574                    //This is never reached, EncodingType enum limits values
575                    return 0.0;
576            }
577        }
578    
579        /**
580         * Get the distance the robot has driven since the last reset.
581         *
582         * @return The distance driven since the last reset as scaled by the value from setDistancePerPulse().
583         */
584        public double getDistance() {
585            return getRaw() * decodingScaleFactor() * m_distancePerPulse;
586        }
587    
588        /**
589         * Get the current rate of the encoder.
590         * Units are distance per second as scaled by the value from setDistancePerPulse().
591         *
592         * @return The current rate of the encoder.
593         */
594        public double getRate() {
595            return m_distancePerPulse / getPeriod();
596        }
597    
598        /**
599         * Set the minimum rate of the device before the hardware reports it stopped.
600         *
601         * @param minRate The minimum rate.  The units are in distance per second as scaled by the value from setDistancePerPulse().
602         */
603        public void setMinRate(double minRate) {
604            setMaxPeriod(m_distancePerPulse / minRate);
605        }
606    
607        /**
608         * Set the distance per pulse for this encoder.
609         * This sets the multiplier used to determine the distance driven based on the count value
610         * from the encoder.
611         * Do not include the decoding type in this scale.  The library already compensates for the decoding type.
612         * Set this value based on the encoder's rated Pulses per Revolution and
613         * factor in gearing reductions following the encoder shaft.
614         * This distance can be in any units you like, linear or angular.
615         *
616         * @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
617         */
618        public void setDistancePerPulse(double distancePerPulse) {
619            m_distancePerPulse = distancePerPulse;
620        }
621    
622        /**
623         * Set the direction sensing for this encoder.
624         * This sets the direction sensing on the encoder so that it could count in the correct
625         * software direction regardless of the mounting.
626         * @param reverseDirection true if the encoder direction should be reversed
627         */
628        public void setReverseDirection(boolean reverseDirection) {
629            if (m_counter != null) {
630                m_counter.setReverseDirection(reverseDirection);
631            } else {
632                m_encoder.writeConfig_Reverse(reverseDirection);
633            }
634        }
635        
636        /**
637         * Set the Samples to Average which specifies the number of samples of the timer to 
638         * average when calculating the period. Perform averaging to account for 
639         * mechanical imperfections or as oversampling to increase resolution.
640         * @param samplesToAverage The number of samples to average from 1 to 127.
641         */
642        public void setSamplesToAverage(int samplesToAverage)
643        {
644            BoundaryException.assertWithinBounds(samplesToAverage, 1, 127);
645            switch (m_encodingType.value) {
646                case EncodingType.k4X_val:
647                    m_encoder.writeTimerConfig_AverageSize(samplesToAverage);
648                    break;
649                case EncodingType.k1X_val:
650                case EncodingType.k2X_val:
651                    m_counter.setSamplesToAverage(samplesToAverage);
652            }
653        }
654        
655        /**
656         * Get the Samples to Average which specifies the number of samples of the timer to 
657         * average when calculating the period. Perform averaging to account for 
658         * mechanical imperfections or as oversampling to increase resolution.
659         * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
660         */
661        public int getSamplesToAverage()
662        {
663            switch (m_encodingType.value) {
664                case EncodingType.k4X_val:
665                    return m_encoder.readTimerConfig_AverageSize();
666                case EncodingType.k1X_val:
667                case EncodingType.k2X_val:
668                    return m_counter.getSamplesToAverage();
669            }
670            return 1;
671        }
672    
673        /**
674         * Set which parameter of the encoder you are using as a process control variable.
675         * The encoder class supports the rate and distance parameters.
676         * @param pidSource An enum to select the parameter.
677         */
678        public void setPIDSourceParameter(PIDSourceParameter pidSource) {
679            BoundaryException.assertWithinBounds(pidSource.value, 0, 1);
680            m_pidSource = pidSource;
681        }
682    
683        /**
684         * Implement the PIDSource interface.
685         *
686         * @return The current value of the selected source parameter.
687         */
688        public double pidGet() {
689            switch (m_pidSource.value) {
690            case PIDSourceParameter.kDistance_val:
691                return getDistance();
692            case PIDSourceParameter.kRate_val:
693                return getRate();
694            default:
695                return 0.0;
696            }
697        }
698    
699        /*
700         * Live Window code, only does anything if live window is activated.
701         */
702        public String getSmartDashboardType(){
703            switch(m_encodingType.value)
704            {
705                case EncodingType.k4X_val:
706                    return "Quadrature Encoder";
707                default:
708                    return "Encoder";
709            }
710        }
711        private ITable m_table;
712        
713        /**
714         * {@inheritDoc}
715         */
716        public void initTable(ITable subtable) {
717            m_table = subtable;
718            updateTable();
719        }
720        
721        /**
722         * {@inheritDoc}
723         */
724        public ITable getTable(){
725            return m_table;
726        }
727        
728        /**
729         * {@inheritDoc}
730         */
731        public void updateTable() {
732            if (m_table != null) {
733                m_table.putNumber("Speed", getRate());
734                m_table.putNumber("Distance", getDistance());
735                m_table.putNumber("Distance per Tick", m_distancePerPulse);
736            }
737        }
738    
739        /**
740         * {@inheritDoc}
741         */
742        public void startLiveWindowMode() {}
743        
744        /**
745         * {@inheritDoc}
746         */
747        public void stopLiveWindowMode() {}
748    }