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/*----------------------------------------------------------------------------*/
007package edu.wpi.first.wpilibj;
008
009import java.nio.ByteOrder;
010import java.nio.IntBuffer;
011import java.nio.LongBuffer;
012import java.nio.ByteBuffer;
013
014//import com.sun.jna.Pointer;
015
016
017import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
018import edu.wpi.first.wpilibj.communication.UsageReporting;
019import edu.wpi.first.wpilibj.hal.AnalogJNI;
020import edu.wpi.first.wpilibj.hal.HALUtil;
021import edu.wpi.first.wpilibj.livewindow.LiveWindow;
022import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
023import edu.wpi.first.wpilibj.tables.ITable;
024import edu.wpi.first.wpilibj.util.AllocationException;
025import edu.wpi.first.wpilibj.util.CheckedAllocationException;
026
027/**
028 * Analog channel class.
029 *
030 * Each analog channel is read from hardware as a 12-bit number representing
031 * 0V to 5V.
032 *
033 * Connected to each analog channel is an averaging and oversampling engine.
034 * This engine accumulates the specified ( by setAverageBits() and
035 * setOversampleBits() ) number of samples before returning a new value. This is
036 * not a sliding window average. The only difference between the oversampled
037 * samples and the averaged samples is that the oversampled samples are simply
038 * accumulated effectively increasing the resolution, while the averaged samples
039 * are divided by the number of samples to retain the resolution, but get more
040 * stable values.
041 */
042public class AnalogInput extends SensorBase implements PIDSource,
043                LiveWindowSendable {
044
045        private static final int kAccumulatorSlot = 1;
046        private static Resource channels = new Resource(kAnalogInputChannels);
047        private ByteBuffer m_port;
048        private int m_channel;
049        private static final int[] kAccumulatorChannels = { 0, 1 };
050        private long m_accumulatorOffset;
051
052        /**
053         * Construct an analog channel.
054         *
055         * @param channel The channel number to represent. 0-3 are on-board 4-7 are on the MXP port.
056         */
057        public AnalogInput(final int channel) {
058                m_channel = channel;
059
060                if (AnalogJNI.checkAnalogInputChannel(channel) == 0) {
061                        throw new AllocationException("Analog input channel " + m_channel
062                                        + " cannot be allocated. Channel is not present.");
063                }
064                try {
065                        channels.allocate(channel);
066                } catch (CheckedAllocationException e) {
067                        throw new AllocationException("Analog input channel " + m_channel
068                                         + " is already allocated");
069                }
070
071                ByteBuffer port_pointer = AnalogJNI.getPort((byte) channel);
072                ByteBuffer status = ByteBuffer.allocateDirect(4);
073                // set the byte order
074                status.order(ByteOrder.LITTLE_ENDIAN);
075                m_port = AnalogJNI.initializeAnalogInputPort(port_pointer, status.asIntBuffer());
076                HALUtil.checkStatus(status.asIntBuffer());
077
078                LiveWindow.addSensor("AnalogInput", channel, this);
079                UsageReporting.report(tResourceType.kResourceType_AnalogChannel, channel);
080        }
081
082        /**
083         * Channel destructor.
084         */
085        public void free() {
086                channels.free(m_channel);
087                m_channel = 0;
088                m_accumulatorOffset = 0;
089        }
090
091        /**
092         * Get a sample straight from this channel. The sample is a 12-bit value
093         * representing the 0V to 5V range of the A/D converter. The units are in
094         * A/D converter codes. Use GetVoltage() to get the analog value in
095         * calibrated units.
096         *
097         * @return A sample straight from this channel.
098         */
099        public int getValue() {
100                ByteBuffer status = ByteBuffer.allocateDirect(4);
101                // set the byte order
102                status.order(ByteOrder.LITTLE_ENDIAN);
103                int value = AnalogJNI.getAnalogValue(m_port, status.asIntBuffer());
104                HALUtil.checkStatus(status.asIntBuffer());
105                return value;
106        }
107
108        /**
109         * Get a sample from the output of the oversample and average engine for
110         * this channel. The sample is 12-bit + the bits configured in
111         * SetOversampleBits(). The value configured in setAverageBits() will cause
112         * this value to be averaged 2^bits number of samples. This is not a
113         * sliding window. The sample will not change until 2^(OversampleBits +
114         * AverageBits) samples have been acquired from this channel. Use
115         * getAverageVoltage() to get the analog value in calibrated units.
116         *
117         * @return A sample from the oversample and average engine for this channel.
118         */
119        public int getAverageValue() {
120                ByteBuffer status = ByteBuffer.allocateDirect(4);
121                // set the byte order
122                status.order(ByteOrder.LITTLE_ENDIAN);
123                int value = AnalogJNI.getAnalogAverageValue(m_port, status.asIntBuffer());
124                HALUtil.checkStatus(status.asIntBuffer());
125                return value;
126        }
127
128        /**
129         * Get a scaled sample straight from this channel. The value is scaled to
130         * units of Volts using the calibrated scaling data from getLSBWeight() and
131         * getOffset().
132         *
133         * @return A scaled sample straight from this channel.
134         */
135        public double getVoltage() {
136                ByteBuffer status = ByteBuffer.allocateDirect(4);
137                // set the byte order
138                status.order(ByteOrder.LITTLE_ENDIAN);
139                double value = AnalogJNI.getAnalogVoltage(m_port, status.asIntBuffer());
140                HALUtil.checkStatus(status.asIntBuffer());
141                return value;
142        }
143
144        /**
145         * Get a scaled sample from the output of the oversample and average engine
146         * for this channel. The value is scaled to units of Volts using the
147         * calibrated scaling data from getLSBWeight() and getOffset(). Using
148         * oversampling will cause this value to be higher resolution, but it will
149         * update more slowly. Using averaging will cause this value to be more
150         * stable, but it will update more slowly.
151         *
152         * @return A scaled sample from the output of the oversample and average
153         *               engine for this channel.
154         */
155        public double getAverageVoltage() {
156                ByteBuffer status = ByteBuffer.allocateDirect(4);
157                // set the byte order
158                status.order(ByteOrder.LITTLE_ENDIAN);
159                double value = AnalogJNI.getAnalogAverageVoltage(m_port, status.asIntBuffer());
160                HALUtil.checkStatus(status.asIntBuffer());
161                return value;
162        }
163
164        /**
165         * Get the factory scaling least significant bit weight constant. The least
166         * significant bit weight constant for the channel that was calibrated in
167         * manufacturing and stored in an eeprom.
168         *
169         * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
170         *
171         * @return Least significant bit weight.
172         */
173        public long getLSBWeight() {
174                ByteBuffer status = ByteBuffer.allocateDirect(4);
175                // set the byte order
176                status.order(ByteOrder.LITTLE_ENDIAN);
177                long value = AnalogJNI.getAnalogLSBWeight(m_port, status.asIntBuffer());
178                HALUtil.checkStatus(status.asIntBuffer());
179                return value;
180        }
181
182        /**
183         * Get the factory scaling offset constant. The offset constant for the
184         * channel that was calibrated in manufacturing and stored in an eeprom.
185         *
186         * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
187         *
188         * @return Offset constant.
189         */
190        public int getOffset() {
191                ByteBuffer status = ByteBuffer.allocateDirect(4);
192                // set the byte order
193                status.order(ByteOrder.LITTLE_ENDIAN);
194                int value = AnalogJNI.getAnalogOffset(m_port, status.asIntBuffer());
195                HALUtil.checkStatus(status.asIntBuffer());
196                return value;
197        }
198
199        /**
200         * Get the channel number.
201         *
202         * @return The channel number.
203         */
204        public int getChannel() {
205                return m_channel;
206        }
207
208        /**
209         * Set the number of averaging bits. This sets the number of averaging bits.
210         * The actual number of averaged samples is 2^bits. The averaging is done
211         * automatically in the FPGA.
212         *
213         * @param bits
214         *                      The number of averaging bits.
215         */
216        public void setAverageBits(final int bits) {
217                ByteBuffer status = ByteBuffer.allocateDirect(4);
218                // set the byte order
219                status.order(ByteOrder.LITTLE_ENDIAN);
220                AnalogJNI.setAnalogAverageBits(m_port, bits, status.asIntBuffer());
221                HALUtil.checkStatus(status.asIntBuffer());
222        }
223
224        /**
225         * Get the number of averaging bits. This gets the number of averaging bits
226         * from the FPGA. The actual number of averaged samples is 2^bits. The
227         * averaging is done automatically in the FPGA.
228         *
229         * @return The number of averaging bits.
230         */
231        public int getAverageBits() {
232                ByteBuffer status = ByteBuffer.allocateDirect(4);
233                // set the byte order
234                status.order(ByteOrder.LITTLE_ENDIAN);
235                int value = AnalogJNI.getAnalogAverageBits(m_port, status.asIntBuffer());
236                HALUtil.checkStatus(status.asIntBuffer());
237                return value;
238        }
239
240        /**
241         * Set the number of oversample bits. This sets the number of oversample
242         * bits. The actual number of oversampled values is 2^bits. The
243         * oversampling is done automatically in the FPGA.
244         *
245         * @param bits
246         *                      The number of oversample bits.
247         */
248        public void setOversampleBits(final int bits) {
249                ByteBuffer status = ByteBuffer.allocateDirect(4);
250                // set the byte order
251                status.order(ByteOrder.LITTLE_ENDIAN);
252                AnalogJNI.setAnalogOversampleBits(m_port, bits, status.asIntBuffer());
253                HALUtil.checkStatus(status.asIntBuffer());
254        }
255
256        /**
257         * Get the number of oversample bits. This gets the number of oversample
258         * bits from the FPGA. The actual number of oversampled values is 2^bits.
259         * The oversampling is done automatically in the FPGA.
260         *
261         * @return The number of oversample bits.
262         */
263        public int getOversampleBits() {
264                ByteBuffer status = ByteBuffer.allocateDirect(4);
265                // set the byte order
266                status.order(ByteOrder.LITTLE_ENDIAN);
267                int value = AnalogJNI.getAnalogOversampleBits(m_port, status.asIntBuffer());
268                HALUtil.checkStatus(status.asIntBuffer());
269                return value;
270        }
271
272        /**
273         * Initialize the accumulator.
274         */
275        public void initAccumulator() {
276                if (!isAccumulatorChannel()) {
277                        throw new AllocationException(
278                                        "Accumulators are only available on slot "
279                                                        + kAccumulatorSlot + " on channels "
280                                                        + kAccumulatorChannels[0] + ","
281                                                        + kAccumulatorChannels[1]);
282                }
283                m_accumulatorOffset = 0;
284                ByteBuffer status = ByteBuffer.allocateDirect(4);
285                // set the byte order
286                status.order(ByteOrder.LITTLE_ENDIAN);
287                AnalogJNI.initAccumulator(m_port, status.asIntBuffer());
288                HALUtil.checkStatus(status.asIntBuffer());
289        }
290
291        /**
292         * Set an initial value for the accumulator.
293         *
294         * This will be added to all values returned to the user.
295         *
296         * @param initialValue
297         *                      The value that the accumulator should start from when reset.
298         */
299        public void setAccumulatorInitialValue(long initialValue) {
300                m_accumulatorOffset = initialValue;
301        }
302
303        /**
304         * Resets the accumulator to the initial value.
305         */
306        public void resetAccumulator() {
307                ByteBuffer status = ByteBuffer.allocateDirect(4);
308                // set the byte order
309                status.order(ByteOrder.LITTLE_ENDIAN);
310                AnalogJNI.resetAccumulator(m_port, status.asIntBuffer());
311                HALUtil.checkStatus(status.asIntBuffer());
312
313                // Wait until the next sample, so the next call to getAccumulator*()
314                // won't have old values.
315                final double sampleTime = 1.0 / getGlobalSampleRate();
316                final double overSamples = 1 << getOversampleBits();
317                final double averageSamples = 1 << getAverageBits();
318                Timer.delay(sampleTime * overSamples * averageSamples);
319
320        }
321
322        /**
323         * Set the center value of the accumulator.
324         *
325         * The center value is subtracted from each A/D value before it is added to
326         * the accumulator. This is used for the center value of devices like gyros
327         * and accelerometers to take the device offset
328         * into account when integrating.
329         *
330         * This center value is based on the output of the oversampled and averaged
331         * source the accumulator channel. Because of this, any non-zero oversample bits will
332         * affect the size of the value for this field.
333         */
334        public void setAccumulatorCenter(int center) {
335                ByteBuffer status = ByteBuffer.allocateDirect(4);
336                // set the byte order
337                status.order(ByteOrder.LITTLE_ENDIAN);
338                AnalogJNI.setAccumulatorCenter(m_port, center, status.asIntBuffer());
339                HALUtil.checkStatus(status.asIntBuffer());
340        }
341
342        /**
343         * Set the accumulator's deadband.
344         * @param deadband The deadband size in ADC codes (12-bit value)
345         */
346        public void setAccumulatorDeadband(int deadband) {
347                ByteBuffer status = ByteBuffer.allocateDirect(4);
348                // set the byte order
349                status.order(ByteOrder.LITTLE_ENDIAN);
350                AnalogJNI.setAccumulatorDeadband(m_port, deadband, status.asIntBuffer());
351                HALUtil.checkStatus(status.asIntBuffer());
352        }
353
354        /**
355         * Read the accumulated value.
356         *
357         * Read the value that has been accumulating. The accumulator
358         * is attached after the oversample and average engine.
359         *
360         * @return The 64-bit value accumulated since the last Reset().
361         */
362        public long getAccumulatorValue() {
363                ByteBuffer status = ByteBuffer.allocateDirect(4);
364                // set the byte order
365                status.order(ByteOrder.LITTLE_ENDIAN);
366                long value = AnalogJNI.getAccumulatorValue(m_port, status.asIntBuffer());
367                HALUtil.checkStatus(status.asIntBuffer());
368                return value + m_accumulatorOffset;
369        }
370
371        /**
372         * Read the number of accumulated values.
373         *
374         * Read the count of the accumulated values since the accumulator was last
375         * Reset().
376         *
377         * @return The number of times samples from the channel were accumulated.
378         */
379        public long getAccumulatorCount() {
380                ByteBuffer status = ByteBuffer.allocateDirect(4);
381                // set the byte order
382                status.order(ByteOrder.LITTLE_ENDIAN);
383                long value = AnalogJNI.getAccumulatorCount(m_port, status.asIntBuffer());
384                HALUtil.checkStatus(status.asIntBuffer());
385                return value;
386        }
387
388        /**
389         * Read the accumulated value and the number of accumulated values
390         * atomically.
391         *
392         * This function reads the value and count from the FPGA atomically. This
393         * can be used for averaging.
394         *
395         * @param result
396         *                      AccumulatorResult object to store the results in.
397         */
398        public void getAccumulatorOutput(AccumulatorResult result) {
399                if (result == null) {
400                        throw new IllegalArgumentException("Null parameter `result'");
401                }
402                if (!isAccumulatorChannel()) {
403                        throw new IllegalArgumentException("Channel " + m_channel
404                                        + " is not an accumulator channel.");
405                }
406                ByteBuffer value = ByteBuffer.allocateDirect(8);
407                // set the byte order
408                value.order(ByteOrder.LITTLE_ENDIAN);
409                ByteBuffer count = ByteBuffer.allocateDirect(4);
410                // set the byte order
411                count.order(ByteOrder.LITTLE_ENDIAN);
412                ByteBuffer status = ByteBuffer.allocateDirect(4);
413                // set the byte order
414                status.order(ByteOrder.LITTLE_ENDIAN);
415                AnalogJNI.getAccumulatorOutput(m_port, value.asLongBuffer(), count.asIntBuffer(), status.asIntBuffer());
416                result.value = value.asLongBuffer().get(0) + m_accumulatorOffset;
417                result.count = count.asIntBuffer().get(0);
418                HALUtil.checkStatus(status.asIntBuffer());
419        }
420
421        /**
422         * Is the channel attached to an accumulator.
423         *
424         * @return The analog channel is attached to an accumulator.
425         */
426        public boolean isAccumulatorChannel() {
427                for (int i = 0; i < kAccumulatorChannels.length; i++) {
428                        if (m_channel == kAccumulatorChannels[i]) {
429                                return true;
430                        }
431                }
432                return false;
433        }
434
435        /**
436         * Set the sample rate per channel.
437         *
438         * This is a global setting for all channels.
439         * The maximum rate is 500kS/s divided by the number of channels in use.
440         * This is 62500 samples/s per channel if all 8 channels are used.
441         * @param samplesPerSecond The number of samples per second.
442         */
443        public static void setGlobalSampleRate(final double samplesPerSecond) {
444                ByteBuffer status = ByteBuffer.allocateDirect(4);
445                status.order(ByteOrder.LITTLE_ENDIAN);
446
447                AnalogJNI.setAnalogSampleRate((float)samplesPerSecond, status.asIntBuffer());
448
449                HALUtil.checkStatus(status.asIntBuffer());
450        }
451
452        /**
453         * Get the current sample rate.
454         *
455         * This assumes one entry in the scan list. This is a global setting for
456         * all channels.
457         *
458         * @return Sample rate.
459         */
460        public static double getGlobalSampleRate() {
461                ByteBuffer status = ByteBuffer.allocateDirect(4);
462                status.order(ByteOrder.LITTLE_ENDIAN);
463
464                double value = AnalogJNI.getAnalogSampleRate(status.asIntBuffer());
465
466                HALUtil.checkStatus(status.asIntBuffer());
467
468                return value;
469        }
470
471        /**
472         * Get the average voltage for use with PIDController
473         *
474         * @return the average voltage
475         */
476        public double pidGet() {
477                return getAverageVoltage();
478        }
479
480        /**
481         * Live Window code, only does anything if live window is activated.
482         */
483        public String getSmartDashboardType() {
484                return "Analog Input";
485        }
486
487        private ITable m_table;
488
489        /**
490         * {@inheritDoc}
491         */
492        public void initTable(ITable subtable) {
493                m_table = subtable;
494                updateTable();
495        }
496
497        /**
498         * {@inheritDoc}
499         */
500        public void updateTable() {
501                if (m_table != null) {
502                        m_table.putNumber("Value", getAverageVoltage());
503                }
504        }
505
506        /**
507         * {@inheritDoc}
508         */
509        public ITable getTable() {
510                return m_table;
511        }
512
513        /**
514         * Analog Channels don't have to do anything special when entering the
515         * LiveWindow. {@inheritDoc}
516         */
517        public void startLiveWindowMode() {
518        }
519
520        /**
521         * Analog Channels don't have to do anything special when exiting the
522         * LiveWindow. {@inheritDoc}
523         */
524        public void stopLiveWindowMode() {
525        }
526}