001/*
002 * Copyright (C) Cross The Road Electronics.  All rights reserved.
003 * License information can be found in CTRE_LICENSE.txt
004 * For support and suggestions contact support@ctr-electronics.com or file
005 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
006 */
007package com.ctre.phoenix6.hardware.core;
008
009import com.ctre.phoenix6.hardware.ParentDevice;
010import com.ctre.phoenix6.controls.*;
011import com.ctre.phoenix6.configs.*;
012import com.ctre.phoenix6.StatusCode;
013import com.ctre.phoenix6.jni.PlatformJNI;
014import com.ctre.phoenix6.sim.DeviceType;
015import com.ctre.phoenix6.sim.CANcoderSimState;
016import com.ctre.phoenix6.*;
017import com.ctre.phoenix6.spns.*;
018import com.ctre.phoenix6.signals.*;
019import edu.wpi.first.units.*;
020import edu.wpi.first.units.measure.*;
021import static edu.wpi.first.units.Units.*;
022
023/**
024 * Class for CANcoder, a CAN based magnetic encoder that provides absolute and
025 * relative position along with filtered velocity.
026 * 
027 * <pre>
028 * // Constants used in CANcoder construction
029 * final int kCANcoderId = 0;
030 * final String kCANcoderCANbus = "canivore";
031 * 
032 * // Construct the CANcoder
033 * CANcoder cancoder = new CANcoder(kCANcoderId, kCANcoderCANbus);
034 * 
035 * // Configure the CANcoder for basic use
036 * CANcoderConfiguration configs = new CANcoderConfiguration();
037 * // This CANcoder should report absolute position from [-0.5, 0.5) rotations,
038 * // with a 0.26 rotation offset, with clockwise being positive
039 * configs.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRange.Signed_PlusMinusHalf;
040 * configs.MountPose.MagnetOffset = 0.26;
041 * configs.MountPose.SensorDirection = SensorDirectionValue.Clockwise_Positive;
042 * 
043 * // Write these configs to the CANcoder
044 * cancoder.getConfigurator().apply(configs);
045 * 
046 * // Set the position to 0 rotations for initial use
047 * cancoder.setPosition(0);
048 * 
049 * // Get Position and Velocity
050 * var position = cancoder.getPosition();
051 * var velocity = cancoder.getVelocity();
052 * 
053 * // Refresh and print these values
054 * System.out.println("Position is " + position.refresh().toString());
055 * System.out.println("Velocity is " + velocity.refresh().toString());
056 * </pre>
057 */
058public class CoreCANcoder extends ParentDevice
059{
060    private CANcoderConfigurator _configurator;
061
062    /**
063     * Constructs a new CANcoder object.
064     * <p>
065     * Constructs the device using the default CAN bus for the system:
066     * <ul>
067     *   <li>"rio" on roboRIO
068     *   <li>"can0" on Linux
069     *   <li>"*" on Windows
070     * </ul>
071     *
072     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
073     */
074    public CoreCANcoder(int deviceId)
075    {
076        this(deviceId, "");
077    }
078
079    /**
080     * Constructs a new CANcoder object.
081     *
082     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
083     * @param canbus      Name of the CAN bus this device is on. Possible CAN bus strings are:
084     *                    <ul>
085     *                      <li>"rio" for the native roboRIO CAN bus
086     *                      <li>CANivore name or serial number
087     *                      <li>SocketCAN interface (non-FRC Linux only)
088     *                      <li>"*" for any CANivore seen by the program
089     *                      <li>empty string (default) to select the default for the system:
090     *                      <ul>
091     *                        <li>"rio" on roboRIO
092     *                        <li>"can0" on Linux
093     *                        <li>"*" on Windows
094     *                      </ul>
095     *                    </ul>
096     */
097    public CoreCANcoder(int deviceId, String canbus)
098    {
099        super(deviceId, "cancoder", canbus);
100        _configurator = new CANcoderConfigurator(this.deviceIdentifier);
101        PlatformJNI.JNI_SimCreate(DeviceType.P6_CANcoderType.value, deviceId);
102    }
103
104    /**
105     * Constructs a new CANcoder object.
106     *
107     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
108     * @param canbus      The CAN bus this device is on.
109     */
110    public CoreCANcoder(int deviceId, CANBus canbus)
111    {
112        this(deviceId, canbus.getName());
113    }
114
115    /**
116     * Gets the configurator to use with this device's configs
117     *
118     * @return Configurator for this object
119     */
120    public CANcoderConfigurator getConfigurator()
121    {
122        return this._configurator;
123    }
124
125
126    private CANcoderSimState _simState = null;
127    /**
128     * Get the simulation state for this device.
129     * <p>
130     * This function reuses an allocated simulation state
131     * object, so it is safe to call this function multiple
132     * times in a robot loop.
133     *
134     * @return Simulation state
135     */
136    public CANcoderSimState getSimState() {
137        if (_simState == null)
138            _simState = new CANcoderSimState(this);
139        return _simState;
140    }
141
142
143        
144    /**
145     * App Major Version number.
146     * 
147     * <ul>
148     *   <li> <b>Minimum Value:</b> 0
149     *   <li> <b>Maximum Value:</b> 255
150     *   <li> <b>Default Value:</b> 0
151     *   <li> <b>Units:</b> 
152     * </ul>
153     * 
154     * Default Rates:
155     * <ul>
156     *   <li> <b>CAN:</b> 4.0 Hz
157     * </ul>
158     * <p>
159     * This refreshes and returns a cached StatusSignal object.
160     * 
161     * @return VersionMajor Status Signal Object
162     */
163    public StatusSignal<Integer> getVersionMajor()
164    {
165        return getVersionMajor(true);
166    }
167    
168    /**
169     * App Major Version number.
170     * 
171     * <ul>
172     *   <li> <b>Minimum Value:</b> 0
173     *   <li> <b>Maximum Value:</b> 255
174     *   <li> <b>Default Value:</b> 0
175     *   <li> <b>Units:</b> 
176     * </ul>
177     * 
178     * Default Rates:
179     * <ul>
180     *   <li> <b>CAN:</b> 4.0 Hz
181     * </ul>
182     * <p>
183     * This refreshes and returns a cached StatusSignal object.
184     * 
185     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
186     * @return VersionMajor Status Signal Object
187     */
188    public StatusSignal<Integer> getVersionMajor(boolean refresh)
189    {
190        @SuppressWarnings("unchecked")
191        var retval = super.lookupStatusSignal(SpnValue.Version_Major.value, Integer.class, val -> (int)val, "VersionMajor", false, refresh);
192        return retval;
193    }
194        
195    /**
196     * App Minor Version number.
197     * 
198     * <ul>
199     *   <li> <b>Minimum Value:</b> 0
200     *   <li> <b>Maximum Value:</b> 255
201     *   <li> <b>Default Value:</b> 0
202     *   <li> <b>Units:</b> 
203     * </ul>
204     * 
205     * Default Rates:
206     * <ul>
207     *   <li> <b>CAN:</b> 4.0 Hz
208     * </ul>
209     * <p>
210     * This refreshes and returns a cached StatusSignal object.
211     * 
212     * @return VersionMinor Status Signal Object
213     */
214    public StatusSignal<Integer> getVersionMinor()
215    {
216        return getVersionMinor(true);
217    }
218    
219    /**
220     * App Minor Version number.
221     * 
222     * <ul>
223     *   <li> <b>Minimum Value:</b> 0
224     *   <li> <b>Maximum Value:</b> 255
225     *   <li> <b>Default Value:</b> 0
226     *   <li> <b>Units:</b> 
227     * </ul>
228     * 
229     * Default Rates:
230     * <ul>
231     *   <li> <b>CAN:</b> 4.0 Hz
232     * </ul>
233     * <p>
234     * This refreshes and returns a cached StatusSignal object.
235     * 
236     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
237     * @return VersionMinor Status Signal Object
238     */
239    public StatusSignal<Integer> getVersionMinor(boolean refresh)
240    {
241        @SuppressWarnings("unchecked")
242        var retval = super.lookupStatusSignal(SpnValue.Version_Minor.value, Integer.class, val -> (int)val, "VersionMinor", false, refresh);
243        return retval;
244    }
245        
246    /**
247     * App Bugfix Version number.
248     * 
249     * <ul>
250     *   <li> <b>Minimum Value:</b> 0
251     *   <li> <b>Maximum Value:</b> 255
252     *   <li> <b>Default Value:</b> 0
253     *   <li> <b>Units:</b> 
254     * </ul>
255     * 
256     * Default Rates:
257     * <ul>
258     *   <li> <b>CAN:</b> 4.0 Hz
259     * </ul>
260     * <p>
261     * This refreshes and returns a cached StatusSignal object.
262     * 
263     * @return VersionBugfix Status Signal Object
264     */
265    public StatusSignal<Integer> getVersionBugfix()
266    {
267        return getVersionBugfix(true);
268    }
269    
270    /**
271     * App Bugfix Version number.
272     * 
273     * <ul>
274     *   <li> <b>Minimum Value:</b> 0
275     *   <li> <b>Maximum Value:</b> 255
276     *   <li> <b>Default Value:</b> 0
277     *   <li> <b>Units:</b> 
278     * </ul>
279     * 
280     * Default Rates:
281     * <ul>
282     *   <li> <b>CAN:</b> 4.0 Hz
283     * </ul>
284     * <p>
285     * This refreshes and returns a cached StatusSignal object.
286     * 
287     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
288     * @return VersionBugfix Status Signal Object
289     */
290    public StatusSignal<Integer> getVersionBugfix(boolean refresh)
291    {
292        @SuppressWarnings("unchecked")
293        var retval = super.lookupStatusSignal(SpnValue.Version_Bugfix.value, Integer.class, val -> (int)val, "VersionBugfix", false, refresh);
294        return retval;
295    }
296        
297    /**
298     * App Build Version number.
299     * 
300     * <ul>
301     *   <li> <b>Minimum Value:</b> 0
302     *   <li> <b>Maximum Value:</b> 255
303     *   <li> <b>Default Value:</b> 0
304     *   <li> <b>Units:</b> 
305     * </ul>
306     * 
307     * Default Rates:
308     * <ul>
309     *   <li> <b>CAN:</b> 4.0 Hz
310     * </ul>
311     * <p>
312     * This refreshes and returns a cached StatusSignal object.
313     * 
314     * @return VersionBuild Status Signal Object
315     */
316    public StatusSignal<Integer> getVersionBuild()
317    {
318        return getVersionBuild(true);
319    }
320    
321    /**
322     * App Build Version number.
323     * 
324     * <ul>
325     *   <li> <b>Minimum Value:</b> 0
326     *   <li> <b>Maximum Value:</b> 255
327     *   <li> <b>Default Value:</b> 0
328     *   <li> <b>Units:</b> 
329     * </ul>
330     * 
331     * Default Rates:
332     * <ul>
333     *   <li> <b>CAN:</b> 4.0 Hz
334     * </ul>
335     * <p>
336     * This refreshes and returns a cached StatusSignal object.
337     * 
338     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
339     * @return VersionBuild Status Signal Object
340     */
341    public StatusSignal<Integer> getVersionBuild(boolean refresh)
342    {
343        @SuppressWarnings("unchecked")
344        var retval = super.lookupStatusSignal(SpnValue.Version_Build.value, Integer.class, val -> (int)val, "VersionBuild", false, refresh);
345        return retval;
346    }
347        
348    /**
349     * Full Version of firmware in device.  The format is a four byte
350     * value.
351     * 
352     * <ul>
353     *   <li> <b>Minimum Value:</b> 0
354     *   <li> <b>Maximum Value:</b> 4294967295
355     *   <li> <b>Default Value:</b> 0
356     *   <li> <b>Units:</b> 
357     * </ul>
358     * 
359     * Default Rates:
360     * <ul>
361     *   <li> <b>CAN:</b> 4.0 Hz
362     * </ul>
363     * <p>
364     * This refreshes and returns a cached StatusSignal object.
365     * 
366     * @return Version Status Signal Object
367     */
368    public StatusSignal<Integer> getVersion()
369    {
370        return getVersion(true);
371    }
372    
373    /**
374     * Full Version of firmware in device.  The format is a four byte
375     * value.
376     * 
377     * <ul>
378     *   <li> <b>Minimum Value:</b> 0
379     *   <li> <b>Maximum Value:</b> 4294967295
380     *   <li> <b>Default Value:</b> 0
381     *   <li> <b>Units:</b> 
382     * </ul>
383     * 
384     * Default Rates:
385     * <ul>
386     *   <li> <b>CAN:</b> 4.0 Hz
387     * </ul>
388     * <p>
389     * This refreshes and returns a cached StatusSignal object.
390     * 
391     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
392     * @return Version Status Signal Object
393     */
394    public StatusSignal<Integer> getVersion(boolean refresh)
395    {
396        @SuppressWarnings("unchecked")
397        var retval = super.lookupStatusSignal(SpnValue.Version_Full.value, Integer.class, val -> (int)val, "Version", false, refresh);
398        return retval;
399    }
400        
401    /**
402     * Integer representing all fault flags reported by the device.
403     * <p>
404     * These are device specific and are not used directly in typical
405     * applications. Use the signal specific GetFault_*() methods instead.
406     * 
407     * <ul>
408     *   <li> <b>Minimum Value:</b> 0
409     *   <li> <b>Maximum Value:</b> 4294967295
410     *   <li> <b>Default Value:</b> 0
411     *   <li> <b>Units:</b> 
412     * </ul>
413     * 
414     * Default Rates:
415     * <ul>
416     *   <li> <b>CAN:</b> 4.0 Hz
417     * </ul>
418     * <p>
419     * This refreshes and returns a cached StatusSignal object.
420     * 
421     * @return FaultField Status Signal Object
422     */
423    public StatusSignal<Integer> getFaultField()
424    {
425        return getFaultField(true);
426    }
427    
428    /**
429     * Integer representing all fault flags reported by the device.
430     * <p>
431     * These are device specific and are not used directly in typical
432     * applications. Use the signal specific GetFault_*() methods instead.
433     * 
434     * <ul>
435     *   <li> <b>Minimum Value:</b> 0
436     *   <li> <b>Maximum Value:</b> 4294967295
437     *   <li> <b>Default Value:</b> 0
438     *   <li> <b>Units:</b> 
439     * </ul>
440     * 
441     * Default Rates:
442     * <ul>
443     *   <li> <b>CAN:</b> 4.0 Hz
444     * </ul>
445     * <p>
446     * This refreshes and returns a cached StatusSignal object.
447     * 
448     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
449     * @return FaultField Status Signal Object
450     */
451    public StatusSignal<Integer> getFaultField(boolean refresh)
452    {
453        @SuppressWarnings("unchecked")
454        var retval = super.lookupStatusSignal(SpnValue.AllFaults.value, Integer.class, val -> (int)val, "FaultField", true, refresh);
455        return retval;
456    }
457        
458    /**
459     * Integer representing all (persistent) sticky fault flags reported
460     * by the device.
461     * <p>
462     * These are device specific and are not used directly in typical
463     * applications. Use the signal specific GetStickyFault_*() methods
464     * instead.
465     * 
466     * <ul>
467     *   <li> <b>Minimum Value:</b> 0
468     *   <li> <b>Maximum Value:</b> 4294967295
469     *   <li> <b>Default Value:</b> 0
470     *   <li> <b>Units:</b> 
471     * </ul>
472     * 
473     * Default Rates:
474     * <ul>
475     *   <li> <b>CAN:</b> 4.0 Hz
476     * </ul>
477     * <p>
478     * This refreshes and returns a cached StatusSignal object.
479     * 
480     * @return StickyFaultField Status Signal Object
481     */
482    public StatusSignal<Integer> getStickyFaultField()
483    {
484        return getStickyFaultField(true);
485    }
486    
487    /**
488     * Integer representing all (persistent) sticky fault flags reported
489     * by the device.
490     * <p>
491     * These are device specific and are not used directly in typical
492     * applications. Use the signal specific GetStickyFault_*() methods
493     * instead.
494     * 
495     * <ul>
496     *   <li> <b>Minimum Value:</b> 0
497     *   <li> <b>Maximum Value:</b> 4294967295
498     *   <li> <b>Default Value:</b> 0
499     *   <li> <b>Units:</b> 
500     * </ul>
501     * 
502     * Default Rates:
503     * <ul>
504     *   <li> <b>CAN:</b> 4.0 Hz
505     * </ul>
506     * <p>
507     * This refreshes and returns a cached StatusSignal object.
508     * 
509     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
510     * @return StickyFaultField Status Signal Object
511     */
512    public StatusSignal<Integer> getStickyFaultField(boolean refresh)
513    {
514        @SuppressWarnings("unchecked")
515        var retval = super.lookupStatusSignal(SpnValue.AllStickyFaults.value, Integer.class, val -> (int)val, "StickyFaultField", true, refresh);
516        return retval;
517    }
518        
519    /**
520     * Velocity of the device.
521     * 
522     * <ul>
523     *   <li> <b>Minimum Value:</b> -512.0
524     *   <li> <b>Maximum Value:</b> 511.998046875
525     *   <li> <b>Default Value:</b> 0
526     *   <li> <b>Units:</b> rotations per second
527     * </ul>
528     * 
529     * Default Rates:
530     * <ul>
531     *   <li> <b>CAN 2.0:</b> 100.0 Hz
532     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
533     * </ul>
534     * <p>
535     * This refreshes and returns a cached StatusSignal object.
536     * 
537     * @return Velocity Status Signal Object
538     */
539    public StatusSignal<AngularVelocity> getVelocity()
540    {
541        return getVelocity(true);
542    }
543    
544    /**
545     * Velocity of the device.
546     * 
547     * <ul>
548     *   <li> <b>Minimum Value:</b> -512.0
549     *   <li> <b>Maximum Value:</b> 511.998046875
550     *   <li> <b>Default Value:</b> 0
551     *   <li> <b>Units:</b> rotations per second
552     * </ul>
553     * 
554     * Default Rates:
555     * <ul>
556     *   <li> <b>CAN 2.0:</b> 100.0 Hz
557     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
558     * </ul>
559     * <p>
560     * This refreshes and returns a cached StatusSignal object.
561     * 
562     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
563     * @return Velocity Status Signal Object
564     */
565    public StatusSignal<AngularVelocity> getVelocity(boolean refresh)
566    {
567        @SuppressWarnings("unchecked")
568        var retval = super.lookupStatusSignal(SpnValue.CANcoder_Velocity.value, AngularVelocity.class, val -> RotationsPerSecond.of(val), "Velocity", true, refresh);
569        return retval;
570    }
571        
572    /**
573     * Position of the device. This is initialized to the absolute
574     * position on boot.
575     * 
576     * <ul>
577     *   <li> <b>Minimum Value:</b> -16384.0
578     *   <li> <b>Maximum Value:</b> 16383.999755859375
579     *   <li> <b>Default Value:</b> 0
580     *   <li> <b>Units:</b> rotations
581     * </ul>
582     * 
583     * Default Rates:
584     * <ul>
585     *   <li> <b>CAN 2.0:</b> 100.0 Hz
586     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
587     * </ul>
588     * <p>
589     * This refreshes and returns a cached StatusSignal object.
590     * 
591     * @return Position Status Signal Object
592     */
593    public StatusSignal<Angle> getPosition()
594    {
595        return getPosition(true);
596    }
597    
598    /**
599     * Position of the device. This is initialized to the absolute
600     * position on boot.
601     * 
602     * <ul>
603     *   <li> <b>Minimum Value:</b> -16384.0
604     *   <li> <b>Maximum Value:</b> 16383.999755859375
605     *   <li> <b>Default Value:</b> 0
606     *   <li> <b>Units:</b> rotations
607     * </ul>
608     * 
609     * Default Rates:
610     * <ul>
611     *   <li> <b>CAN 2.0:</b> 100.0 Hz
612     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
613     * </ul>
614     * <p>
615     * This refreshes and returns a cached StatusSignal object.
616     * 
617     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
618     * @return Position Status Signal Object
619     */
620    public StatusSignal<Angle> getPosition(boolean refresh)
621    {
622        @SuppressWarnings("unchecked")
623        var retval = super.lookupStatusSignal(SpnValue.CANcoder_Position.value, Angle.class, val -> Rotations.of(val), "Position", true, refresh);
624        return retval;
625    }
626        
627    /**
628     * Absolute Position of the device. The possible range is documented
629     * below; however, the exact expected range is determined by the
630     * AbsoluteSensorDiscontinuityPoint. This position is only affected by
631     * the MagnetSensor configs.
632     * 
633     * <ul>
634     *   <li> <b>Minimum Value:</b> -1.0
635     *   <li> <b>Maximum Value:</b> 0.999755859375
636     *   <li> <b>Default Value:</b> 0
637     *   <li> <b>Units:</b> rotations
638     * </ul>
639     * 
640     * Default Rates:
641     * <ul>
642     *   <li> <b>CAN 2.0:</b> 100.0 Hz
643     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
644     * </ul>
645     * <p>
646     * This refreshes and returns a cached StatusSignal object.
647     * 
648     * @return AbsolutePosition Status Signal Object
649     */
650    public StatusSignal<Angle> getAbsolutePosition()
651    {
652        return getAbsolutePosition(true);
653    }
654    
655    /**
656     * Absolute Position of the device. The possible range is documented
657     * below; however, the exact expected range is determined by the
658     * AbsoluteSensorDiscontinuityPoint. This position is only affected by
659     * the MagnetSensor configs.
660     * 
661     * <ul>
662     *   <li> <b>Minimum Value:</b> -1.0
663     *   <li> <b>Maximum Value:</b> 0.999755859375
664     *   <li> <b>Default Value:</b> 0
665     *   <li> <b>Units:</b> rotations
666     * </ul>
667     * 
668     * Default Rates:
669     * <ul>
670     *   <li> <b>CAN 2.0:</b> 100.0 Hz
671     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
672     * </ul>
673     * <p>
674     * This refreshes and returns a cached StatusSignal object.
675     * 
676     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
677     * @return AbsolutePosition Status Signal Object
678     */
679    public StatusSignal<Angle> getAbsolutePosition(boolean refresh)
680    {
681        @SuppressWarnings("unchecked")
682        var retval = super.lookupStatusSignal(SpnValue.CANcoder_AbsPosition.value, Angle.class, val -> Rotations.of(val), "AbsolutePosition", true, refresh);
683        return retval;
684    }
685        
686    /**
687     * The unfiltered velocity reported by CANcoder.
688     * <p>
689     * This is the unfiltered velocity reported by CANcoder. This signal
690     * does not use the fusing algorithm.
691     * 
692     * <ul>
693     *   <li> <b>Minimum Value:</b> -8000.0
694     *   <li> <b>Maximum Value:</b> 7999.755859375
695     *   <li> <b>Default Value:</b> 0
696     *   <li> <b>Units:</b> rotations per second
697     * </ul>
698     * 
699     * Default Rates:
700     * <ul>
701     *   <li> <b>CAN 2.0:</b> 4.0 Hz
702     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
703     * </ul>
704     * <p>
705     * This refreshes and returns a cached StatusSignal object.
706     * 
707     * @return UnfilteredVelocity Status Signal Object
708     */
709    public StatusSignal<AngularVelocity> getUnfilteredVelocity()
710    {
711        return getUnfilteredVelocity(true);
712    }
713    
714    /**
715     * The unfiltered velocity reported by CANcoder.
716     * <p>
717     * This is the unfiltered velocity reported by CANcoder. This signal
718     * does not use the fusing algorithm.
719     * 
720     * <ul>
721     *   <li> <b>Minimum Value:</b> -8000.0
722     *   <li> <b>Maximum Value:</b> 7999.755859375
723     *   <li> <b>Default Value:</b> 0
724     *   <li> <b>Units:</b> rotations per second
725     * </ul>
726     * 
727     * Default Rates:
728     * <ul>
729     *   <li> <b>CAN 2.0:</b> 4.0 Hz
730     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
731     * </ul>
732     * <p>
733     * This refreshes and returns a cached StatusSignal object.
734     * 
735     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
736     * @return UnfilteredVelocity Status Signal Object
737     */
738    public StatusSignal<AngularVelocity> getUnfilteredVelocity(boolean refresh)
739    {
740        @SuppressWarnings("unchecked")
741        var retval = super.lookupStatusSignal(SpnValue.CANCoder_RawVel.value, AngularVelocity.class, val -> RotationsPerSecond.of(val), "UnfilteredVelocity", true, refresh);
742        return retval;
743    }
744        
745    /**
746     * The relative position reported by the CANcoder since boot.
747     * <p>
748     * This is the total displacement reported by CANcoder since power up.
749     * This signal is relative and is not influenced by the fusing
750     * algorithm.
751     * 
752     * <ul>
753     *   <li> <b>Minimum Value:</b> -16384.0
754     *   <li> <b>Maximum Value:</b> 16383.999755859375
755     *   <li> <b>Default Value:</b> 0
756     *   <li> <b>Units:</b> rotations
757     * </ul>
758     * 
759     * Default Rates:
760     * <ul>
761     *   <li> <b>CAN 2.0:</b> 4.0 Hz
762     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
763     * </ul>
764     * <p>
765     * This refreshes and returns a cached StatusSignal object.
766     * 
767     * @return PositionSinceBoot Status Signal Object
768     */
769    public StatusSignal<Angle> getPositionSinceBoot()
770    {
771        return getPositionSinceBoot(true);
772    }
773    
774    /**
775     * The relative position reported by the CANcoder since boot.
776     * <p>
777     * This is the total displacement reported by CANcoder since power up.
778     * This signal is relative and is not influenced by the fusing
779     * algorithm.
780     * 
781     * <ul>
782     *   <li> <b>Minimum Value:</b> -16384.0
783     *   <li> <b>Maximum Value:</b> 16383.999755859375
784     *   <li> <b>Default Value:</b> 0
785     *   <li> <b>Units:</b> rotations
786     * </ul>
787     * 
788     * Default Rates:
789     * <ul>
790     *   <li> <b>CAN 2.0:</b> 4.0 Hz
791     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
792     * </ul>
793     * <p>
794     * This refreshes and returns a cached StatusSignal object.
795     * 
796     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
797     * @return PositionSinceBoot Status Signal Object
798     */
799    public StatusSignal<Angle> getPositionSinceBoot(boolean refresh)
800    {
801        @SuppressWarnings("unchecked")
802        var retval = super.lookupStatusSignal(SpnValue.CANCoder_RawPos.value, Angle.class, val -> Rotations.of(val), "PositionSinceBoot", true, refresh);
803        return retval;
804    }
805        
806    /**
807     * Measured supply voltage to the CANcoder.
808     * 
809     * <ul>
810     *   <li> <b>Minimum Value:</b> 4
811     *   <li> <b>Maximum Value:</b> 16.75
812     *   <li> <b>Default Value:</b> 4
813     *   <li> <b>Units:</b> V
814     * </ul>
815     * 
816     * Default Rates:
817     * <ul>
818     *   <li> <b>CAN 2.0:</b> 4.0 Hz
819     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
820     * </ul>
821     * <p>
822     * This refreshes and returns a cached StatusSignal object.
823     * 
824     * @return SupplyVoltage Status Signal Object
825     */
826    public StatusSignal<Voltage> getSupplyVoltage()
827    {
828        return getSupplyVoltage(true);
829    }
830    
831    /**
832     * Measured supply voltage to the CANcoder.
833     * 
834     * <ul>
835     *   <li> <b>Minimum Value:</b> 4
836     *   <li> <b>Maximum Value:</b> 16.75
837     *   <li> <b>Default Value:</b> 4
838     *   <li> <b>Units:</b> V
839     * </ul>
840     * 
841     * Default Rates:
842     * <ul>
843     *   <li> <b>CAN 2.0:</b> 4.0 Hz
844     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
845     * </ul>
846     * <p>
847     * This refreshes and returns a cached StatusSignal object.
848     * 
849     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
850     * @return SupplyVoltage Status Signal Object
851     */
852    public StatusSignal<Voltage> getSupplyVoltage(boolean refresh)
853    {
854        @SuppressWarnings("unchecked")
855        var retval = super.lookupStatusSignal(SpnValue.CANCoder_SupplyVoltage.value, Voltage.class, val -> Volts.of(val), "SupplyVoltage", true, refresh);
856        return retval;
857    }
858        
859    /**
860     * Magnet health as measured by CANcoder.
861     * <p>
862     * Red indicates too close or too far, Orange is adequate but with
863     * reduced accuracy, green is ideal. Invalid means the accuracy cannot
864     * be determined.
865     * 
866     * 
867     * Default Rates:
868     * <ul>
869     *   <li> <b>CAN 2.0:</b> 4.0 Hz
870     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
871     * </ul>
872     * <p>
873     * This refreshes and returns a cached StatusSignal object.
874     * 
875     * @return MagnetHealth Status Signal Object
876     */
877    public StatusSignal<MagnetHealthValue> getMagnetHealth()
878    {
879        return getMagnetHealth(true);
880    }
881    
882    /**
883     * Magnet health as measured by CANcoder.
884     * <p>
885     * Red indicates too close or too far, Orange is adequate but with
886     * reduced accuracy, green is ideal. Invalid means the accuracy cannot
887     * be determined.
888     * 
889     * 
890     * Default Rates:
891     * <ul>
892     *   <li> <b>CAN 2.0:</b> 4.0 Hz
893     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
894     * </ul>
895     * <p>
896     * This refreshes and returns a cached StatusSignal object.
897     * 
898     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
899     * @return MagnetHealth Status Signal Object
900     */
901    public StatusSignal<MagnetHealthValue> getMagnetHealth(boolean refresh)
902    {
903        @SuppressWarnings("unchecked")
904        var retval = super.lookupStatusSignal(SpnValue.CANcoder_MagHealth.value, MagnetHealthValue.class, val -> MagnetHealthValue.valueOf((int)val), "MagnetHealth", true, refresh);
905        return retval;
906    }
907        
908    /**
909     * Whether the device is Phoenix Pro licensed.
910     * 
911     * <ul>
912     *   <li> <b>Default Value:</b> False
913     * </ul>
914     * 
915     * Default Rates:
916     * <ul>
917     *   <li> <b>CAN:</b> 4.0 Hz
918     * </ul>
919     * <p>
920     * This refreshes and returns a cached StatusSignal object.
921     * 
922     * @return IsProLicensed Status Signal Object
923     */
924    public StatusSignal<Boolean> getIsProLicensed()
925    {
926        return getIsProLicensed(true);
927    }
928    
929    /**
930     * Whether the device is Phoenix Pro licensed.
931     * 
932     * <ul>
933     *   <li> <b>Default Value:</b> False
934     * </ul>
935     * 
936     * Default Rates:
937     * <ul>
938     *   <li> <b>CAN:</b> 4.0 Hz
939     * </ul>
940     * <p>
941     * This refreshes and returns a cached StatusSignal object.
942     * 
943     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
944     * @return IsProLicensed Status Signal Object
945     */
946    public StatusSignal<Boolean> getIsProLicensed(boolean refresh)
947    {
948        @SuppressWarnings("unchecked")
949        var retval = super.lookupStatusSignal(SpnValue.Version_IsProLicensed.value, Boolean.class, val -> val != 0, "IsProLicensed", true, refresh);
950        return retval;
951    }
952        
953    /**
954     * Hardware fault occurred
955     * 
956     * <ul>
957     *   <li> <b>Default Value:</b> False
958     * </ul>
959     * 
960     * Default Rates:
961     * <ul>
962     *   <li> <b>CAN:</b> 4.0 Hz
963     * </ul>
964     * <p>
965     * This refreshes and returns a cached StatusSignal object.
966     * 
967     * @return Fault_Hardware Status Signal Object
968     */
969    public StatusSignal<Boolean> getFault_Hardware()
970    {
971        return getFault_Hardware(true);
972    }
973    
974    /**
975     * Hardware fault occurred
976     * 
977     * <ul>
978     *   <li> <b>Default Value:</b> False
979     * </ul>
980     * 
981     * Default Rates:
982     * <ul>
983     *   <li> <b>CAN:</b> 4.0 Hz
984     * </ul>
985     * <p>
986     * This refreshes and returns a cached StatusSignal object.
987     * 
988     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
989     * @return Fault_Hardware Status Signal Object
990     */
991    public StatusSignal<Boolean> getFault_Hardware(boolean refresh)
992    {
993        @SuppressWarnings("unchecked")
994        var retval = super.lookupStatusSignal(SpnValue.Fault_Hardware.value, Boolean.class, val -> val != 0, "Fault_Hardware", true, refresh);
995        return retval;
996    }
997        
998    /**
999     * Hardware fault occurred
1000     * 
1001     * <ul>
1002     *   <li> <b>Default Value:</b> False
1003     * </ul>
1004     * 
1005     * Default Rates:
1006     * <ul>
1007     *   <li> <b>CAN:</b> 4.0 Hz
1008     * </ul>
1009     * <p>
1010     * This refreshes and returns a cached StatusSignal object.
1011     * 
1012     * @return StickyFault_Hardware Status Signal Object
1013     */
1014    public StatusSignal<Boolean> getStickyFault_Hardware()
1015    {
1016        return getStickyFault_Hardware(true);
1017    }
1018    
1019    /**
1020     * Hardware fault occurred
1021     * 
1022     * <ul>
1023     *   <li> <b>Default Value:</b> False
1024     * </ul>
1025     * 
1026     * Default Rates:
1027     * <ul>
1028     *   <li> <b>CAN:</b> 4.0 Hz
1029     * </ul>
1030     * <p>
1031     * This refreshes and returns a cached StatusSignal object.
1032     * 
1033     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1034     * @return StickyFault_Hardware Status Signal Object
1035     */
1036    public StatusSignal<Boolean> getStickyFault_Hardware(boolean refresh)
1037    {
1038        @SuppressWarnings("unchecked")
1039        var retval = super.lookupStatusSignal(SpnValue.StickyFault_Hardware.value, Boolean.class, val -> val != 0, "StickyFault_Hardware", true, refresh);
1040        return retval;
1041    }
1042        
1043    /**
1044     * Device supply voltage dropped to near brownout levels
1045     * 
1046     * <ul>
1047     *   <li> <b>Default Value:</b> False
1048     * </ul>
1049     * 
1050     * Default Rates:
1051     * <ul>
1052     *   <li> <b>CAN:</b> 4.0 Hz
1053     * </ul>
1054     * <p>
1055     * This refreshes and returns a cached StatusSignal object.
1056     * 
1057     * @return Fault_Undervoltage Status Signal Object
1058     */
1059    public StatusSignal<Boolean> getFault_Undervoltage()
1060    {
1061        return getFault_Undervoltage(true);
1062    }
1063    
1064    /**
1065     * Device supply voltage dropped to near brownout levels
1066     * 
1067     * <ul>
1068     *   <li> <b>Default Value:</b> False
1069     * </ul>
1070     * 
1071     * Default Rates:
1072     * <ul>
1073     *   <li> <b>CAN:</b> 4.0 Hz
1074     * </ul>
1075     * <p>
1076     * This refreshes and returns a cached StatusSignal object.
1077     * 
1078     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1079     * @return Fault_Undervoltage Status Signal Object
1080     */
1081    public StatusSignal<Boolean> getFault_Undervoltage(boolean refresh)
1082    {
1083        @SuppressWarnings("unchecked")
1084        var retval = super.lookupStatusSignal(SpnValue.Fault_Undervoltage.value, Boolean.class, val -> val != 0, "Fault_Undervoltage", true, refresh);
1085        return retval;
1086    }
1087        
1088    /**
1089     * Device supply voltage dropped to near brownout levels
1090     * 
1091     * <ul>
1092     *   <li> <b>Default Value:</b> False
1093     * </ul>
1094     * 
1095     * Default Rates:
1096     * <ul>
1097     *   <li> <b>CAN:</b> 4.0 Hz
1098     * </ul>
1099     * <p>
1100     * This refreshes and returns a cached StatusSignal object.
1101     * 
1102     * @return StickyFault_Undervoltage Status Signal Object
1103     */
1104    public StatusSignal<Boolean> getStickyFault_Undervoltage()
1105    {
1106        return getStickyFault_Undervoltage(true);
1107    }
1108    
1109    /**
1110     * Device supply voltage dropped to near brownout levels
1111     * 
1112     * <ul>
1113     *   <li> <b>Default Value:</b> False
1114     * </ul>
1115     * 
1116     * Default Rates:
1117     * <ul>
1118     *   <li> <b>CAN:</b> 4.0 Hz
1119     * </ul>
1120     * <p>
1121     * This refreshes and returns a cached StatusSignal object.
1122     * 
1123     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1124     * @return StickyFault_Undervoltage Status Signal Object
1125     */
1126    public StatusSignal<Boolean> getStickyFault_Undervoltage(boolean refresh)
1127    {
1128        @SuppressWarnings("unchecked")
1129        var retval = super.lookupStatusSignal(SpnValue.StickyFault_Undervoltage.value, Boolean.class, val -> val != 0, "StickyFault_Undervoltage", true, refresh);
1130        return retval;
1131    }
1132        
1133    /**
1134     * Device boot while detecting the enable signal
1135     * 
1136     * <ul>
1137     *   <li> <b>Default Value:</b> False
1138     * </ul>
1139     * 
1140     * Default Rates:
1141     * <ul>
1142     *   <li> <b>CAN:</b> 4.0 Hz
1143     * </ul>
1144     * <p>
1145     * This refreshes and returns a cached StatusSignal object.
1146     * 
1147     * @return Fault_BootDuringEnable Status Signal Object
1148     */
1149    public StatusSignal<Boolean> getFault_BootDuringEnable()
1150    {
1151        return getFault_BootDuringEnable(true);
1152    }
1153    
1154    /**
1155     * Device boot while detecting the enable signal
1156     * 
1157     * <ul>
1158     *   <li> <b>Default Value:</b> False
1159     * </ul>
1160     * 
1161     * Default Rates:
1162     * <ul>
1163     *   <li> <b>CAN:</b> 4.0 Hz
1164     * </ul>
1165     * <p>
1166     * This refreshes and returns a cached StatusSignal object.
1167     * 
1168     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1169     * @return Fault_BootDuringEnable Status Signal Object
1170     */
1171    public StatusSignal<Boolean> getFault_BootDuringEnable(boolean refresh)
1172    {
1173        @SuppressWarnings("unchecked")
1174        var retval = super.lookupStatusSignal(SpnValue.Fault_BootDuringEnable.value, Boolean.class, val -> val != 0, "Fault_BootDuringEnable", true, refresh);
1175        return retval;
1176    }
1177        
1178    /**
1179     * Device boot while detecting the enable signal
1180     * 
1181     * <ul>
1182     *   <li> <b>Default Value:</b> False
1183     * </ul>
1184     * 
1185     * Default Rates:
1186     * <ul>
1187     *   <li> <b>CAN:</b> 4.0 Hz
1188     * </ul>
1189     * <p>
1190     * This refreshes and returns a cached StatusSignal object.
1191     * 
1192     * @return StickyFault_BootDuringEnable Status Signal Object
1193     */
1194    public StatusSignal<Boolean> getStickyFault_BootDuringEnable()
1195    {
1196        return getStickyFault_BootDuringEnable(true);
1197    }
1198    
1199    /**
1200     * Device boot while detecting the enable signal
1201     * 
1202     * <ul>
1203     *   <li> <b>Default Value:</b> False
1204     * </ul>
1205     * 
1206     * Default Rates:
1207     * <ul>
1208     *   <li> <b>CAN:</b> 4.0 Hz
1209     * </ul>
1210     * <p>
1211     * This refreshes and returns a cached StatusSignal object.
1212     * 
1213     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1214     * @return StickyFault_BootDuringEnable Status Signal Object
1215     */
1216    public StatusSignal<Boolean> getStickyFault_BootDuringEnable(boolean refresh)
1217    {
1218        @SuppressWarnings("unchecked")
1219        var retval = super.lookupStatusSignal(SpnValue.StickyFault_BootDuringEnable.value, Boolean.class, val -> val != 0, "StickyFault_BootDuringEnable", true, refresh);
1220        return retval;
1221    }
1222        
1223    /**
1224     * An unlicensed feature is in use, device may not behave as expected.
1225     * 
1226     * <ul>
1227     *   <li> <b>Default Value:</b> False
1228     * </ul>
1229     * 
1230     * Default Rates:
1231     * <ul>
1232     *   <li> <b>CAN:</b> 4.0 Hz
1233     * </ul>
1234     * <p>
1235     * This refreshes and returns a cached StatusSignal object.
1236     * 
1237     * @return Fault_UnlicensedFeatureInUse Status Signal Object
1238     */
1239    public StatusSignal<Boolean> getFault_UnlicensedFeatureInUse()
1240    {
1241        return getFault_UnlicensedFeatureInUse(true);
1242    }
1243    
1244    /**
1245     * An unlicensed feature is in use, device may not behave as expected.
1246     * 
1247     * <ul>
1248     *   <li> <b>Default Value:</b> False
1249     * </ul>
1250     * 
1251     * Default Rates:
1252     * <ul>
1253     *   <li> <b>CAN:</b> 4.0 Hz
1254     * </ul>
1255     * <p>
1256     * This refreshes and returns a cached StatusSignal object.
1257     * 
1258     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1259     * @return Fault_UnlicensedFeatureInUse Status Signal Object
1260     */
1261    public StatusSignal<Boolean> getFault_UnlicensedFeatureInUse(boolean refresh)
1262    {
1263        @SuppressWarnings("unchecked")
1264        var retval = super.lookupStatusSignal(SpnValue.Fault_UnlicensedFeatureInUse.value, Boolean.class, val -> val != 0, "Fault_UnlicensedFeatureInUse", true, refresh);
1265        return retval;
1266    }
1267        
1268    /**
1269     * An unlicensed feature is in use, device may not behave as expected.
1270     * 
1271     * <ul>
1272     *   <li> <b>Default Value:</b> False
1273     * </ul>
1274     * 
1275     * Default Rates:
1276     * <ul>
1277     *   <li> <b>CAN:</b> 4.0 Hz
1278     * </ul>
1279     * <p>
1280     * This refreshes and returns a cached StatusSignal object.
1281     * 
1282     * @return StickyFault_UnlicensedFeatureInUse Status Signal Object
1283     */
1284    public StatusSignal<Boolean> getStickyFault_UnlicensedFeatureInUse()
1285    {
1286        return getStickyFault_UnlicensedFeatureInUse(true);
1287    }
1288    
1289    /**
1290     * An unlicensed feature is in use, device may not behave as expected.
1291     * 
1292     * <ul>
1293     *   <li> <b>Default Value:</b> False
1294     * </ul>
1295     * 
1296     * Default Rates:
1297     * <ul>
1298     *   <li> <b>CAN:</b> 4.0 Hz
1299     * </ul>
1300     * <p>
1301     * This refreshes and returns a cached StatusSignal object.
1302     * 
1303     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1304     * @return StickyFault_UnlicensedFeatureInUse Status Signal Object
1305     */
1306    public StatusSignal<Boolean> getStickyFault_UnlicensedFeatureInUse(boolean refresh)
1307    {
1308        @SuppressWarnings("unchecked")
1309        var retval = super.lookupStatusSignal(SpnValue.StickyFault_UnlicensedFeatureInUse.value, Boolean.class, val -> val != 0, "StickyFault_UnlicensedFeatureInUse", true, refresh);
1310        return retval;
1311    }
1312        
1313    /**
1314     * The magnet distance is not correct or magnet is missing
1315     * 
1316     * <ul>
1317     *   <li> <b>Default Value:</b> False
1318     * </ul>
1319     * 
1320     * Default Rates:
1321     * <ul>
1322     *   <li> <b>CAN:</b> 4.0 Hz
1323     * </ul>
1324     * <p>
1325     * This refreshes and returns a cached StatusSignal object.
1326     * 
1327     * @return Fault_BadMagnet Status Signal Object
1328     */
1329    public StatusSignal<Boolean> getFault_BadMagnet()
1330    {
1331        return getFault_BadMagnet(true);
1332    }
1333    
1334    /**
1335     * The magnet distance is not correct or magnet is missing
1336     * 
1337     * <ul>
1338     *   <li> <b>Default Value:</b> False
1339     * </ul>
1340     * 
1341     * Default Rates:
1342     * <ul>
1343     *   <li> <b>CAN:</b> 4.0 Hz
1344     * </ul>
1345     * <p>
1346     * This refreshes and returns a cached StatusSignal object.
1347     * 
1348     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1349     * @return Fault_BadMagnet Status Signal Object
1350     */
1351    public StatusSignal<Boolean> getFault_BadMagnet(boolean refresh)
1352    {
1353        @SuppressWarnings("unchecked")
1354        var retval = super.lookupStatusSignal(SpnValue.Fault_CANCODER_BadMagnet.value, Boolean.class, val -> val != 0, "Fault_BadMagnet", true, refresh);
1355        return retval;
1356    }
1357        
1358    /**
1359     * The magnet distance is not correct or magnet is missing
1360     * 
1361     * <ul>
1362     *   <li> <b>Default Value:</b> False
1363     * </ul>
1364     * 
1365     * Default Rates:
1366     * <ul>
1367     *   <li> <b>CAN:</b> 4.0 Hz
1368     * </ul>
1369     * <p>
1370     * This refreshes and returns a cached StatusSignal object.
1371     * 
1372     * @return StickyFault_BadMagnet Status Signal Object
1373     */
1374    public StatusSignal<Boolean> getStickyFault_BadMagnet()
1375    {
1376        return getStickyFault_BadMagnet(true);
1377    }
1378    
1379    /**
1380     * The magnet distance is not correct or magnet is missing
1381     * 
1382     * <ul>
1383     *   <li> <b>Default Value:</b> False
1384     * </ul>
1385     * 
1386     * Default Rates:
1387     * <ul>
1388     *   <li> <b>CAN:</b> 4.0 Hz
1389     * </ul>
1390     * <p>
1391     * This refreshes and returns a cached StatusSignal object.
1392     * 
1393     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1394     * @return StickyFault_BadMagnet Status Signal Object
1395     */
1396    public StatusSignal<Boolean> getStickyFault_BadMagnet(boolean refresh)
1397    {
1398        @SuppressWarnings("unchecked")
1399        var retval = super.lookupStatusSignal(SpnValue.StickyFault_CANCODER_BadMagnet.value, Boolean.class, val -> val != 0, "StickyFault_BadMagnet", true, refresh);
1400        return retval;
1401    }
1402
1403    
1404
1405    /**
1406     * Control device with generic control request object.
1407     * <p>
1408     * User must make sure the specified object is castable to a valid control request,
1409     * otherwise this function will fail at run-time and return the NotSupported StatusCode
1410     *
1411     * @param request Control object to request of the device
1412     * @return Status Code of the request, 0 is OK
1413     */
1414    public StatusCode setControl(ControlRequest request)
1415    {
1416        
1417        return StatusCode.NotSupported;
1418    }
1419
1420    
1421    /**
1422     * Sets the current position of the device.
1423     * <p>
1424     * This will wait up to 0.100 seconds (100ms) by default.
1425     * 
1426     * @param newValue Value to set to. Units are in rotations.
1427     * @return StatusCode of the set command
1428     */
1429    public StatusCode setPosition(double newValue) {
1430        return setPosition(newValue, 0.100);
1431    }
1432    /**
1433     * Sets the current position of the device.
1434     * 
1435     * @param newValue Value to set to. Units are in rotations.
1436     * @param timeoutSeconds Maximum time to wait up to in seconds.
1437     * @return StatusCode of the set command
1438     */
1439    public StatusCode setPosition(double newValue, double timeoutSeconds) {
1440        return getConfigurator().setPosition(newValue, timeoutSeconds);
1441    }
1442    
1443    /**
1444     * Sets the current position of the device.
1445     * <p>
1446     * This will wait up to 0.100 seconds (100ms) by default.
1447     * 
1448     * @param newValue Value to set to. Units are in rotations.
1449     * @return StatusCode of the set command
1450     */
1451    public StatusCode setPosition(Angle newValue) {
1452        return setPosition(newValue.in(Rotations));
1453    }
1454    /**
1455     * Sets the current position of the device.
1456     * 
1457     * @param newValue Value to set to. Units are in rotations.
1458     * @param timeoutSeconds Maximum time to wait up to in seconds.
1459     * @return StatusCode of the set command
1460     */
1461    public StatusCode setPosition(Angle newValue, double timeoutSeconds) {
1462        return setPosition(newValue.in(Rotations), timeoutSeconds);
1463    }
1464    
1465    /**
1466     * Clear the sticky faults in the device.
1467     * <p>
1468     * This typically has no impact on the device functionality.  Instead,
1469     * it just clears telemetry faults that are accessible via API and
1470     * Tuner Self-Test.
1471     * <p>
1472     * This will wait up to 0.100 seconds (100ms) by default.
1473     * 
1474     * @return StatusCode of the set command
1475     */
1476    public StatusCode clearStickyFaults() {
1477        return clearStickyFaults(0.100);
1478    }
1479    /**
1480     * Clear the sticky faults in the device.
1481     * <p>
1482     * This typically has no impact on the device functionality.  Instead,
1483     * it just clears telemetry faults that are accessible via API and
1484     * Tuner Self-Test.
1485     * 
1486     * @param timeoutSeconds Maximum time to wait up to in seconds.
1487     * @return StatusCode of the set command
1488     */
1489    public StatusCode clearStickyFaults(double timeoutSeconds) {
1490        return getConfigurator().clearStickyFaults(timeoutSeconds);
1491    }
1492    
1493    /**
1494     * Clear sticky fault: Hardware fault occurred
1495     * <p>
1496     * This will wait up to 0.100 seconds (100ms) by default.
1497     * 
1498     * @return StatusCode of the set command
1499     */
1500    public StatusCode clearStickyFault_Hardware() {
1501        return clearStickyFault_Hardware(0.100);
1502    }
1503    /**
1504     * Clear sticky fault: Hardware fault occurred
1505     * 
1506     * @param timeoutSeconds Maximum time to wait up to in seconds.
1507     * @return StatusCode of the set command
1508     */
1509    public StatusCode clearStickyFault_Hardware(double timeoutSeconds) {
1510        return getConfigurator().clearStickyFault_Hardware(timeoutSeconds);
1511    }
1512    
1513    /**
1514     * Clear sticky fault: Device supply voltage dropped to near brownout
1515     * levels
1516     * <p>
1517     * This will wait up to 0.100 seconds (100ms) by default.
1518     * 
1519     * @return StatusCode of the set command
1520     */
1521    public StatusCode clearStickyFault_Undervoltage() {
1522        return clearStickyFault_Undervoltage(0.100);
1523    }
1524    /**
1525     * Clear sticky fault: Device supply voltage dropped to near brownout
1526     * levels
1527     * 
1528     * @param timeoutSeconds Maximum time to wait up to in seconds.
1529     * @return StatusCode of the set command
1530     */
1531    public StatusCode clearStickyFault_Undervoltage(double timeoutSeconds) {
1532        return getConfigurator().clearStickyFault_Undervoltage(timeoutSeconds);
1533    }
1534    
1535    /**
1536     * Clear sticky fault: Device boot while detecting the enable signal
1537     * <p>
1538     * This will wait up to 0.100 seconds (100ms) by default.
1539     * 
1540     * @return StatusCode of the set command
1541     */
1542    public StatusCode clearStickyFault_BootDuringEnable() {
1543        return clearStickyFault_BootDuringEnable(0.100);
1544    }
1545    /**
1546     * Clear sticky fault: Device boot while detecting the enable signal
1547     * 
1548     * @param timeoutSeconds Maximum time to wait up to in seconds.
1549     * @return StatusCode of the set command
1550     */
1551    public StatusCode clearStickyFault_BootDuringEnable(double timeoutSeconds) {
1552        return getConfigurator().clearStickyFault_BootDuringEnable(timeoutSeconds);
1553    }
1554    
1555    /**
1556     * Clear sticky fault: An unlicensed feature is in use, device may not
1557     * behave as expected.
1558     * <p>
1559     * This will wait up to 0.100 seconds (100ms) by default.
1560     * 
1561     * @return StatusCode of the set command
1562     */
1563    public StatusCode clearStickyFault_UnlicensedFeatureInUse() {
1564        return clearStickyFault_UnlicensedFeatureInUse(0.100);
1565    }
1566    /**
1567     * Clear sticky fault: An unlicensed feature is in use, device may not
1568     * behave as expected.
1569     * 
1570     * @param timeoutSeconds Maximum time to wait up to in seconds.
1571     * @return StatusCode of the set command
1572     */
1573    public StatusCode clearStickyFault_UnlicensedFeatureInUse(double timeoutSeconds) {
1574        return getConfigurator().clearStickyFault_UnlicensedFeatureInUse(timeoutSeconds);
1575    }
1576    
1577    /**
1578     * Clear sticky fault: The magnet distance is not correct or magnet is
1579     * missing
1580     * <p>
1581     * This will wait up to 0.100 seconds (100ms) by default.
1582     * 
1583     * @return StatusCode of the set command
1584     */
1585    public StatusCode clearStickyFault_BadMagnet() {
1586        return clearStickyFault_BadMagnet(0.100);
1587    }
1588    /**
1589     * Clear sticky fault: The magnet distance is not correct or magnet is
1590     * missing
1591     * 
1592     * @param timeoutSeconds Maximum time to wait up to in seconds.
1593     * @return StatusCode of the set command
1594     */
1595    public StatusCode clearStickyFault_BadMagnet(double timeoutSeconds) {
1596        return getConfigurator().clearStickyFault_BadMagnet(timeoutSeconds);
1597    }
1598}
1599