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.CANdiSimState;
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 CTR Electronics' CANdi™ branded device, a device that integrates
025 * digital signals into the existing CAN bus network.
026 * 
027 * <pre>
028 * // Constants used in CANdi construction
029 * final int kCANdiId = 0;
030 * final String kCANdiCANbus = "canivore";
031 * 
032 * // Construct the CANdi
033 * CANdi CANdi = new CANdi(kCANdiId, kCANdiCANbus);
034 * 
035 * // Configure the CANdi for basic use
036 * CANdiConfiguration configs = new CANdiConfiguration();
037 * 
038 * // Write these configs to the CANdi
039 * CANdi.getConfigurator().apply(configs);
040 * 
041 * // Get Pin 1
042 * var p1State = CANdi.getP1State();
043 * 
044 * // Refresh and print these values
045 * System.out.println("Pin 1 is " + p1State.refresh().toString());
046 * </pre>
047 */
048public class CoreCANdi extends ParentDevice
049{
050    private CANdiConfigurator _configurator;
051
052    /**
053     * Constructs a new CANdi object.
054     * <p>
055     * Constructs the device using the default CAN bus for the system:
056     * <ul>
057     *   <li>"rio" on roboRIO
058     *   <li>"can0" on Linux
059     *   <li>"*" on Windows
060     * </ul>
061     *
062     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
063     */
064    public CoreCANdi(int deviceId)
065    {
066        this(deviceId, "");
067    }
068
069    /**
070     * Constructs a new CANdi object.
071     *
072     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
073     * @param canbus      Name of the CAN bus this device is on. Possible CAN bus strings are:
074     *                    <ul>
075     *                      <li>"rio" for the native roboRIO CAN bus
076     *                      <li>CANivore name or serial number
077     *                      <li>SocketCAN interface (non-FRC Linux only)
078     *                      <li>"*" for any CANivore seen by the program
079     *                      <li>empty string (default) to select the default for the system:
080     *                      <ul>
081     *                        <li>"rio" on roboRIO
082     *                        <li>"can0" on Linux
083     *                        <li>"*" on Windows
084     *                      </ul>
085     *                    </ul>
086     */
087    public CoreCANdi(int deviceId, String canbus)
088    {
089        super(deviceId, "candi", canbus);
090        _configurator = new CANdiConfigurator(this.deviceIdentifier);
091        PlatformJNI.JNI_SimCreate(DeviceType.P6_CANdiType.value, deviceId);
092    }
093
094    /**
095     * Constructs a new CANdi object.
096     *
097     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
098     * @param canbus      The CAN bus this device is on.
099     */
100    public CoreCANdi(int deviceId, CANBus canbus)
101    {
102        this(deviceId, canbus.getName());
103    }
104
105    /**
106     * Gets the configurator to use with this device's configs
107     *
108     * @return Configurator for this object
109     */
110    public CANdiConfigurator getConfigurator()
111    {
112        return this._configurator;
113    }
114
115
116    private CANdiSimState _simState = null;
117    /**
118     * Get the simulation state for this device.
119     * <p>
120     * This function reuses an allocated simulation state
121     * object, so it is safe to call this function multiple
122     * times in a robot loop.
123     *
124     * @return Simulation state
125     */
126    public CANdiSimState getSimState() {
127        if (_simState == null)
128            _simState = new CANdiSimState(this);
129        return _simState;
130    }
131
132
133        
134    /**
135     * App Major Version number.
136     * 
137     * <ul>
138     *   <li> <b>Minimum Value:</b> 0
139     *   <li> <b>Maximum Value:</b> 255
140     *   <li> <b>Default Value:</b> 0
141     *   <li> <b>Units:</b> 
142     * </ul>
143     * 
144     * Default Rates:
145     * <ul>
146     *   <li> <b>CAN:</b> 4.0 Hz
147     * </ul>
148     * <p>
149     * This refreshes and returns a cached StatusSignal object.
150     * 
151     * @return VersionMajor Status Signal Object
152     */
153    public StatusSignal<Integer> getVersionMajor()
154    {
155        return getVersionMajor(true);
156    }
157    
158    /**
159     * App Major Version number.
160     * 
161     * <ul>
162     *   <li> <b>Minimum Value:</b> 0
163     *   <li> <b>Maximum Value:</b> 255
164     *   <li> <b>Default Value:</b> 0
165     *   <li> <b>Units:</b> 
166     * </ul>
167     * 
168     * Default Rates:
169     * <ul>
170     *   <li> <b>CAN:</b> 4.0 Hz
171     * </ul>
172     * <p>
173     * This refreshes and returns a cached StatusSignal object.
174     * 
175     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
176     * @return VersionMajor Status Signal Object
177     */
178    public StatusSignal<Integer> getVersionMajor(boolean refresh)
179    {
180        @SuppressWarnings("unchecked")
181        var retval = super.lookupStatusSignal(SpnValue.Version_Major.value, Integer.class, val -> (int)val, "VersionMajor", false, refresh);
182        return retval;
183    }
184        
185    /**
186     * App Minor Version number.
187     * 
188     * <ul>
189     *   <li> <b>Minimum Value:</b> 0
190     *   <li> <b>Maximum Value:</b> 255
191     *   <li> <b>Default Value:</b> 0
192     *   <li> <b>Units:</b> 
193     * </ul>
194     * 
195     * Default Rates:
196     * <ul>
197     *   <li> <b>CAN:</b> 4.0 Hz
198     * </ul>
199     * <p>
200     * This refreshes and returns a cached StatusSignal object.
201     * 
202     * @return VersionMinor Status Signal Object
203     */
204    public StatusSignal<Integer> getVersionMinor()
205    {
206        return getVersionMinor(true);
207    }
208    
209    /**
210     * App Minor Version number.
211     * 
212     * <ul>
213     *   <li> <b>Minimum Value:</b> 0
214     *   <li> <b>Maximum Value:</b> 255
215     *   <li> <b>Default Value:</b> 0
216     *   <li> <b>Units:</b> 
217     * </ul>
218     * 
219     * Default Rates:
220     * <ul>
221     *   <li> <b>CAN:</b> 4.0 Hz
222     * </ul>
223     * <p>
224     * This refreshes and returns a cached StatusSignal object.
225     * 
226     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
227     * @return VersionMinor Status Signal Object
228     */
229    public StatusSignal<Integer> getVersionMinor(boolean refresh)
230    {
231        @SuppressWarnings("unchecked")
232        var retval = super.lookupStatusSignal(SpnValue.Version_Minor.value, Integer.class, val -> (int)val, "VersionMinor", false, refresh);
233        return retval;
234    }
235        
236    /**
237     * App Bugfix Version number.
238     * 
239     * <ul>
240     *   <li> <b>Minimum Value:</b> 0
241     *   <li> <b>Maximum Value:</b> 255
242     *   <li> <b>Default Value:</b> 0
243     *   <li> <b>Units:</b> 
244     * </ul>
245     * 
246     * Default Rates:
247     * <ul>
248     *   <li> <b>CAN:</b> 4.0 Hz
249     * </ul>
250     * <p>
251     * This refreshes and returns a cached StatusSignal object.
252     * 
253     * @return VersionBugfix Status Signal Object
254     */
255    public StatusSignal<Integer> getVersionBugfix()
256    {
257        return getVersionBugfix(true);
258    }
259    
260    /**
261     * App Bugfix Version number.
262     * 
263     * <ul>
264     *   <li> <b>Minimum Value:</b> 0
265     *   <li> <b>Maximum Value:</b> 255
266     *   <li> <b>Default Value:</b> 0
267     *   <li> <b>Units:</b> 
268     * </ul>
269     * 
270     * Default Rates:
271     * <ul>
272     *   <li> <b>CAN:</b> 4.0 Hz
273     * </ul>
274     * <p>
275     * This refreshes and returns a cached StatusSignal object.
276     * 
277     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
278     * @return VersionBugfix Status Signal Object
279     */
280    public StatusSignal<Integer> getVersionBugfix(boolean refresh)
281    {
282        @SuppressWarnings("unchecked")
283        var retval = super.lookupStatusSignal(SpnValue.Version_Bugfix.value, Integer.class, val -> (int)val, "VersionBugfix", false, refresh);
284        return retval;
285    }
286        
287    /**
288     * App Build Version number.
289     * 
290     * <ul>
291     *   <li> <b>Minimum Value:</b> 0
292     *   <li> <b>Maximum Value:</b> 255
293     *   <li> <b>Default Value:</b> 0
294     *   <li> <b>Units:</b> 
295     * </ul>
296     * 
297     * Default Rates:
298     * <ul>
299     *   <li> <b>CAN:</b> 4.0 Hz
300     * </ul>
301     * <p>
302     * This refreshes and returns a cached StatusSignal object.
303     * 
304     * @return VersionBuild Status Signal Object
305     */
306    public StatusSignal<Integer> getVersionBuild()
307    {
308        return getVersionBuild(true);
309    }
310    
311    /**
312     * App Build Version number.
313     * 
314     * <ul>
315     *   <li> <b>Minimum Value:</b> 0
316     *   <li> <b>Maximum Value:</b> 255
317     *   <li> <b>Default Value:</b> 0
318     *   <li> <b>Units:</b> 
319     * </ul>
320     * 
321     * Default Rates:
322     * <ul>
323     *   <li> <b>CAN:</b> 4.0 Hz
324     * </ul>
325     * <p>
326     * This refreshes and returns a cached StatusSignal object.
327     * 
328     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
329     * @return VersionBuild Status Signal Object
330     */
331    public StatusSignal<Integer> getVersionBuild(boolean refresh)
332    {
333        @SuppressWarnings("unchecked")
334        var retval = super.lookupStatusSignal(SpnValue.Version_Build.value, Integer.class, val -> (int)val, "VersionBuild", false, refresh);
335        return retval;
336    }
337        
338    /**
339     * Full Version of firmware in device.  The format is a four byte
340     * value.
341     * 
342     * <ul>
343     *   <li> <b>Minimum Value:</b> 0
344     *   <li> <b>Maximum Value:</b> 4294967295
345     *   <li> <b>Default Value:</b> 0
346     *   <li> <b>Units:</b> 
347     * </ul>
348     * 
349     * Default Rates:
350     * <ul>
351     *   <li> <b>CAN:</b> 4.0 Hz
352     * </ul>
353     * <p>
354     * This refreshes and returns a cached StatusSignal object.
355     * 
356     * @return Version Status Signal Object
357     */
358    public StatusSignal<Integer> getVersion()
359    {
360        return getVersion(true);
361    }
362    
363    /**
364     * Full Version of firmware in device.  The format is a four byte
365     * value.
366     * 
367     * <ul>
368     *   <li> <b>Minimum Value:</b> 0
369     *   <li> <b>Maximum Value:</b> 4294967295
370     *   <li> <b>Default Value:</b> 0
371     *   <li> <b>Units:</b> 
372     * </ul>
373     * 
374     * Default Rates:
375     * <ul>
376     *   <li> <b>CAN:</b> 4.0 Hz
377     * </ul>
378     * <p>
379     * This refreshes and returns a cached StatusSignal object.
380     * 
381     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
382     * @return Version Status Signal Object
383     */
384    public StatusSignal<Integer> getVersion(boolean refresh)
385    {
386        @SuppressWarnings("unchecked")
387        var retval = super.lookupStatusSignal(SpnValue.Version_Full.value, Integer.class, val -> (int)val, "Version", false, refresh);
388        return retval;
389    }
390        
391    /**
392     * Integer representing all fault flags reported by the device.
393     * <p>
394     * These are device specific and are not used directly in typical
395     * applications. Use the signal specific GetFault_*() methods instead.
396     * 
397     * <ul>
398     *   <li> <b>Minimum Value:</b> 0
399     *   <li> <b>Maximum Value:</b> 4294967295
400     *   <li> <b>Default Value:</b> 0
401     *   <li> <b>Units:</b> 
402     * </ul>
403     * 
404     * Default Rates:
405     * <ul>
406     *   <li> <b>CAN:</b> 4.0 Hz
407     * </ul>
408     * <p>
409     * This refreshes and returns a cached StatusSignal object.
410     * 
411     * @return FaultField Status Signal Object
412     */
413    public StatusSignal<Integer> getFaultField()
414    {
415        return getFaultField(true);
416    }
417    
418    /**
419     * Integer representing all fault flags reported by the device.
420     * <p>
421     * These are device specific and are not used directly in typical
422     * applications. Use the signal specific GetFault_*() methods instead.
423     * 
424     * <ul>
425     *   <li> <b>Minimum Value:</b> 0
426     *   <li> <b>Maximum Value:</b> 4294967295
427     *   <li> <b>Default Value:</b> 0
428     *   <li> <b>Units:</b> 
429     * </ul>
430     * 
431     * Default Rates:
432     * <ul>
433     *   <li> <b>CAN:</b> 4.0 Hz
434     * </ul>
435     * <p>
436     * This refreshes and returns a cached StatusSignal object.
437     * 
438     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
439     * @return FaultField Status Signal Object
440     */
441    public StatusSignal<Integer> getFaultField(boolean refresh)
442    {
443        @SuppressWarnings("unchecked")
444        var retval = super.lookupStatusSignal(SpnValue.AllFaults.value, Integer.class, val -> (int)val, "FaultField", true, refresh);
445        return retval;
446    }
447        
448    /**
449     * Integer representing all (persistent) sticky fault flags reported
450     * by the device.
451     * <p>
452     * These are device specific and are not used directly in typical
453     * applications. Use the signal specific GetStickyFault_*() methods
454     * instead.
455     * 
456     * <ul>
457     *   <li> <b>Minimum Value:</b> 0
458     *   <li> <b>Maximum Value:</b> 4294967295
459     *   <li> <b>Default Value:</b> 0
460     *   <li> <b>Units:</b> 
461     * </ul>
462     * 
463     * Default Rates:
464     * <ul>
465     *   <li> <b>CAN:</b> 4.0 Hz
466     * </ul>
467     * <p>
468     * This refreshes and returns a cached StatusSignal object.
469     * 
470     * @return StickyFaultField Status Signal Object
471     */
472    public StatusSignal<Integer> getStickyFaultField()
473    {
474        return getStickyFaultField(true);
475    }
476    
477    /**
478     * Integer representing all (persistent) sticky fault flags reported
479     * by the device.
480     * <p>
481     * These are device specific and are not used directly in typical
482     * applications. Use the signal specific GetStickyFault_*() methods
483     * instead.
484     * 
485     * <ul>
486     *   <li> <b>Minimum Value:</b> 0
487     *   <li> <b>Maximum Value:</b> 4294967295
488     *   <li> <b>Default Value:</b> 0
489     *   <li> <b>Units:</b> 
490     * </ul>
491     * 
492     * Default Rates:
493     * <ul>
494     *   <li> <b>CAN:</b> 4.0 Hz
495     * </ul>
496     * <p>
497     * This refreshes and returns a cached StatusSignal object.
498     * 
499     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
500     * @return StickyFaultField Status Signal Object
501     */
502    public StatusSignal<Integer> getStickyFaultField(boolean refresh)
503    {
504        @SuppressWarnings("unchecked")
505        var retval = super.lookupStatusSignal(SpnValue.AllStickyFaults.value, Integer.class, val -> (int)val, "StickyFaultField", true, refresh);
506        return retval;
507    }
508        
509    /**
510     * Whether the device is Phoenix Pro licensed.
511     * 
512     * <ul>
513     *   <li> <b>Default Value:</b> False
514     * </ul>
515     * 
516     * Default Rates:
517     * <ul>
518     *   <li> <b>CAN:</b> 4.0 Hz
519     * </ul>
520     * <p>
521     * This refreshes and returns a cached StatusSignal object.
522     * 
523     * @return IsProLicensed Status Signal Object
524     */
525    public StatusSignal<Boolean> getIsProLicensed()
526    {
527        return getIsProLicensed(true);
528    }
529    
530    /**
531     * Whether the device is Phoenix Pro licensed.
532     * 
533     * <ul>
534     *   <li> <b>Default Value:</b> False
535     * </ul>
536     * 
537     * Default Rates:
538     * <ul>
539     *   <li> <b>CAN:</b> 4.0 Hz
540     * </ul>
541     * <p>
542     * This refreshes and returns a cached StatusSignal object.
543     * 
544     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
545     * @return IsProLicensed Status Signal Object
546     */
547    public StatusSignal<Boolean> getIsProLicensed(boolean refresh)
548    {
549        @SuppressWarnings("unchecked")
550        var retval = super.lookupStatusSignal(SpnValue.Version_IsProLicensed.value, Boolean.class, val -> val != 0, "IsProLicensed", true, refresh);
551        return retval;
552    }
553        
554    /**
555     * State of the Signal 1 input (S1IN).
556     * 
557     * 
558     * Default Rates:
559     * <ul>
560     *   <li> <b>CAN 2.0:</b> 100.0 Hz
561     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
562     * </ul>
563     * <p>
564     * This refreshes and returns a cached StatusSignal object.
565     * 
566     * @return S1State Status Signal Object
567     */
568    public StatusSignal<S1StateValue> getS1State()
569    {
570        return getS1State(true);
571    }
572    
573    /**
574     * State of the Signal 1 input (S1IN).
575     * 
576     * 
577     * Default Rates:
578     * <ul>
579     *   <li> <b>CAN 2.0:</b> 100.0 Hz
580     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
581     * </ul>
582     * <p>
583     * This refreshes and returns a cached StatusSignal object.
584     * 
585     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
586     * @return S1State Status Signal Object
587     */
588    public StatusSignal<S1StateValue> getS1State(boolean refresh)
589    {
590        @SuppressWarnings("unchecked")
591        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pin1State.value, S1StateValue.class, val -> S1StateValue.valueOf((int)val), "S1State", true, refresh);
592        return retval;
593    }
594        
595    /**
596     * State of the Signal 2 input (S2IN).
597     * 
598     * 
599     * Default Rates:
600     * <ul>
601     *   <li> <b>CAN 2.0:</b> 100.0 Hz
602     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
603     * </ul>
604     * <p>
605     * This refreshes and returns a cached StatusSignal object.
606     * 
607     * @return S2State Status Signal Object
608     */
609    public StatusSignal<S2StateValue> getS2State()
610    {
611        return getS2State(true);
612    }
613    
614    /**
615     * State of the Signal 2 input (S2IN).
616     * 
617     * 
618     * Default Rates:
619     * <ul>
620     *   <li> <b>CAN 2.0:</b> 100.0 Hz
621     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
622     * </ul>
623     * <p>
624     * This refreshes and returns a cached StatusSignal object.
625     * 
626     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
627     * @return S2State Status Signal Object
628     */
629    public StatusSignal<S2StateValue> getS2State(boolean refresh)
630    {
631        @SuppressWarnings("unchecked")
632        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pin2State.value, S2StateValue.class, val -> S2StateValue.valueOf((int)val), "S2State", true, refresh);
633        return retval;
634    }
635        
636    /**
637     * Position from a quadrature encoder sensor connected to both the
638     * S1IN and S2IN inputs.
639     * 
640     * <ul>
641     *   <li> <b>Minimum Value:</b> -16384.0
642     *   <li> <b>Maximum Value:</b> 16383.999755859375
643     *   <li> <b>Default Value:</b> 0
644     *   <li> <b>Units:</b> rotations
645     * </ul>
646     * 
647     * Default Rates:
648     * <ul>
649     *   <li> <b>CAN 2.0:</b> 20.0 Hz
650     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
651     * </ul>
652     * <p>
653     * This refreshes and returns a cached StatusSignal object.
654     * 
655     * @return QuadraturePosition Status Signal Object
656     */
657    public StatusSignal<Angle> getQuadraturePosition()
658    {
659        return getQuadraturePosition(true);
660    }
661    
662    /**
663     * Position from a quadrature encoder sensor connected to both the
664     * S1IN and S2IN inputs.
665     * 
666     * <ul>
667     *   <li> <b>Minimum Value:</b> -16384.0
668     *   <li> <b>Maximum Value:</b> 16383.999755859375
669     *   <li> <b>Default Value:</b> 0
670     *   <li> <b>Units:</b> rotations
671     * </ul>
672     * 
673     * Default Rates:
674     * <ul>
675     *   <li> <b>CAN 2.0:</b> 20.0 Hz
676     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
677     * </ul>
678     * <p>
679     * This refreshes and returns a cached StatusSignal object.
680     * 
681     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
682     * @return QuadraturePosition Status Signal Object
683     */
684    public StatusSignal<Angle> getQuadraturePosition(boolean refresh)
685    {
686        @SuppressWarnings("unchecked")
687        var retval = super.lookupStatusSignal(SpnValue.CANdi_QuadPosition.value, Angle.class, val -> Rotations.of(val), "QuadraturePosition", true, refresh);
688        return retval;
689    }
690        
691    /**
692     * Measured rise to rise time of the PWM signal at the S1 input of the
693     * CTR Electronics' CANdi™.
694     * 
695     * <ul>
696     *   <li> <b>Minimum Value:</b> 0
697     *   <li> <b>Maximum Value:</b> 131070
698     *   <li> <b>Default Value:</b> 0
699     *   <li> <b>Units:</b> us
700     * </ul>
701     * 
702     * Default Rates:
703     * <ul>
704     *   <li> <b>CAN 2.0:</b> 20.0 Hz
705     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
706     * </ul>
707     * <p>
708     * This refreshes and returns a cached StatusSignal object.
709     * 
710     * @return PWM1RiseToRise Status Signal Object
711     */
712    public StatusSignal<Time> getPWM1RiseToRise()
713    {
714        return getPWM1RiseToRise(true);
715    }
716    
717    /**
718     * Measured rise to rise time of the PWM signal at the S1 input of the
719     * CTR Electronics' CANdi™.
720     * 
721     * <ul>
722     *   <li> <b>Minimum Value:</b> 0
723     *   <li> <b>Maximum Value:</b> 131070
724     *   <li> <b>Default Value:</b> 0
725     *   <li> <b>Units:</b> us
726     * </ul>
727     * 
728     * Default Rates:
729     * <ul>
730     *   <li> <b>CAN 2.0:</b> 20.0 Hz
731     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
732     * </ul>
733     * <p>
734     * This refreshes and returns a cached StatusSignal object.
735     * 
736     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
737     * @return PWM1RiseToRise Status Signal Object
738     */
739    public StatusSignal<Time> getPWM1RiseToRise(boolean refresh)
740    {
741        @SuppressWarnings("unchecked")
742        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pwm1_RiseToRise.value, Time.class, val -> Microseconds.of(val), "PWM1RiseToRise", true, refresh);
743        return retval;
744    }
745        
746    /**
747     * Measured position of the PWM sensor at the S1 input of the CTR
748     * Electronics' CANdi™.
749     * 
750     * <ul>
751     *   <li> <b>Minimum Value:</b> -16384.0
752     *   <li> <b>Maximum Value:</b> 16383.999755859375
753     *   <li> <b>Default Value:</b> 0
754     *   <li> <b>Units:</b> rotations
755     * </ul>
756     * 
757     * Default Rates:
758     * <ul>
759     *   <li> <b>CAN 2.0:</b> 20.0 Hz
760     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
761     * </ul>
762     * <p>
763     * This refreshes and returns a cached StatusSignal object.
764     * 
765     * @return PWM1Position Status Signal Object
766     */
767    public StatusSignal<Angle> getPWM1Position()
768    {
769        return getPWM1Position(true);
770    }
771    
772    /**
773     * Measured position of the PWM sensor at the S1 input of the CTR
774     * Electronics' CANdi™.
775     * 
776     * <ul>
777     *   <li> <b>Minimum Value:</b> -16384.0
778     *   <li> <b>Maximum Value:</b> 16383.999755859375
779     *   <li> <b>Default Value:</b> 0
780     *   <li> <b>Units:</b> rotations
781     * </ul>
782     * 
783     * Default Rates:
784     * <ul>
785     *   <li> <b>CAN 2.0:</b> 20.0 Hz
786     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
787     * </ul>
788     * <p>
789     * This refreshes and returns a cached StatusSignal object.
790     * 
791     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
792     * @return PWM1Position Status Signal Object
793     */
794    public StatusSignal<Angle> getPWM1Position(boolean refresh)
795    {
796        @SuppressWarnings("unchecked")
797        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pwm1_Position.value, Angle.class, val -> Rotations.of(val), "PWM1Position", true, refresh);
798        return retval;
799    }
800        
801    /**
802     * Measured velocity of the PWM sensor at the S1 input of the CTR
803     * Electronics' CANdi™.
804     * 
805     * <ul>
806     *   <li> <b>Minimum Value:</b> -512.0
807     *   <li> <b>Maximum Value:</b> 511.998046875
808     *   <li> <b>Default Value:</b> 0
809     *   <li> <b>Units:</b> rotations per second
810     * </ul>
811     * 
812     * Default Rates:
813     * <ul>
814     *   <li> <b>CAN 2.0:</b> 20.0 Hz
815     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
816     * </ul>
817     * <p>
818     * This refreshes and returns a cached StatusSignal object.
819     * 
820     * @return PWM1Velocity Status Signal Object
821     */
822    public StatusSignal<AngularVelocity> getPWM1Velocity()
823    {
824        return getPWM1Velocity(true);
825    }
826    
827    /**
828     * Measured velocity of the PWM sensor at the S1 input of the CTR
829     * Electronics' CANdi™.
830     * 
831     * <ul>
832     *   <li> <b>Minimum Value:</b> -512.0
833     *   <li> <b>Maximum Value:</b> 511.998046875
834     *   <li> <b>Default Value:</b> 0
835     *   <li> <b>Units:</b> rotations per second
836     * </ul>
837     * 
838     * Default Rates:
839     * <ul>
840     *   <li> <b>CAN 2.0:</b> 20.0 Hz
841     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
842     * </ul>
843     * <p>
844     * This refreshes and returns a cached StatusSignal object.
845     * 
846     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
847     * @return PWM1Velocity Status Signal Object
848     */
849    public StatusSignal<AngularVelocity> getPWM1Velocity(boolean refresh)
850    {
851        @SuppressWarnings("unchecked")
852        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pwm1_Velocity.value, AngularVelocity.class, val -> RotationsPerSecond.of(val), "PWM1Velocity", true, refresh);
853        return retval;
854    }
855        
856    /**
857     * Measured rise to rise time of the PWM signal at the S2 input of the
858     * CTR Electronics' CANdi™.
859     * 
860     * <ul>
861     *   <li> <b>Minimum Value:</b> 0
862     *   <li> <b>Maximum Value:</b> 131070
863     *   <li> <b>Default Value:</b> 0
864     *   <li> <b>Units:</b> us
865     * </ul>
866     * 
867     * Default Rates:
868     * <ul>
869     *   <li> <b>CAN 2.0:</b> 20.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 PWM2RiseToRise Status Signal Object
876     */
877    public StatusSignal<Time> getPWM2RiseToRise()
878    {
879        return getPWM2RiseToRise(true);
880    }
881    
882    /**
883     * Measured rise to rise time of the PWM signal at the S2 input of the
884     * CTR Electronics' CANdi™.
885     * 
886     * <ul>
887     *   <li> <b>Minimum Value:</b> 0
888     *   <li> <b>Maximum Value:</b> 131070
889     *   <li> <b>Default Value:</b> 0
890     *   <li> <b>Units:</b> us
891     * </ul>
892     * 
893     * Default Rates:
894     * <ul>
895     *   <li> <b>CAN 2.0:</b> 20.0 Hz
896     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
897     * </ul>
898     * <p>
899     * This refreshes and returns a cached StatusSignal object.
900     * 
901     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
902     * @return PWM2RiseToRise Status Signal Object
903     */
904    public StatusSignal<Time> getPWM2RiseToRise(boolean refresh)
905    {
906        @SuppressWarnings("unchecked")
907        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pwm2_RiseToRise.value, Time.class, val -> Microseconds.of(val), "PWM2RiseToRise", true, refresh);
908        return retval;
909    }
910        
911    /**
912     * Measured position of the PWM sensor at the S2 input of the CTR
913     * Electronics' CANdi™.
914     * 
915     * <ul>
916     *   <li> <b>Minimum Value:</b> -16384.0
917     *   <li> <b>Maximum Value:</b> 16383.999755859375
918     *   <li> <b>Default Value:</b> 0
919     *   <li> <b>Units:</b> rotations
920     * </ul>
921     * 
922     * Default Rates:
923     * <ul>
924     *   <li> <b>CAN 2.0:</b> 20.0 Hz
925     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
926     * </ul>
927     * <p>
928     * This refreshes and returns a cached StatusSignal object.
929     * 
930     * @return PWM2Position Status Signal Object
931     */
932    public StatusSignal<Angle> getPWM2Position()
933    {
934        return getPWM2Position(true);
935    }
936    
937    /**
938     * Measured position of the PWM sensor at the S2 input of the CTR
939     * Electronics' CANdi™.
940     * 
941     * <ul>
942     *   <li> <b>Minimum Value:</b> -16384.0
943     *   <li> <b>Maximum Value:</b> 16383.999755859375
944     *   <li> <b>Default Value:</b> 0
945     *   <li> <b>Units:</b> rotations
946     * </ul>
947     * 
948     * Default Rates:
949     * <ul>
950     *   <li> <b>CAN 2.0:</b> 20.0 Hz
951     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
952     * </ul>
953     * <p>
954     * This refreshes and returns a cached StatusSignal object.
955     * 
956     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
957     * @return PWM2Position Status Signal Object
958     */
959    public StatusSignal<Angle> getPWM2Position(boolean refresh)
960    {
961        @SuppressWarnings("unchecked")
962        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pwm2_Position.value, Angle.class, val -> Rotations.of(val), "PWM2Position", true, refresh);
963        return retval;
964    }
965        
966    /**
967     * True when the CANdi™ is in overcurrent protection mode. This may be
968     * due to either overcurrent or a short-circuit.
969     * 
970     * <ul>
971     *   <li> <b>Default Value:</b> 0
972     * </ul>
973     * 
974     * Default Rates:
975     * <ul>
976     *   <li> <b>CAN 2.0:</b> 100.0 Hz
977     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
978     * </ul>
979     * <p>
980     * This refreshes and returns a cached StatusSignal object.
981     * 
982     * @return Overcurrent Status Signal Object
983     */
984    public StatusSignal<Boolean> getOvercurrent()
985    {
986        return getOvercurrent(true);
987    }
988    
989    /**
990     * True when the CANdi™ is in overcurrent protection mode. This may be
991     * due to either overcurrent or a short-circuit.
992     * 
993     * <ul>
994     *   <li> <b>Default Value:</b> 0
995     * </ul>
996     * 
997     * Default Rates:
998     * <ul>
999     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1000     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1001     * </ul>
1002     * <p>
1003     * This refreshes and returns a cached StatusSignal object.
1004     * 
1005     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1006     * @return Overcurrent Status Signal Object
1007     */
1008    public StatusSignal<Boolean> getOvercurrent(boolean refresh)
1009    {
1010        @SuppressWarnings("unchecked")
1011        var retval = super.lookupStatusSignal(SpnValue.CANdi_Overcurrent.value, Boolean.class, val -> val != 0, "Overcurrent", true, refresh);
1012        return retval;
1013    }
1014        
1015    /**
1016     * Measured supply voltage to the CANdi™.
1017     * 
1018     * <ul>
1019     *   <li> <b>Minimum Value:</b> 4.0
1020     *   <li> <b>Maximum Value:</b> 29.5
1021     *   <li> <b>Default Value:</b> 0
1022     *   <li> <b>Units:</b> V
1023     * </ul>
1024     * 
1025     * Default Rates:
1026     * <ul>
1027     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1028     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1029     * </ul>
1030     * <p>
1031     * This refreshes and returns a cached StatusSignal object.
1032     * 
1033     * @return SupplyVoltage Status Signal Object
1034     */
1035    public StatusSignal<Voltage> getSupplyVoltage()
1036    {
1037        return getSupplyVoltage(true);
1038    }
1039    
1040    /**
1041     * Measured supply voltage to the CANdi™.
1042     * 
1043     * <ul>
1044     *   <li> <b>Minimum Value:</b> 4.0
1045     *   <li> <b>Maximum Value:</b> 29.5
1046     *   <li> <b>Default Value:</b> 0
1047     *   <li> <b>Units:</b> V
1048     * </ul>
1049     * 
1050     * Default Rates:
1051     * <ul>
1052     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1053     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1054     * </ul>
1055     * <p>
1056     * This refreshes and returns a cached StatusSignal object.
1057     * 
1058     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1059     * @return SupplyVoltage Status Signal Object
1060     */
1061    public StatusSignal<Voltage> getSupplyVoltage(boolean refresh)
1062    {
1063        @SuppressWarnings("unchecked")
1064        var retval = super.lookupStatusSignal(SpnValue.CANdi_VSense.value, Voltage.class, val -> Volts.of(val), "SupplyVoltage", true, refresh);
1065        return retval;
1066    }
1067        
1068    /**
1069     * Measured output current. This includes both Vbat and 5V output
1070     * current.
1071     * 
1072     * <ul>
1073     *   <li> <b>Minimum Value:</b> 0.0
1074     *   <li> <b>Maximum Value:</b> 0.51
1075     *   <li> <b>Default Value:</b> 0
1076     *   <li> <b>Units:</b> A
1077     * </ul>
1078     * 
1079     * Default Rates:
1080     * <ul>
1081     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1082     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1083     * </ul>
1084     * <p>
1085     * This refreshes and returns a cached StatusSignal object.
1086     * 
1087     * @return OutputCurrent Status Signal Object
1088     */
1089    public StatusSignal<Current> getOutputCurrent()
1090    {
1091        return getOutputCurrent(true);
1092    }
1093    
1094    /**
1095     * Measured output current. This includes both Vbat and 5V output
1096     * current.
1097     * 
1098     * <ul>
1099     *   <li> <b>Minimum Value:</b> 0.0
1100     *   <li> <b>Maximum Value:</b> 0.51
1101     *   <li> <b>Default Value:</b> 0
1102     *   <li> <b>Units:</b> A
1103     * </ul>
1104     * 
1105     * Default Rates:
1106     * <ul>
1107     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1108     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1109     * </ul>
1110     * <p>
1111     * This refreshes and returns a cached StatusSignal object.
1112     * 
1113     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1114     * @return OutputCurrent Status Signal Object
1115     */
1116    public StatusSignal<Current> getOutputCurrent(boolean refresh)
1117    {
1118        @SuppressWarnings("unchecked")
1119        var retval = super.lookupStatusSignal(SpnValue.CANdi_OutputCurrent.value, Current.class, val -> Amps.of(val), "OutputCurrent", true, refresh);
1120        return retval;
1121    }
1122        
1123    /**
1124     * Measured velocity of the PWM sensor at the S2 input of the CTR
1125     * Electronics' CANdi™.
1126     * 
1127     * <ul>
1128     *   <li> <b>Minimum Value:</b> -512.0
1129     *   <li> <b>Maximum Value:</b> 511.998046875
1130     *   <li> <b>Default Value:</b> 0
1131     *   <li> <b>Units:</b> rotations per second
1132     * </ul>
1133     * 
1134     * Default Rates:
1135     * <ul>
1136     *   <li> <b>CAN 2.0:</b> 20.0 Hz
1137     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1138     * </ul>
1139     * <p>
1140     * This refreshes and returns a cached StatusSignal object.
1141     * 
1142     * @return PWM2Velocity Status Signal Object
1143     */
1144    public StatusSignal<AngularVelocity> getPWM2Velocity()
1145    {
1146        return getPWM2Velocity(true);
1147    }
1148    
1149    /**
1150     * Measured velocity of the PWM sensor at the S2 input of the CTR
1151     * Electronics' CANdi™.
1152     * 
1153     * <ul>
1154     *   <li> <b>Minimum Value:</b> -512.0
1155     *   <li> <b>Maximum Value:</b> 511.998046875
1156     *   <li> <b>Default Value:</b> 0
1157     *   <li> <b>Units:</b> rotations per second
1158     * </ul>
1159     * 
1160     * Default Rates:
1161     * <ul>
1162     *   <li> <b>CAN 2.0:</b> 20.0 Hz
1163     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
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 PWM2Velocity Status Signal Object
1170     */
1171    public StatusSignal<AngularVelocity> getPWM2Velocity(boolean refresh)
1172    {
1173        @SuppressWarnings("unchecked")
1174        var retval = super.lookupStatusSignal(SpnValue.CANdi_Pwm2_Velocity.value, AngularVelocity.class, val -> RotationsPerSecond.of(val), "PWM2Velocity", true, refresh);
1175        return retval;
1176    }
1177        
1178    /**
1179     * Velocity from a quadrature encoder sensor connected to both the
1180     * S1IN and S2IN inputs.
1181     * 
1182     * <ul>
1183     *   <li> <b>Minimum Value:</b> -512.0
1184     *   <li> <b>Maximum Value:</b> 511.998046875
1185     *   <li> <b>Default Value:</b> 0
1186     *   <li> <b>Units:</b> rotations per second
1187     * </ul>
1188     * 
1189     * Default Rates:
1190     * <ul>
1191     *   <li> <b>CAN 2.0:</b> 20.0 Hz
1192     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1193     * </ul>
1194     * <p>
1195     * This refreshes and returns a cached StatusSignal object.
1196     * 
1197     * @return QuadratureVelocity Status Signal Object
1198     */
1199    public StatusSignal<AngularVelocity> getQuadratureVelocity()
1200    {
1201        return getQuadratureVelocity(true);
1202    }
1203    
1204    /**
1205     * Velocity from a quadrature encoder sensor connected to both the
1206     * S1IN and S2IN inputs.
1207     * 
1208     * <ul>
1209     *   <li> <b>Minimum Value:</b> -512.0
1210     *   <li> <b>Maximum Value:</b> 511.998046875
1211     *   <li> <b>Default Value:</b> 0
1212     *   <li> <b>Units:</b> rotations per second
1213     * </ul>
1214     * 
1215     * Default Rates:
1216     * <ul>
1217     *   <li> <b>CAN 2.0:</b> 20.0 Hz
1218     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1219     * </ul>
1220     * <p>
1221     * This refreshes and returns a cached StatusSignal object.
1222     * 
1223     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1224     * @return QuadratureVelocity Status Signal Object
1225     */
1226    public StatusSignal<AngularVelocity> getQuadratureVelocity(boolean refresh)
1227    {
1228        @SuppressWarnings("unchecked")
1229        var retval = super.lookupStatusSignal(SpnValue.CANdi_QuadVelocity.value, AngularVelocity.class, val -> RotationsPerSecond.of(val), "QuadratureVelocity", true, refresh);
1230        return retval;
1231    }
1232        
1233    /**
1234     * True if the Signal 1 input (S1IN) matches the configured S1 Closed
1235     * State.
1236     * <p>
1237     * Configure the S1 closed state in the Digitals configuration object
1238     * to change when this is asserted.
1239     * 
1240     * <ul>
1241     *   <li> <b>Default Value:</b> False
1242     * </ul>
1243     * 
1244     * Default Rates:
1245     * <ul>
1246     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1247     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1248     * </ul>
1249     * <p>
1250     * This refreshes and returns a cached StatusSignal object.
1251     * 
1252     * @return S1Closed Status Signal Object
1253     */
1254    public StatusSignal<Boolean> getS1Closed()
1255    {
1256        return getS1Closed(true);
1257    }
1258    
1259    /**
1260     * True if the Signal 1 input (S1IN) matches the configured S1 Closed
1261     * State.
1262     * <p>
1263     * Configure the S1 closed state in the Digitals configuration object
1264     * to change when this is asserted.
1265     * 
1266     * <ul>
1267     *   <li> <b>Default Value:</b> False
1268     * </ul>
1269     * 
1270     * Default Rates:
1271     * <ul>
1272     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1273     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1274     * </ul>
1275     * <p>
1276     * This refreshes and returns a cached StatusSignal object.
1277     * 
1278     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1279     * @return S1Closed Status Signal Object
1280     */
1281    public StatusSignal<Boolean> getS1Closed(boolean refresh)
1282    {
1283        @SuppressWarnings("unchecked")
1284        var retval = super.lookupStatusSignal(SpnValue.CANdi_S1Closed.value, Boolean.class, val -> val != 0, "S1Closed", true, refresh);
1285        return retval;
1286    }
1287        
1288    /**
1289     * True if the Signal 2 input (S2IN) matches the configured S2 Closed
1290     * State.
1291     * <p>
1292     * Configure the S2 closed state in the Digitals configuration object
1293     * to change when this is asserted.
1294     * 
1295     * <ul>
1296     *   <li> <b>Default Value:</b> False
1297     * </ul>
1298     * 
1299     * Default Rates:
1300     * <ul>
1301     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1302     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1303     * </ul>
1304     * <p>
1305     * This refreshes and returns a cached StatusSignal object.
1306     * 
1307     * @return S2Closed Status Signal Object
1308     */
1309    public StatusSignal<Boolean> getS2Closed()
1310    {
1311        return getS2Closed(true);
1312    }
1313    
1314    /**
1315     * True if the Signal 2 input (S2IN) matches the configured S2 Closed
1316     * State.
1317     * <p>
1318     * Configure the S2 closed state in the Digitals configuration object
1319     * to change when this is asserted.
1320     * 
1321     * <ul>
1322     *   <li> <b>Default Value:</b> False
1323     * </ul>
1324     * 
1325     * Default Rates:
1326     * <ul>
1327     *   <li> <b>CAN 2.0:</b> 100.0 Hz
1328     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1329     * </ul>
1330     * <p>
1331     * This refreshes and returns a cached StatusSignal object.
1332     * 
1333     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1334     * @return S2Closed Status Signal Object
1335     */
1336    public StatusSignal<Boolean> getS2Closed(boolean refresh)
1337    {
1338        @SuppressWarnings("unchecked")
1339        var retval = super.lookupStatusSignal(SpnValue.CANdi_S2Closed.value, Boolean.class, val -> val != 0, "S2Closed", true, refresh);
1340        return retval;
1341    }
1342        
1343    /**
1344     * Hardware fault occurred
1345     * 
1346     * <ul>
1347     *   <li> <b>Default Value:</b> False
1348     * </ul>
1349     * 
1350     * Default Rates:
1351     * <ul>
1352     *   <li> <b>CAN:</b> 4.0 Hz
1353     * </ul>
1354     * <p>
1355     * This refreshes and returns a cached StatusSignal object.
1356     * 
1357     * @return Fault_Hardware Status Signal Object
1358     */
1359    public StatusSignal<Boolean> getFault_Hardware()
1360    {
1361        return getFault_Hardware(true);
1362    }
1363    
1364    /**
1365     * Hardware fault occurred
1366     * 
1367     * <ul>
1368     *   <li> <b>Default Value:</b> False
1369     * </ul>
1370     * 
1371     * Default Rates:
1372     * <ul>
1373     *   <li> <b>CAN:</b> 4.0 Hz
1374     * </ul>
1375     * <p>
1376     * This refreshes and returns a cached StatusSignal object.
1377     * 
1378     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1379     * @return Fault_Hardware Status Signal Object
1380     */
1381    public StatusSignal<Boolean> getFault_Hardware(boolean refresh)
1382    {
1383        @SuppressWarnings("unchecked")
1384        var retval = super.lookupStatusSignal(SpnValue.Fault_Hardware.value, Boolean.class, val -> val != 0, "Fault_Hardware", true, refresh);
1385        return retval;
1386    }
1387        
1388    /**
1389     * Hardware fault occurred
1390     * 
1391     * <ul>
1392     *   <li> <b>Default Value:</b> False
1393     * </ul>
1394     * 
1395     * Default Rates:
1396     * <ul>
1397     *   <li> <b>CAN:</b> 4.0 Hz
1398     * </ul>
1399     * <p>
1400     * This refreshes and returns a cached StatusSignal object.
1401     * 
1402     * @return StickyFault_Hardware Status Signal Object
1403     */
1404    public StatusSignal<Boolean> getStickyFault_Hardware()
1405    {
1406        return getStickyFault_Hardware(true);
1407    }
1408    
1409    /**
1410     * Hardware fault occurred
1411     * 
1412     * <ul>
1413     *   <li> <b>Default Value:</b> False
1414     * </ul>
1415     * 
1416     * Default Rates:
1417     * <ul>
1418     *   <li> <b>CAN:</b> 4.0 Hz
1419     * </ul>
1420     * <p>
1421     * This refreshes and returns a cached StatusSignal object.
1422     * 
1423     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1424     * @return StickyFault_Hardware Status Signal Object
1425     */
1426    public StatusSignal<Boolean> getStickyFault_Hardware(boolean refresh)
1427    {
1428        @SuppressWarnings("unchecked")
1429        var retval = super.lookupStatusSignal(SpnValue.StickyFault_Hardware.value, Boolean.class, val -> val != 0, "StickyFault_Hardware", true, refresh);
1430        return retval;
1431    }
1432        
1433    /**
1434     * Device supply voltage dropped to near brownout levels
1435     * 
1436     * <ul>
1437     *   <li> <b>Default Value:</b> False
1438     * </ul>
1439     * 
1440     * Default Rates:
1441     * <ul>
1442     *   <li> <b>CAN:</b> 4.0 Hz
1443     * </ul>
1444     * <p>
1445     * This refreshes and returns a cached StatusSignal object.
1446     * 
1447     * @return Fault_Undervoltage Status Signal Object
1448     */
1449    public StatusSignal<Boolean> getFault_Undervoltage()
1450    {
1451        return getFault_Undervoltage(true);
1452    }
1453    
1454    /**
1455     * Device supply voltage dropped to near brownout levels
1456     * 
1457     * <ul>
1458     *   <li> <b>Default Value:</b> False
1459     * </ul>
1460     * 
1461     * Default Rates:
1462     * <ul>
1463     *   <li> <b>CAN:</b> 4.0 Hz
1464     * </ul>
1465     * <p>
1466     * This refreshes and returns a cached StatusSignal object.
1467     * 
1468     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1469     * @return Fault_Undervoltage Status Signal Object
1470     */
1471    public StatusSignal<Boolean> getFault_Undervoltage(boolean refresh)
1472    {
1473        @SuppressWarnings("unchecked")
1474        var retval = super.lookupStatusSignal(SpnValue.Fault_Undervoltage.value, Boolean.class, val -> val != 0, "Fault_Undervoltage", true, refresh);
1475        return retval;
1476    }
1477        
1478    /**
1479     * Device supply voltage dropped to near brownout levels
1480     * 
1481     * <ul>
1482     *   <li> <b>Default Value:</b> False
1483     * </ul>
1484     * 
1485     * Default Rates:
1486     * <ul>
1487     *   <li> <b>CAN:</b> 4.0 Hz
1488     * </ul>
1489     * <p>
1490     * This refreshes and returns a cached StatusSignal object.
1491     * 
1492     * @return StickyFault_Undervoltage Status Signal Object
1493     */
1494    public StatusSignal<Boolean> getStickyFault_Undervoltage()
1495    {
1496        return getStickyFault_Undervoltage(true);
1497    }
1498    
1499    /**
1500     * Device supply voltage dropped to near brownout levels
1501     * 
1502     * <ul>
1503     *   <li> <b>Default Value:</b> False
1504     * </ul>
1505     * 
1506     * Default Rates:
1507     * <ul>
1508     *   <li> <b>CAN:</b> 4.0 Hz
1509     * </ul>
1510     * <p>
1511     * This refreshes and returns a cached StatusSignal object.
1512     * 
1513     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1514     * @return StickyFault_Undervoltage Status Signal Object
1515     */
1516    public StatusSignal<Boolean> getStickyFault_Undervoltage(boolean refresh)
1517    {
1518        @SuppressWarnings("unchecked")
1519        var retval = super.lookupStatusSignal(SpnValue.StickyFault_Undervoltage.value, Boolean.class, val -> val != 0, "StickyFault_Undervoltage", true, refresh);
1520        return retval;
1521    }
1522        
1523    /**
1524     * Device boot while detecting the enable signal
1525     * 
1526     * <ul>
1527     *   <li> <b>Default Value:</b> False
1528     * </ul>
1529     * 
1530     * Default Rates:
1531     * <ul>
1532     *   <li> <b>CAN:</b> 4.0 Hz
1533     * </ul>
1534     * <p>
1535     * This refreshes and returns a cached StatusSignal object.
1536     * 
1537     * @return Fault_BootDuringEnable Status Signal Object
1538     */
1539    public StatusSignal<Boolean> getFault_BootDuringEnable()
1540    {
1541        return getFault_BootDuringEnable(true);
1542    }
1543    
1544    /**
1545     * Device boot while detecting the enable signal
1546     * 
1547     * <ul>
1548     *   <li> <b>Default Value:</b> False
1549     * </ul>
1550     * 
1551     * Default Rates:
1552     * <ul>
1553     *   <li> <b>CAN:</b> 4.0 Hz
1554     * </ul>
1555     * <p>
1556     * This refreshes and returns a cached StatusSignal object.
1557     * 
1558     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1559     * @return Fault_BootDuringEnable Status Signal Object
1560     */
1561    public StatusSignal<Boolean> getFault_BootDuringEnable(boolean refresh)
1562    {
1563        @SuppressWarnings("unchecked")
1564        var retval = super.lookupStatusSignal(SpnValue.Fault_BootDuringEnable.value, Boolean.class, val -> val != 0, "Fault_BootDuringEnable", true, refresh);
1565        return retval;
1566    }
1567        
1568    /**
1569     * Device boot while detecting the enable signal
1570     * 
1571     * <ul>
1572     *   <li> <b>Default Value:</b> False
1573     * </ul>
1574     * 
1575     * Default Rates:
1576     * <ul>
1577     *   <li> <b>CAN:</b> 4.0 Hz
1578     * </ul>
1579     * <p>
1580     * This refreshes and returns a cached StatusSignal object.
1581     * 
1582     * @return StickyFault_BootDuringEnable Status Signal Object
1583     */
1584    public StatusSignal<Boolean> getStickyFault_BootDuringEnable()
1585    {
1586        return getStickyFault_BootDuringEnable(true);
1587    }
1588    
1589    /**
1590     * Device boot while detecting the enable signal
1591     * 
1592     * <ul>
1593     *   <li> <b>Default Value:</b> False
1594     * </ul>
1595     * 
1596     * Default Rates:
1597     * <ul>
1598     *   <li> <b>CAN:</b> 4.0 Hz
1599     * </ul>
1600     * <p>
1601     * This refreshes and returns a cached StatusSignal object.
1602     * 
1603     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1604     * @return StickyFault_BootDuringEnable Status Signal Object
1605     */
1606    public StatusSignal<Boolean> getStickyFault_BootDuringEnable(boolean refresh)
1607    {
1608        @SuppressWarnings("unchecked")
1609        var retval = super.lookupStatusSignal(SpnValue.StickyFault_BootDuringEnable.value, Boolean.class, val -> val != 0, "StickyFault_BootDuringEnable", true, refresh);
1610        return retval;
1611    }
1612        
1613    /**
1614     * An unlicensed feature is in use, device may not behave as expected.
1615     * 
1616     * <ul>
1617     *   <li> <b>Default Value:</b> False
1618     * </ul>
1619     * 
1620     * Default Rates:
1621     * <ul>
1622     *   <li> <b>CAN:</b> 4.0 Hz
1623     * </ul>
1624     * <p>
1625     * This refreshes and returns a cached StatusSignal object.
1626     * 
1627     * @return Fault_UnlicensedFeatureInUse Status Signal Object
1628     */
1629    public StatusSignal<Boolean> getFault_UnlicensedFeatureInUse()
1630    {
1631        return getFault_UnlicensedFeatureInUse(true);
1632    }
1633    
1634    /**
1635     * An unlicensed feature is in use, device may not behave as expected.
1636     * 
1637     * <ul>
1638     *   <li> <b>Default Value:</b> False
1639     * </ul>
1640     * 
1641     * Default Rates:
1642     * <ul>
1643     *   <li> <b>CAN:</b> 4.0 Hz
1644     * </ul>
1645     * <p>
1646     * This refreshes and returns a cached StatusSignal object.
1647     * 
1648     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1649     * @return Fault_UnlicensedFeatureInUse Status Signal Object
1650     */
1651    public StatusSignal<Boolean> getFault_UnlicensedFeatureInUse(boolean refresh)
1652    {
1653        @SuppressWarnings("unchecked")
1654        var retval = super.lookupStatusSignal(SpnValue.Fault_UnlicensedFeatureInUse.value, Boolean.class, val -> val != 0, "Fault_UnlicensedFeatureInUse", true, refresh);
1655        return retval;
1656    }
1657        
1658    /**
1659     * An unlicensed feature is in use, device may not behave as expected.
1660     * 
1661     * <ul>
1662     *   <li> <b>Default Value:</b> False
1663     * </ul>
1664     * 
1665     * Default Rates:
1666     * <ul>
1667     *   <li> <b>CAN:</b> 4.0 Hz
1668     * </ul>
1669     * <p>
1670     * This refreshes and returns a cached StatusSignal object.
1671     * 
1672     * @return StickyFault_UnlicensedFeatureInUse Status Signal Object
1673     */
1674    public StatusSignal<Boolean> getStickyFault_UnlicensedFeatureInUse()
1675    {
1676        return getStickyFault_UnlicensedFeatureInUse(true);
1677    }
1678    
1679    /**
1680     * An unlicensed feature is in use, device may not behave as expected.
1681     * 
1682     * <ul>
1683     *   <li> <b>Default Value:</b> False
1684     * </ul>
1685     * 
1686     * Default Rates:
1687     * <ul>
1688     *   <li> <b>CAN:</b> 4.0 Hz
1689     * </ul>
1690     * <p>
1691     * This refreshes and returns a cached StatusSignal object.
1692     * 
1693     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1694     * @return StickyFault_UnlicensedFeatureInUse Status Signal Object
1695     */
1696    public StatusSignal<Boolean> getStickyFault_UnlicensedFeatureInUse(boolean refresh)
1697    {
1698        @SuppressWarnings("unchecked")
1699        var retval = super.lookupStatusSignal(SpnValue.StickyFault_UnlicensedFeatureInUse.value, Boolean.class, val -> val != 0, "StickyFault_UnlicensedFeatureInUse", true, refresh);
1700        return retval;
1701    }
1702        
1703    /**
1704     * The CTR Electronics' CANdi™ branded device has detected a 5V fault.
1705     * This may be due to overcurrent or a short-circuit.
1706     * 
1707     * <ul>
1708     *   <li> <b>Default Value:</b> False
1709     * </ul>
1710     * 
1711     * Default Rates:
1712     * <ul>
1713     *   <li> <b>CAN:</b> 4.0 Hz
1714     * </ul>
1715     * <p>
1716     * This refreshes and returns a cached StatusSignal object.
1717     * 
1718     * @return Fault_5V Status Signal Object
1719     */
1720    public StatusSignal<Boolean> getFault_5V()
1721    {
1722        return getFault_5V(true);
1723    }
1724    
1725    /**
1726     * The CTR Electronics' CANdi™ branded device has detected a 5V fault.
1727     * This may be due to overcurrent or a short-circuit.
1728     * 
1729     * <ul>
1730     *   <li> <b>Default Value:</b> False
1731     * </ul>
1732     * 
1733     * Default Rates:
1734     * <ul>
1735     *   <li> <b>CAN:</b> 4.0 Hz
1736     * </ul>
1737     * <p>
1738     * This refreshes and returns a cached StatusSignal object.
1739     * 
1740     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1741     * @return Fault_5V Status Signal Object
1742     */
1743    public StatusSignal<Boolean> getFault_5V(boolean refresh)
1744    {
1745        @SuppressWarnings("unchecked")
1746        var retval = super.lookupStatusSignal(SpnValue.Fault_CANDI_5V.value, Boolean.class, val -> val != 0, "Fault_5V", true, refresh);
1747        return retval;
1748    }
1749        
1750    /**
1751     * The CTR Electronics' CANdi™ branded device has detected a 5V fault.
1752     * This may be due to overcurrent or a short-circuit.
1753     * 
1754     * <ul>
1755     *   <li> <b>Default Value:</b> False
1756     * </ul>
1757     * 
1758     * Default Rates:
1759     * <ul>
1760     *   <li> <b>CAN:</b> 4.0 Hz
1761     * </ul>
1762     * <p>
1763     * This refreshes and returns a cached StatusSignal object.
1764     * 
1765     * @return StickyFault_5V Status Signal Object
1766     */
1767    public StatusSignal<Boolean> getStickyFault_5V()
1768    {
1769        return getStickyFault_5V(true);
1770    }
1771    
1772    /**
1773     * The CTR Electronics' CANdi™ branded device has detected a 5V fault.
1774     * This may be due to overcurrent or a short-circuit.
1775     * 
1776     * <ul>
1777     *   <li> <b>Default Value:</b> False
1778     * </ul>
1779     * 
1780     * Default Rates:
1781     * <ul>
1782     *   <li> <b>CAN:</b> 4.0 Hz
1783     * </ul>
1784     * <p>
1785     * This refreshes and returns a cached StatusSignal object.
1786     * 
1787     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1788     * @return StickyFault_5V Status Signal Object
1789     */
1790    public StatusSignal<Boolean> getStickyFault_5V(boolean refresh)
1791    {
1792        @SuppressWarnings("unchecked")
1793        var retval = super.lookupStatusSignal(SpnValue.StickyFault_CANDI_5V.value, Boolean.class, val -> val != 0, "StickyFault_5V", true, refresh);
1794        return retval;
1795    }
1796
1797    
1798
1799    /**
1800     * Control device with generic control request object.
1801     * <p>
1802     * User must make sure the specified object is castable to a valid control request,
1803     * otherwise this function will fail at run-time and return the NotSupported StatusCode
1804     *
1805     * @param request Control object to request of the device
1806     * @return Status Code of the request, 0 is OK
1807     */
1808    public StatusCode setControl(ControlRequest request)
1809    {
1810        
1811        return StatusCode.NotSupported;
1812    }
1813
1814    
1815    /**
1816     * Sets the position of the quadrature input.
1817     * <p>
1818     * This will wait up to 0.100 seconds (100ms) by default.
1819     * 
1820     * @param newValue Value to set to. Units are in rotations.
1821     * @return StatusCode of the set command
1822     */
1823    public StatusCode setQuadraturePosition(double newValue) {
1824        return setQuadraturePosition(newValue, 0.100);
1825    }
1826    /**
1827     * Sets the position of the quadrature input.
1828     * 
1829     * @param newValue Value to set to. Units are in rotations.
1830     * @param timeoutSeconds Maximum time to wait up to in seconds.
1831     * @return StatusCode of the set command
1832     */
1833    public StatusCode setQuadraturePosition(double newValue, double timeoutSeconds) {
1834        return getConfigurator().setQuadraturePosition(newValue, timeoutSeconds);
1835    }
1836    
1837    /**
1838     * Sets the position of the quadrature input.
1839     * <p>
1840     * This will wait up to 0.100 seconds (100ms) by default.
1841     * 
1842     * @param newValue Value to set to. Units are in rotations.
1843     * @return StatusCode of the set command
1844     */
1845    public StatusCode setQuadraturePosition(Angle newValue) {
1846        return setQuadraturePosition(newValue.in(Rotations));
1847    }
1848    /**
1849     * Sets the position of the quadrature input.
1850     * 
1851     * @param newValue Value to set to. Units are in rotations.
1852     * @param timeoutSeconds Maximum time to wait up to in seconds.
1853     * @return StatusCode of the set command
1854     */
1855    public StatusCode setQuadraturePosition(Angle newValue, double timeoutSeconds) {
1856        return setQuadraturePosition(newValue.in(Rotations), timeoutSeconds);
1857    }
1858    
1859    /**
1860     * Clear the sticky faults in the device.
1861     * <p>
1862     * This typically has no impact on the device functionality.  Instead,
1863     * it just clears telemetry faults that are accessible via API and
1864     * Tuner Self-Test.
1865     * <p>
1866     * This will wait up to 0.100 seconds (100ms) by default.
1867     * 
1868     * @return StatusCode of the set command
1869     */
1870    public StatusCode clearStickyFaults() {
1871        return clearStickyFaults(0.100);
1872    }
1873    /**
1874     * Clear the sticky faults in the device.
1875     * <p>
1876     * This typically has no impact on the device functionality.  Instead,
1877     * it just clears telemetry faults that are accessible via API and
1878     * Tuner Self-Test.
1879     * 
1880     * @param timeoutSeconds Maximum time to wait up to in seconds.
1881     * @return StatusCode of the set command
1882     */
1883    public StatusCode clearStickyFaults(double timeoutSeconds) {
1884        return getConfigurator().clearStickyFaults(timeoutSeconds);
1885    }
1886    
1887    /**
1888     * Clear sticky fault: Hardware fault occurred
1889     * <p>
1890     * This will wait up to 0.100 seconds (100ms) by default.
1891     * 
1892     * @return StatusCode of the set command
1893     */
1894    public StatusCode clearStickyFault_Hardware() {
1895        return clearStickyFault_Hardware(0.100);
1896    }
1897    /**
1898     * Clear sticky fault: Hardware fault occurred
1899     * 
1900     * @param timeoutSeconds Maximum time to wait up to in seconds.
1901     * @return StatusCode of the set command
1902     */
1903    public StatusCode clearStickyFault_Hardware(double timeoutSeconds) {
1904        return getConfigurator().clearStickyFault_Hardware(timeoutSeconds);
1905    }
1906    
1907    /**
1908     * Clear sticky fault: Device supply voltage dropped to near brownout
1909     * levels
1910     * <p>
1911     * This will wait up to 0.100 seconds (100ms) by default.
1912     * 
1913     * @return StatusCode of the set command
1914     */
1915    public StatusCode clearStickyFault_Undervoltage() {
1916        return clearStickyFault_Undervoltage(0.100);
1917    }
1918    /**
1919     * Clear sticky fault: Device supply voltage dropped to near brownout
1920     * levels
1921     * 
1922     * @param timeoutSeconds Maximum time to wait up to in seconds.
1923     * @return StatusCode of the set command
1924     */
1925    public StatusCode clearStickyFault_Undervoltage(double timeoutSeconds) {
1926        return getConfigurator().clearStickyFault_Undervoltage(timeoutSeconds);
1927    }
1928    
1929    /**
1930     * Clear sticky fault: Device boot while detecting the enable signal
1931     * <p>
1932     * This will wait up to 0.100 seconds (100ms) by default.
1933     * 
1934     * @return StatusCode of the set command
1935     */
1936    public StatusCode clearStickyFault_BootDuringEnable() {
1937        return clearStickyFault_BootDuringEnable(0.100);
1938    }
1939    /**
1940     * Clear sticky fault: Device boot while detecting the enable signal
1941     * 
1942     * @param timeoutSeconds Maximum time to wait up to in seconds.
1943     * @return StatusCode of the set command
1944     */
1945    public StatusCode clearStickyFault_BootDuringEnable(double timeoutSeconds) {
1946        return getConfigurator().clearStickyFault_BootDuringEnable(timeoutSeconds);
1947    }
1948    
1949    /**
1950     * Clear sticky fault: An unlicensed feature is in use, device may not
1951     * behave as expected.
1952     * <p>
1953     * This will wait up to 0.100 seconds (100ms) by default.
1954     * 
1955     * @return StatusCode of the set command
1956     */
1957    public StatusCode clearStickyFault_UnlicensedFeatureInUse() {
1958        return clearStickyFault_UnlicensedFeatureInUse(0.100);
1959    }
1960    /**
1961     * Clear sticky fault: An unlicensed feature is in use, device may not
1962     * behave as expected.
1963     * 
1964     * @param timeoutSeconds Maximum time to wait up to in seconds.
1965     * @return StatusCode of the set command
1966     */
1967    public StatusCode clearStickyFault_UnlicensedFeatureInUse(double timeoutSeconds) {
1968        return getConfigurator().clearStickyFault_UnlicensedFeatureInUse(timeoutSeconds);
1969    }
1970    
1971    /**
1972     * Clear sticky fault: The CTR Electronics' CANdi™ branded device has
1973     * detected a 5V fault. This may be due to overcurrent or a
1974     * short-circuit.
1975     * <p>
1976     * This will wait up to 0.100 seconds (100ms) by default.
1977     * 
1978     * @return StatusCode of the set command
1979     */
1980    public StatusCode clearStickyFault_5V() {
1981        return clearStickyFault_5V(0.100);
1982    }
1983    /**
1984     * Clear sticky fault: The CTR Electronics' CANdi™ branded device has
1985     * detected a 5V fault. This may be due to overcurrent or a
1986     * short-circuit.
1987     * 
1988     * @param timeoutSeconds Maximum time to wait up to in seconds.
1989     * @return StatusCode of the set command
1990     */
1991    public StatusCode clearStickyFault_5V(double timeoutSeconds) {
1992        return getConfigurator().clearStickyFault_5V(timeoutSeconds);
1993    }
1994}
1995