001/*
002 *  Software License Agreement
003 *
004 * Copyright (C) Cross The Road Electronics.  All rights
005 * reserved.
006 *
007 * Cross The Road Electronics (CTRE) licenses to you the right to
008 * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software
009 * API Libraries ONLY when in use with Cross The Road Electronics hardware products.
010 *
011 * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
012 * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT
013 * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A
014 * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL
015 * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL,
016 * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF
017 * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS
018 * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE
019 * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER
020 * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT
021 * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE
022 */
023package com.ctre.phoenix.sensors;
024import com.ctre.phoenix.ErrorCode;
025import com.ctre.phoenix.ErrorCollection;
026import com.ctre.phoenix.ParamEnum;
027import com.ctre.phoenix.sensors.CANCoderConfigUtil;
028
029/**
030 * CTRE CANCoder.
031 *
032 * <pre>
033 * {@code
034 * // Example usage of a CANCoder
035 * CANCoder cancoder = new CANCoder(0); // creates a new CANCoder with ID 0
036 *
037 * CANCoderConfiguration config = new CANCoderConfiguration();
038 * // set units of the CANCoder to radians, with velocity being radians per second
039 * config.sensorCoefficient = 2 * Math.PI / 4096.0;
040 * config.unitString = "rad";
041 * config.sensorTimeBase = SensorTimeBase.PerSecond;
042 * cancoder.configAllSettings(config);
043 *
044 * System.out.println(cancoder.getPosition()); // prints the position of the CANCoder
045 * System.out.println(cancoder.getVelocity()); // prints the velocity recorded by the CANCoder
046 *
047 * ErrorCode error = cancoder.getLastError(); // gets the last error generated by the CANCoder
048 * CANCoderFaults faults = new CANCoderFaults();
049 * ErrorCode faultsError = cancoder.getFaults(faults); // fills faults with the current CANCoder faults; returns the last error generated
050 *
051 * cancoder.setStatusFramePeriod(CANCoderStatusFrame.SensorData, 10); // changes the period of the sensor data frame to 10ms
052 * }
053 * </pre>
054 */
055public class CANCoder{
056    private long m_handle;
057    private CANCoderSimCollection m_simCollection;
058
059    private int m_deviceNumber;
060
061    /**
062     * Constructor.
063     * @param deviceNumber      The CAN Device ID of the CANCoder.
064         * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux),
065         *               or a CANivore device name or serial number
066     */
067    public CANCoder(int deviceNumber, String canbus) {
068        m_handle = CANCoderJNI.Create(deviceNumber, canbus);
069        m_deviceNumber = deviceNumber;
070        m_simCollection = new CANCoderSimCollection(this);
071    }
072
073    /**
074     * Constructor.
075     * @param deviceNumber      The CAN Device ID of the CANCoder.
076     */
077    public CANCoder(int deviceNumber){
078                this(deviceNumber, "");
079    }
080
081    public ErrorCode DestroyObject() {
082        return ErrorCode.valueOf(CANCoderJNI.Destroy(m_handle));
083    }
084
085    public int getDeviceID() {
086        return m_deviceNumber;
087    }
088
089    /**
090     * @return object that can set simulation inputs.
091     */
092    public CANCoderSimCollection getSimCollection() { return m_simCollection; }
093
094    /**
095     * Gets the position of the sensor.  This may be relative or absolute depending on configuration.
096     * The units are determined by the coefficient and unit-string configuration params, default is degrees.
097     * @return The position of the sensor.
098     */
099    public double getPosition() {
100        return CANCoderJNI.GetPosition(m_handle);
101    }
102    /**
103     * Sets the position of the sensor.
104     * The units are determined by the coefficient and unit-string configuration params, default is degrees.
105     * @param newPosition
106     * @return ErrorCode generated by function. 0 indicates no error.
107     */
108    public ErrorCode setPosition(double newPosition, int timeoutMs) {
109        return ErrorCode.valueOf(CANCoderJNI.SetPosition(m_handle, newPosition, timeoutMs));
110    }
111    /**
112     * Sets the position of the sensor.
113     * The units are determined by the coefficient and unit-string configuration params, default is degrees.
114     * @param newPosition
115     * @return ErrorCode generated by function. 0 indicates no error.
116     */
117    public ErrorCode setPosition(double newPosition) {
118        int timeoutMs = 0;
119        return ErrorCode.valueOf(CANCoderJNI.SetPosition(m_handle, newPosition, timeoutMs));
120    }
121    /**
122     * Sets the position of the sensor to match the magnet's "Absolute Sensor".
123     * The units are determined by the coefficient and unit-string configuration params, default is degrees.
124     * @return ErrorCode generated by function. 0 indicates no error.
125     */
126    public ErrorCode setPositionToAbsolute(int timeoutMs) {
127        return ErrorCode.valueOf(CANCoderJNI.SetPositionToAbsolute(m_handle, timeoutMs));
128    }
129    /**
130     * Sets the position of the sensor to match the magnet's "Absolute Sensor".
131     * The units are determined by the coefficient and unit-string configuration params, default is degrees.
132     * @return ErrorCode generated by function. 0 indicates no error.
133     */
134    public ErrorCode setPositionToAbsolute() {
135        int timeoutMs = 0;
136        return ErrorCode.valueOf(CANCoderJNI.SetPositionToAbsolute(m_handle, timeoutMs));
137    }
138    /**
139     * Gets the velocity of the sensor.
140     * The units are determined by the coefficient and unit-string configuration params, default is degrees per second.
141     * @return The Velocity of the sensor.
142     */
143    public double getVelocity() {
144        return CANCoderJNI.GetVelocity(m_handle);
145    }
146    /**
147     * Gets the absolute position of the sensor.
148     * The absolute position may be unsigned (for example: [0,360) deg), or signed (for example: [-180,+180) deg).  This is determined by a configuration.  The default selection is unsigned.
149     * The units are determined by the coefficient and unit-string configuration params, default is degrees.
150     * Note: this signal is not affected by calls to SetPosition().
151     * @return The position of the sensor.
152     */
153    public double getAbsolutePosition() {
154        return CANCoderJNI.GetAbsolutePosition(m_handle);
155    }
156    /**
157     * Configures the period of each velocity sample.
158     * Every 1ms a position value is sampled, and the delta between that sample
159     * and the position sampled kPeriod ms ago is inserted into a filter.
160     * kPeriod is configured with this function.
161     *
162     * @param period
163     *            Desired period for the velocity measurement.
164     * @param timeoutMs
165     *            Timeout value in ms. If nonzero, function will wait for
166     *            config success and report an error if it times out.
167     *            If zero, no blocking or checking is performed.
168     * @return Error Code generated by function. 0 indicates no error.
169     */
170    public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs) {
171        return ErrorCode.valueOf(CANCoderJNI.ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs));
172    }
173    /**
174     * Configures the period of each velocity sample.
175     * Every 1ms a position value is sampled, and the delta between that sample
176     * and the position sampled kPeriod ms ago is inserted into a filter.
177     * kPeriod is configured with this function.
178     *
179     * @param period
180     *            Desired period for the velocity measurement.
181     * @return Error Code generated by function. 0 indicates no error.
182     */
183    public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period) {
184        int timeoutMs = 0;
185        return configVelocityMeasurementPeriod(period, timeoutMs);
186    }
187    /**
188     * Sets the number of velocity samples used in the rolling average velocity
189     * measurement.
190     *
191     * @param windowSize
192     *            Number of samples in the rolling average of velocity
193     *            measurement. Valid values are 1,2,4,8,16,32. If another
194     *            value is specified, it will truncate to nearest support value.
195     * @param timeoutMs
196     *            Timeout value in ms. If nonzero, function will wait for
197     *            config success and report an error if it times out.
198     *            If zero, no blocking or checking is performed.
199     * @return Error Code generated by function. 0 indicates no error.
200     */
201    public ErrorCode configVelocityMeasurementWindow(int windowSize, int timeoutMs) {
202        return ErrorCode.valueOf(CANCoderJNI.ConfigVelocityMeasurementWindow(m_handle, windowSize, timeoutMs));
203    }
204    /**
205     * Sets the number of velocity samples used in the rolling average velocity
206     * measurement.
207     *
208     * @param windowSize
209     *            Number of samples in the rolling average of velocity
210     *            measurement. Valid values are 1,2,4,8,16,32. If another
211     *            value is specified, it will truncate to nearest support value.
212     * @return Error Code generated by function. 0 indicates no error.
213     */
214    public ErrorCode configVelocityMeasurementWindow(int windowSize) {
215        int timeoutMs = 0;
216        return configVelocityMeasurementWindow(windowSize, timeoutMs);
217    }
218    /**
219     * Sets the signage and range of the "Absolute Position" signal.
220     * Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc...
221     * Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc...
222     * @param absoluteSensorRange
223     *            Desired Sign/Range for the absolute position register.
224     * @param timeoutMs
225     *            Timeout value in ms. If nonzero, function will wait for
226     *            config success and report an error if it times out.
227     *            If zero, no blocking or checking is performed.
228     * @return Error Code generated by function. 0 indicates no error.
229     */
230    public ErrorCode configAbsoluteSensorRange(AbsoluteSensorRange absoluteSensorRange, int timeoutMs)
231    {
232        return ErrorCode.valueOf(CANCoderJNI.ConfigAbsoluteSensorRange(m_handle, absoluteSensorRange.value, timeoutMs));
233    }
234    /**
235     * Sets the signage and range of the "Absolute Position" signal.
236     * Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc...
237     * Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc...
238     * @param absoluteSensorRange
239     *            Desired Sign/Range for the absolute position register.
240     * @return Error Code generated by function. 0 indicates no error.
241     */
242    public ErrorCode configAbsoluteSensorRange(AbsoluteSensorRange absoluteSensorRange)
243    {
244        int timeoutMs = 0;
245        return configAbsoluteSensorRange(absoluteSensorRange, timeoutMs);
246    }
247    /**
248     * Adjusts the zero point for the absolute position register.
249     * The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180)
250     * and a hard-limited mechanism may have such a discontinuity in its functional range.
251     * In which case use this config to move the discontinuity outside of the function range.
252     * @param offsetDegrees
253     *            Offset in degrees (unit string and coefficient DO NOT apply for this config).
254     * @param timeoutMs
255     *            Timeout value in ms. If nonzero, function will wait for
256     *            config success and report an error if it times out.
257     *            If zero, no blocking or checking is performed.
258     * @return Error Code generated by function. 0 indicates no error.
259     */
260    public ErrorCode configMagnetOffset(double offsetDegrees, int timeoutMs)
261    {
262        return ErrorCode.valueOf(CANCoderJNI.ConfigMagnetOffset(m_handle, offsetDegrees, timeoutMs));
263    }
264    /**
265     * Adjusts the zero point for the absolute position register.
266     * The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180)
267     * and a hard-limited mechanism may have such a discontinuity in its functional range.
268     * In which case use this config to move the discontinuity outside of the function range.
269     * @param offsetDegrees
270     *            Offset in degrees (unit string and coefficient DO NOT apply for this config).
271     * @return Error Code generated by function. 0 indicates no error.
272     */
273    public ErrorCode configMagnetOffset(double offsetDegrees)
274    {
275        int timeoutMs = 0;
276        return configMagnetOffset(offsetDegrees, timeoutMs);
277    }
278    /**
279     * Pick the strategy on how to initialize the CANCoder's "Position" register.  Depending on the mechanism,
280     * it may be desirable to auto set the Position register to match the Absolute Position (swerve for example).
281     * Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo).
282     *
283     * TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the CANCoder is reset.
284     *
285     * @param initializationStrategy
286     *            The sensor initialization strategy to use.  This will impact the behavior the next time CANCoder boots up.
287     * @param timeoutMs
288     *            Timeout value in ms. If nonzero, function will wait for
289     *            config success and report an error if it times out.
290     *            If zero, no blocking or checking is performed.
291     * @return Error Code generated by function. 0 indicates no error.
292     */
293    public ErrorCode configSensorInitializationStrategy(SensorInitializationStrategy initializationStrategy, int timeoutMs)
294    {
295        return ErrorCode.valueOf(CANCoderJNI.ConfigSensorInitializationStrategy(m_handle, initializationStrategy.value, timeoutMs));
296    }
297    /**
298     * Pick the strategy on how to initialize the CANCoder's "Position" register.  Depending on the mechanism,
299     * it may be desirable to auto set the Position register to match the Absolute Position (swerve for example).
300     * Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo).
301     *
302     * TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the CANCoder is reset.
303     *
304     * @param initializationStrategy
305     *            The sensor initialization strategy to use.  This will impact the behavior the next time CANCoder boots up.
306     * @return Error Code generated by function. 0 indicates no error.
307     */
308    public ErrorCode configSensorInitializationStrategy(SensorInitializationStrategy initializationStrategy)
309    {
310        int timeoutMs = 0;
311        return configSensorInitializationStrategy(initializationStrategy, timeoutMs);
312    }
313    /**
314     * Choose what units you want the API to get/set.  This also impacts the units displayed in Self-Test in Tuner.
315     * Depending on your mechanism, you may want to scale rotational units (deg, radians, rotations), or scale to a distance (inches, centimeters).
316     * @param sensorCoefficient
317     *            Scalar to multiply the CANCoder's native 12-bit resolute sensor. Defaults to 0.087890625 to produce degrees.
318     * @param unitString
319     *            String holding the unit to report in.  This impacts all routines (except for ConfigMagnetOffset) and the self-test in Tuner.
320     *            The string value itself is arbitrary.  The max number of letters will depend on firmware versioning, but generally CANCoder
321     *            supports up to eight letters.  However, common units such as "centimeters" are supported explicitly despite exceeding the eight-letter limit.
322     *                    Default is "deg"
323     * @param sensorTimeBase
324     *            Desired denominator to report velocity in.  This impacts GetVelocity and the reported velocity in self-test in Tuner.
325     *            Default is "Per Second".
326     * @param timeoutMs
327     *            Timeout value in ms. If nonzero, function will wait for
328     *            config success and report an error if it times out.
329     *            If zero, no blocking or checking is performed.
330     * @return Error Code generated by function. 0 indicates no error.
331     */
332    public ErrorCode configFeedbackCoefficient(double sensorCoefficient, String unitString, SensorTimeBase sensorTimeBase, int timeoutMs)
333    {
334        return ErrorCode.valueOf(CANCoderJNI.ConfigFeedbackCoefficient(m_handle, sensorCoefficient, unitString, sensorTimeBase.value, timeoutMs));
335    }
336    /**
337     * Choose what units you want the API to get/set.  This also impacts the units displayed in Self-Test in Tuner.
338     * Depending on your mechanism, you may want to scale rotational units (deg, radians, rotations), or scale to a distance (inches, centimeters).
339     * @param sensorCoefficient
340     *            Scalar to multiply the CANCoder's native 12-bit resolute sensor. Defaults to 0.087890625 to produce degrees.
341     * @param unitString
342     *            String holding the unit to report in.  This impacts all routines (except for ConfigMagnetOffset) and the self-test in Tuner.
343     *            The string value itself is arbitrary.  The max number of letters will depend on firmware versioning, but generally CANCoder
344     *            supports up to eight letters.  However, common units such as "centimeters" are supported explicitly despite exceeding the eight-letter limit.
345     *                    Default is "deg"
346     * @param sensorTimeBase
347     *            Desired denominator to report velocity in.  This impacts GetVelocity and the reported velocity in self-test in Tuner.
348     *            Default is "Per Second".
349     * @return Error Code generated by function. 0 indicates no error.
350     */
351    public ErrorCode configFeedbackCoefficient(double sensorCoefficient, String unitString, SensorTimeBase sensorTimeBase)
352    {
353        int timeoutMs = 0;
354        return configFeedbackCoefficient(sensorCoefficient, unitString, sensorTimeBase, timeoutMs);
355    }
356    /**
357     * Gets the bus voltage seen by the device.
358     *
359     * @return The bus voltage value (in volts).
360     */
361    public double getBusVoltage() {
362        return CANCoderJNI.GetBusVoltage(m_handle);
363    }
364    /**
365     * Gets the magnet's health.
366     *
367     * @return The magnet health code (red/orange/green).
368     */
369    public MagnetFieldStrength getMagnetFieldStrength() {
370        return MagnetFieldStrength.valueOf(CANCoderJNI.GetMagnetFieldStrength(m_handle));
371    }
372    /**
373     * Choose which direction is interpreted as positive displacement.
374     * This affects both "Position" and "Absolute Position".
375     * @param bSensorDirection
376     *            False (default) means positive rotation occurs when magnet
377     *            is spun counter-clockwise when observer is facing the LED side of CANCoder.
378     * @param timeoutMs
379     *            Timeout value in ms. If nonzero, function will wait for
380     *            config success and report an error if it times out.
381     *            If zero, no blocking or checking is performed.
382     * @return Error Code generated by function. 0 indicates no error.
383     */
384    public ErrorCode configSensorDirection(boolean bSensorDirection, int timeoutMs)
385    {
386        return ErrorCode.valueOf(CANCoderJNI.ConfigSensorDirection(m_handle, bSensorDirection ? 1:0, timeoutMs));
387    }
388    /**
389     * Choose which direction is interpreted as positive displacement.
390     * This affects both "Position" and "Absolute Position".
391     * @param bSensorDirection
392     *            False (default) means positive rotation occurs when magnet
393     *            is spun counter-clockwise when observer is facing the LED side of CANCoder.
394     * @return Error Code generated by function. 0 indicates no error.
395     */
396    public ErrorCode configSensorDirection(boolean bSensorDirection)
397    {
398        int timeoutMs = 0;
399        return configSensorDirection(bSensorDirection, timeoutMs);
400    }
401    /**
402     * Call GetLastError() generated by this object.
403     * Not all functions return an error code but can
404     * potentially report errors.
405     *
406     * This function can be used to retrieve those error codes.
407     *
408     * @return The last ErrorCode generated.
409     */
410    public ErrorCode getLastError() {
411        return ErrorCode.valueOf(CANCoderJNI.GetLastError(m_handle));
412    }
413
414    /**
415     * Get the units for the signal retrieved in the last called get routine.
416     */
417    public String getLastUnitString() {
418        return CANCoderJNI.GetLastUnitString(m_handle);
419    }
420
421    /**
422     * Get the timestamp of the CAN frame retrieved in the last called get routine.
423     */
424    public double getLastTimestamp() {
425        return CANCoderJNI.GetLastTimestamp(m_handle);
426    }
427
428    //------ Custom Persistent Params ----------//
429
430    /**
431     * Sets the value of a custom parameter. This is for arbitrary use.
432     *
433     * Sometimes it is necessary to save calibration/duty cycle/output
434     * information in the device. Particularly if the
435     * device is part of a subsystem that can be replaced.
436     *
437     * @param newValue
438     *            Value for custom parameter.
439     * @param paramIndex
440     *            Index of custom parameter. [0-1]
441     * @param timeoutMs
442     *            Timeout value in ms. If nonzero, function will wait for
443     *            config success and report an error if it times out.
444     *            If zero, no blocking or checking is performed.
445     * @return Error Code generated by function. 0 indicates no error.
446     */
447    public ErrorCode configSetCustomParam(int newValue,
448        int paramIndex, int timeoutMs) {
449        return ErrorCode.valueOf(CANCoderJNI.ConfigSetCustomParam(m_handle, newValue, paramIndex, timeoutMs));
450    }
451    /**
452     * Sets the value of a custom parameter. This is for arbitrary use.
453     *
454     * Sometimes it is necessary to save calibration/duty cycle/output
455     * information in the device. Particularly if the
456     * device is part of a subsystem that can be replaced.
457     *
458     * @param newValue
459     *            Value for custom parameter.
460     * @param paramIndex
461     *            Index of custom parameter. [0-1]
462     * @return Error Code generated by function. 0 indicates no error.
463     */
464    public ErrorCode configSetCustomParam(int newValue,
465        int paramIndex) {
466        int timeoutMs = 0;
467        return configSetCustomParam(newValue, paramIndex, timeoutMs);
468    }
469    /**
470     * Gets the value of a custom parameter. This is for arbitrary use.
471     *
472     * Sometimes it is necessary to save calibration/duty cycle/output
473     * information in the device. Particularly if the
474     * device is part of a subsystem that can be replaced.
475     *
476     * @param paramIndex
477     *            Index of custom parameter. [0-1]
478     * @param timeoutMs
479     *            Timeout value in ms. If nonzero, function will wait for
480     *            config success and report an error if it times out.
481     *            If zero, no blocking or checking is performed.
482     * @return Value of the custom param.
483     */
484    public int configGetCustomParam(int paramIndex, int timeoutMs) {
485        return CANCoderJNI.ConfigGetCustomParam(m_handle, paramIndex, timeoutMs);
486    }
487    /**
488     * Gets the value of a custom parameter. This is for arbitrary use.
489     *
490     * Sometimes it is necessary to save calibration/duty cycle/output
491     * information in the device. Particularly if the
492     * device is part of a subsystem that can be replaced.
493     *
494     * @param paramIndex
495     *            Index of custom parameter. [0-1]
496     * @return Value of the custom param.
497     */
498    public int configGetCustomParam(int paramIndex) {
499        int timeoutMs = 0;
500        return configGetCustomParam(paramIndex, timeoutMs);
501    }
502
503    //------ Generic Param API, typically not used ----------//
504    /**
505     * Sets a parameter. Generally this is not used.
506     * This can be utilized in
507     * - Using new features without updating API installation.
508     * - Errata workarounds to circumvent API implementation.
509     * - Allows for rapid testing / unit testing of firmware.
510     *
511     * @param param
512     *            Parameter enumeration.
513     * @param value
514     *            Value of parameter.
515     * @param subValue
516     *            Subvalue for parameter. Maximum value of 255.
517     * @param ordinal
518     *            Ordinal of parameter.
519     * @param timeoutMs
520     *            Timeout value in ms. If nonzero, function will wait for
521     *            config success and report an error if it times out.
522     *            If zero, no blocking or checking is performed.
523     * @return Error Code generated by function. 0 indicates no error.
524     */
525    public ErrorCode configSetParameter(ParamEnum param, double value,
526        int subValue, int ordinal, int timeoutMs) {
527        return ErrorCode.valueOf(CANCoderJNI.ConfigSetParameter(m_handle, param.value, value, subValue, ordinal, timeoutMs));
528
529    }
530    /**
531     * Sets a parameter. Generally this is not used.
532     * This can be utilized in
533     * - Using new features without updating API installation.
534     * - Errata workarounds to circumvent API implementation.
535     * - Allows for rapid testing / unit testing of firmware.
536     *
537     * @param param
538     *            Parameter enumeration.
539     * @param value
540     *            Value of parameter.
541     * @param subValue
542     *            Subvalue for parameter. Maximum value of 255.
543     * @param ordinal
544     *            Ordinal of parameter.
545     * @return Error Code generated by function. 0 indicates no error.
546     */
547    public ErrorCode configSetParameter(ParamEnum param, double value,
548        int subValue, int ordinal) {
549        int timeoutMs = 0;
550        return configSetParameter(param, value, subValue, ordinal, timeoutMs);
551
552    }
553    /**
554     * Gets a parameter. Generally this is not used.
555     * This can be utilized in
556     * - Using new features without updating API installation.
557     * - Errata workarounds to circumvent API implementation.
558     * - Allows for rapid testing / unit testing of firmware.
559     *
560     * @param param
561     *            Parameter enumeration.
562     * @param ordinal
563     *            Ordinal of parameter.
564     * @param timeoutMs
565     *            Timeout value in ms. If nonzero, function will wait for
566     *            config success and report an error if it times out.
567     *            If zero, no blocking or checking is performed.
568     * @return Value of parameter.
569     */
570    public double configGetParameter(ParamEnum param, int ordinal, int timeoutMs) {
571        return CANCoderJNI.ConfigGetParameter(m_handle, param.value, ordinal, timeoutMs);
572    }
573    /**
574     * Gets a parameter. Generally this is not used.
575     * This can be utilized in
576     * - Using new features without updating API installation.
577     * - Errata workarounds to circumvent API implementation.
578     * - Allows for rapid testing / unit testing of firmware.
579     *
580     * @param param
581     *            Parameter enumeration.
582     * @param ordinal
583     *            Ordinal of parameter.
584     * @return Value of parameter.
585     */
586    public double configGetParameter(ParamEnum param, int ordinal) {
587        int timeoutMs = 0;
588        return configGetParameter(param, ordinal, timeoutMs);
589    }
590
591    //------ Frames ----------//
592    /**
593     * Sets the period of the given status frame.
594     *
595     * @param statusFrame
596     *            Frame whose period is to be changed.
597     * @param periodMs
598     *            Period in ms for the given frame.
599     * @param timeoutMs
600     *            Timeout value in ms. If nonzero, function will wait for
601     *            config success and report an error if it times out.
602     *            If zero, no blocking or checking is performed.
603     * @return Error Code generated by function. 0 indicates no error.
604     */
605    public ErrorCode setStatusFramePeriod(CANCoderStatusFrame statusFrame, int periodMs, int timeoutMs) {
606        return ErrorCode.valueOf(CANCoderJNI.SetStatusFramePeriod(m_handle, statusFrame.value, periodMs, timeoutMs));
607    }
608    /**
609     * Sets the period of the given status frame.
610     *
611     * @param statusFrame
612     *            Frame whose period is to be changed.
613     * @param periodMs
614     *            Period in ms for the given frame.
615     * @return Error Code generated by function. 0 indicates no error.
616     */
617    public ErrorCode setStatusFramePeriod(CANCoderStatusFrame statusFrame, int periodMs) {
618        int timeoutMs = 0;
619        return setStatusFramePeriod(statusFrame, periodMs, timeoutMs);
620    }
621    /**
622     * Gets the period of the given status frame.
623     *
624     * @param frame
625     *            Frame to get the period of.
626     * @param timeoutMs
627     *            Timeout value in ms. If nonzero, function will wait for
628     *            config success and report an error if it times out.
629     *            If zero, no blocking or checking is performed.
630     * @return Period of the given status frame.
631     */
632    public int getStatusFramePeriod(CANCoderStatusFrame frame,
633        int timeoutMs) {
634        return CANCoderJNI.GetStatusFramePeriod(m_handle, frame.value, timeoutMs);
635    }
636    /**
637     * Gets the period of the given status frame.
638     *
639     * @param frame
640     *            Frame to get the period of.
641     * @return Period of the given status frame.
642     */
643    public int getStatusFramePeriod(CANCoderStatusFrame frame) {
644        int timeoutMs = 0;
645        return getStatusFramePeriod(frame, timeoutMs);
646    }
647    //------ Firmware ----------//
648    /**
649     * Gets the firmware version of the device.
650     *
651     * @return Firmware version of device.
652     */
653    public int getFirmwareVersion() {
654        return CANCoderJNI.GetFirmwareVersion(m_handle);
655    }
656    /**
657     * Returns true if the device has reset since last call.
658     *
659     * @return Has a Device Reset Occurred?
660     */
661    public boolean hasResetOccurred() {
662        return CANCoderJNI.HasResetOccurred(m_handle);
663    }
664    //------ Faults ----------//
665    /**
666     * Gets the CANCoder fault status
667     *
668     * @param toFill
669     *            Container for fault statuses.
670     * @return Error Code generated by function. 0 indicates no error.
671     */
672    public ErrorCode getFaults(CANCoderFaults toFill) {
673        int bits = CANCoderJNI.GetFaults(m_handle);
674        toFill.update(bits);
675        return getLastError();
676    }
677    /**
678     * Gets the CANCoder sticky fault status
679     *
680     * @param toFill
681     *            Container for sticky fault statuses.
682     * @return Error Code generated by function. 0 indicates no error.
683     */
684    public ErrorCode getStickyFaults(CANCoderStickyFaults toFill) {
685        int bits = CANCoderJNI.GetStickyFaults(m_handle);
686        toFill.update(bits);
687        return getLastError();
688    }
689    /**
690     * Clears the Sticky Faults
691     *
692     * @return Error Code generated by function. 0 indicates no error.
693     */
694    public ErrorCode clearStickyFaults(int timeoutMs) {
695        return ErrorCode.valueOf(CANCoderJNI.ClearStickyFaults(m_handle, timeoutMs));
696    }
697    /**
698     * Clears the Sticky Faults
699     *
700     * @return Error Code generated by function. 0 indicates no error.
701     */
702    public ErrorCode clearStickyFaults() {
703        int timeoutMs = 0;
704        return clearStickyFaults(timeoutMs);
705    }
706
707    /**
708     *
709     * @param timeoutMs
710     *              Timeout value in ms. If nonzero, function will wait for
711     *              config success and report an error if it times out.
712     * @return Read value of the config param.
713     */
714    public SensorVelocityMeasPeriod configGetVelocityMeasurementPeriod(int timeoutMs)
715    {
716        return SensorVelocityMeasPeriod.valueOf(CANCoderJNI.ConfigGetVelocityMeasurementPeriod(m_handle, timeoutMs));
717    }
718    /**
719     * @return Read value of the config param.
720     */
721    public SensorVelocityMeasPeriod configGetVelocityMeasurementPeriod()
722    {
723        int timeoutMs = 50;
724        return configGetVelocityMeasurementPeriod(timeoutMs);
725    }
726    /**
727     *
728     * @param timeoutMs
729     *              Timeout value in ms. If nonzero, function will wait for
730     *              config success and report an error if it times out.
731     * @return Read value of the config param.
732     */
733    public int configGetVelocityMeasurementWindow(int timeoutMs)
734    {
735        return CANCoderJNI.ConfigGetVelocityMeasurementWindow(m_handle, timeoutMs);
736    }
737    /**
738     * @return Read value of the config param.
739     */
740    public int configGetVelocityMeasurementWindow()
741    {
742        int timeoutMs = 50;
743        return configGetVelocityMeasurementWindow(timeoutMs);
744    }
745    /**
746     *
747     * @param timeoutMs
748     *              Timeout value in ms. If nonzero, function will wait for
749     *              config success and report an error if it times out.
750     * @return Read value of the config param.
751     */
752    public AbsoluteSensorRange configGetAbsoluteSensorRange(int timeoutMs)
753    {
754        return AbsoluteSensorRange.valueOf(CANCoderJNI.ConfigGetAbsoluteSensorRange(m_handle, timeoutMs));
755    }
756    /**
757     * @return Read value of the config param.
758     */
759    public AbsoluteSensorRange configGetAbsoluteSensorRange()
760    {
761        int timeoutMs = 50;
762        return configGetAbsoluteSensorRange(timeoutMs);
763    }
764    /**
765     *
766     * @param timeoutMs
767     *              Timeout value in ms. If nonzero, function will wait for
768     *              config success and report an error if it times out.
769     * @return Read value of the config param.
770     */
771    public double configGetMagnetOffset(int timeoutMs)
772    {
773        return CANCoderJNI.ConfigGetMagnetOffset(m_handle, timeoutMs);
774    }
775    /**
776     * @return Read value of the config param.
777     */
778    public double configGetMagnetOffset()
779    {
780        int timeoutMs = 50;
781        return configGetMagnetOffset(timeoutMs);
782    }
783    /**
784     *
785     * @param timeoutMs
786     *              Timeout value in ms. If nonzero, function will wait for
787     *              config success and report an error if it times out.
788     * @return Read value of the config param.
789     */
790    public boolean configGetSensorDirection(int timeoutMs)
791    {
792        return 0 != CANCoderJNI.ConfigGetSensorDirection(m_handle, timeoutMs);
793    }
794    /**
795     * @return Read value of the config param.
796     */
797    public boolean configGetSensorDirection()
798    {
799        int timeoutMs = 50;
800        return configGetSensorDirection(timeoutMs);
801    }
802    /**
803     *
804     * @param timeoutMs
805     *              Timeout value in ms. If nonzero, function will wait for
806     *              config success and report an error if it times out.
807     * @return Read value of the config param.
808     */
809    public SensorInitializationStrategy configGetSensorInitializationStrategy(int timeoutMs)
810    {
811        return SensorInitializationStrategy.valueOf(CANCoderJNI.ConfigGetSensorInitializationStrategy(m_handle, timeoutMs));
812    }
813    /**
814     * @return Read value of the config param.
815     */
816    public SensorInitializationStrategy configGetSensorInitializationStrategy()
817    {
818        int timeoutMs = 50;
819        return configGetSensorInitializationStrategy(timeoutMs);
820    }
821    /**
822     *
823     * @param timeoutMs
824     *              Timeout value in ms. If nonzero, function will wait for
825     *              config success and report an error if it times out.
826     * @return Read value of the config param.
827     */
828    public double configGetFeedbackCoefficient(int timeoutMs)
829    {
830        return CANCoderJNI.ConfigGetFeedbackCoefficient(m_handle, timeoutMs);
831    }
832    /**
833     * @return Read value of the config param.
834     */
835    public double configGetFeedbackCoefficient()
836    {
837        int timeoutMs = 50;
838        return configGetFeedbackCoefficient(timeoutMs);
839    }
840    /**
841     *
842     * @param timeoutMs
843     *              Timeout value in ms. If nonzero, function will wait for
844     *              config success and report an error if it times out.
845     * @return Read value of the config param.
846     */
847    public String configGetFeedbackUnitString(int timeoutMs)
848    {
849        return CANCoderJNI.ConfigGetFeedbackUnitString(m_handle, timeoutMs);
850    }
851    /**
852     * @return Read value of the config param.
853     */
854    public String configGetFeedbackUnitString()
855    {
856        int timeoutMs = 50;
857        return configGetFeedbackUnitString(timeoutMs);
858    }
859    /**
860     *
861     * @param timeoutMs
862     *              Timeout value in ms. If nonzero, function will wait for
863     *              config success and report an error if it times out.
864     * @return Read value of the config param.
865     */
866    public SensorTimeBase configGetFeedbackTimeBase(int timeoutMs)
867    {
868        return SensorTimeBase.valueOf(CANCoderJNI.ConfigGetFeedbackTimeBase(m_handle, timeoutMs));
869    }
870    /**
871     * @return Read value of the config param.
872     */
873    public SensorTimeBase configGetFeedbackTimeBase()
874    {
875        int timeoutMs = 50;
876        return configGetFeedbackTimeBase(timeoutMs);
877    }
878
879    /**
880     * Configures all persistent settings.
881     *
882     * @param allConfigs        Object with all of the persistant settings
883     * @param timeoutMs
884     *              Timeout value in ms. If nonzero, function will wait for
885     *              config success and report an error if it times out.
886     *              If zero, no blocking or checking is performed.
887     *
888     * @return Error Code generated by function. 0 indicates no error.
889     */
890    public ErrorCode configAllSettings(CANCoderConfiguration allConfigs, int timeoutMs) {
891
892        ErrorCollection errorCollection = new ErrorCollection();
893        errorCollection.NewError(configFactoryDefault(timeoutMs));
894
895        if (CANCoderConfigUtil.velocityMeasurementPeriodDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementPeriod(allConfigs.velocityMeasurementPeriod, timeoutMs));
896        if (CANCoderConfigUtil.velocityMeasurementWindowDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementWindow(allConfigs.velocityMeasurementWindow, timeoutMs));
897        if (CANCoderConfigUtil.customParam0Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam0, 0, timeoutMs));
898        if (CANCoderConfigUtil.customParam1Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam1, 1, timeoutMs));
899                if (CANCoderConfigUtil.absoluteSensorRangeDifferent(allConfigs)) errorCollection.NewError(configAbsoluteSensorRange(allConfigs.absoluteSensorRange, timeoutMs));
900                if (CANCoderConfigUtil.magnetOffsetDegreesDifferent(allConfigs)) errorCollection.NewError(configMagnetOffset(allConfigs.magnetOffsetDegrees, timeoutMs));
901                if (CANCoderConfigUtil.sensorDirectionDifferent(allConfigs)) errorCollection.NewError(configSensorDirection(allConfigs.sensorDirection, timeoutMs));
902                if (CANCoderConfigUtil.initializationStrategyDifferent(allConfigs)) errorCollection.NewError(configSensorInitializationStrategy(allConfigs.initializationStrategy, timeoutMs));
903                if (CANCoderConfigUtil.sensorCoefficientDifferent(allConfigs) ||
904                CANCoderConfigUtil.unitStringDifferent(allConfigs) ||
905                CANCoderConfigUtil.sensorTimeBaseDifferent(allConfigs)) {
906            errorCollection.NewError(configFeedbackCoefficient(allConfigs.sensorCoefficient, allConfigs.unitString, allConfigs.sensorTimeBase, timeoutMs));
907        }
908
909        return errorCollection._worstError;
910    }
911    /**
912     * Configures all persistent settings (overloaded so timeoutMs is 50 ms).
913     *
914         * @param allConfigs        Object with all of the persistant settings
915     *
916     * @return Error Code generated by function. 0 indicates no error.
917     */
918        public ErrorCode configAllSettings(CANCoderConfiguration allConfigs) {
919                int timeoutMs = 50;
920                return configAllSettings(allConfigs, timeoutMs);
921        }
922
923    /**
924     * Gets all persistant settings.
925     *
926     * @param allConfigs        Object with all of the persistant settings
927     * @param timeoutMs
928     *              Timeout value in ms. If nonzero, function will wait for
929     *              config success and report an error if it times out.
930     *              If zero, no blocking or checking is performed.
931     */
932    public void getAllConfigs(CANCoderConfiguration allConfigs, int timeoutMs) {
933        allConfigs.velocityMeasurementPeriod = configGetVelocityMeasurementPeriod(timeoutMs);
934        allConfigs.velocityMeasurementWindow = configGetVelocityMeasurementWindow(timeoutMs);
935        allConfigs.customParam0 = (int)configGetParameter(ParamEnum.eCustomParam, 0, timeoutMs);
936        allConfigs.customParam1 = (int)configGetParameter(ParamEnum.eCustomParam, 1, timeoutMs);
937        allConfigs.absoluteSensorRange = configGetAbsoluteSensorRange(timeoutMs);
938        allConfigs.magnetOffsetDegrees = configGetMagnetOffset(timeoutMs);
939        allConfigs.sensorDirection = configGetSensorDirection(timeoutMs);
940        allConfigs.initializationStrategy = configGetSensorInitializationStrategy(timeoutMs);
941        allConfigs.sensorCoefficient = configGetFeedbackCoefficient(timeoutMs);
942        allConfigs.unitString = configGetFeedbackUnitString(timeoutMs);
943        allConfigs.sensorTimeBase = configGetFeedbackTimeBase(timeoutMs);
944    }
945    /**
946     * Gets all persistant settings (overloaded so timeoutMs is 50 ms).
947     *
948         * @param allConfigs        Object with all of the persistant settings
949     */
950    public void getAllConfigs(CANCoderConfiguration allConfigs) {
951        int timeoutMs = 50;
952        getAllConfigs(allConfigs, timeoutMs);
953    }
954
955    /**
956     * Configures all persistent settings to defaults.
957     *
958     * @param timeoutMs
959     *              Timeout value in ms. If nonzero, function will wait for
960     *              config success and report an error if it times out.
961     *              If zero, no blocking or checking is performed.
962     *
963     * @return Error Code generated by function. 0 indicates no error.
964     */
965    public ErrorCode configFactoryDefault(int timeoutMs) {
966        return ErrorCode.valueOf(CANCoderJNI.ConfigFactoryDefault(m_handle, timeoutMs));
967    }
968    /**
969     * Configures all persistent settings to defaults.
970     *
971     * @return Error Code generated by function. 0 indicates no error.
972     */
973    public ErrorCode configFactoryDefault() {
974        int timeoutMs = 50;
975        return configFactoryDefault(timeoutMs);
976    }
977}