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.Pigeon2SimState;
016import com.ctre.phoenix6.*;
017import com.ctre.phoenix6.spns.*;
018import edu.wpi.first.units.*;
019import edu.wpi.first.units.measure.*;
020import static edu.wpi.first.units.Units.*;
021
022/**
023 * Class description for the Pigeon 2 IMU sensor that measures orientation.
024 * 
025 * <pre>
026 * // Constants used in Pigeon2 construction
027 * final int kPigeon2Id = 0;
028 * final String kPigeon2CANbus = "canivore";
029 * 
030 * // Construct the Pigeon 2
031 * Pigeon2 pigeon = new Pigeon2(kPigeon2Id, kPigeon2CANbus);
032 * 
033 * // Configure the Pigeon2 for basic use
034 * Pigeon2Configuration configs = new Pigeon2Configuration();
035 * // This Pigeon is mounted X-up, so we should mount-pose with Pitch at 90 degrees
036 * configs.MountPose.MountPoseYaw = 0;
037 * configs.MountPose.MountPosePitch = 90;
038 * configs.MountPose.MountPoseRoll = 0;
039 * // This Pigeon has no need to trim the gyro
040 * configs.GyroTrim.GyroScalarX = 0;
041 * configs.GyroTrim.GyroScalarY = 0;
042 * configs.GyroTrim.GyroScalarZ = 0;
043 * // We want the thermal comp and no-motion cal enabled, with the compass disabled for best behavior
044 * configs.Pigeon2Features.DisableNoMotionCalibration = false;
045 * configs.Pigeon2Features.DisableTemperatureCompensation = false;
046 * configs.Pigeon2Features.EnableCompass = false;
047 * 
048 * // Write these configs to the Pigeon2
049 * pigeon.getConfigurator().apply(configs);
050 * 
051 * // Set the yaw to 0 degrees for initial use
052 * pigeon.setYaw(0);
053 * 
054 * // Get Yaw Pitch Roll StatusSignals
055 * var yaw = pigeon.getYaw();
056 * var pitch = pigeon.getPitch();
057 * var roll = pigeon.getRoll();
058 * 
059 * // Refresh and print these values
060 * System.out.println("Yaw is " + yaw.refresh().toString());
061 * System.out.println("Pitch is " + pitch.refresh().toString());
062 * System.out.println("Roll is " + roll.refresh().toString());
063 * </pre>
064 */
065public class CorePigeon2 extends ParentDevice
066{
067    private Pigeon2Configurator _configurator;
068
069    /**
070     * Constructs a new Pigeon 2 sensor object.
071     * <p>
072     * Constructs the device using the default CAN bus for the system:
073     * <ul>
074     *   <li>"rio" on roboRIO
075     *   <li>"can0" on Linux
076     *   <li>"*" on Windows
077     * </ul>
078     *
079     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
080     */
081    public CorePigeon2(int deviceId)
082    {
083        this(deviceId, "");
084    }
085
086    /**
087     * Constructs a new Pigeon 2 sensor object.
088     *
089     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
090     * @param canbus      Name of the CAN bus this device is on. Possible CAN bus strings are:
091     *                    <ul>
092     *                      <li>"rio" for the native roboRIO CAN bus
093     *                      <li>CANivore name or serial number
094     *                      <li>SocketCAN interface (non-FRC Linux only)
095     *                      <li>"*" for any CANivore seen by the program
096     *                      <li>empty string (default) to select the default for the system:
097     *                      <ul>
098     *                        <li>"rio" on roboRIO
099     *                        <li>"can0" on Linux
100     *                        <li>"*" on Windows
101     *                      </ul>
102     *                    </ul>
103     */
104    public CorePigeon2(int deviceId, String canbus)
105    {
106        super(deviceId, "pigeon 2", canbus);
107        _configurator = new Pigeon2Configurator(this.deviceIdentifier);
108        PlatformJNI.JNI_SimCreate(DeviceType.P6_Pigeon2Type.value, deviceId);
109    }
110
111    /**
112     * Constructs a new Pigeon 2 sensor object.
113     *
114     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
115     * @param canbus      The CAN bus this device is on.
116     */
117    public CorePigeon2(int deviceId, CANBus canbus)
118    {
119        this(deviceId, canbus.getName());
120    }
121
122    /**
123     * Gets the configurator to use with this device's configs
124     *
125     * @return Configurator for this object
126     */
127    public Pigeon2Configurator getConfigurator()
128    {
129        return this._configurator;
130    }
131
132
133    private Pigeon2SimState _simState = null;
134    /**
135     * Get the simulation state for this device.
136     * <p>
137     * This function reuses an allocated simulation state
138     * object, so it is safe to call this function multiple
139     * times in a robot loop.
140     *
141     * @return Simulation state
142     */
143    public Pigeon2SimState getSimState() {
144        if (_simState == null)
145            _simState = new Pigeon2SimState(this);
146        return _simState;
147    }
148
149
150        
151    /**
152     * App Major Version number.
153     * 
154     * <ul>
155     *   <li> <b>Minimum Value:</b> 0
156     *   <li> <b>Maximum Value:</b> 255
157     *   <li> <b>Default Value:</b> 0
158     *   <li> <b>Units:</b> 
159     * </ul>
160     * 
161     * Default Rates:
162     * <ul>
163     *   <li> <b>CAN:</b> 4.0 Hz
164     * </ul>
165     * <p>
166     * This refreshes and returns a cached StatusSignal object.
167     * 
168     * @return VersionMajor Status Signal Object
169     */
170    public StatusSignal<Integer> getVersionMajor()
171    {
172        return getVersionMajor(true);
173    }
174    
175    /**
176     * App Major Version number.
177     * 
178     * <ul>
179     *   <li> <b>Minimum Value:</b> 0
180     *   <li> <b>Maximum Value:</b> 255
181     *   <li> <b>Default Value:</b> 0
182     *   <li> <b>Units:</b> 
183     * </ul>
184     * 
185     * Default Rates:
186     * <ul>
187     *   <li> <b>CAN:</b> 4.0 Hz
188     * </ul>
189     * <p>
190     * This refreshes and returns a cached StatusSignal object.
191     * 
192     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
193     * @return VersionMajor Status Signal Object
194     */
195    public StatusSignal<Integer> getVersionMajor(boolean refresh)
196    {
197        @SuppressWarnings("unchecked")
198        var retval = super.lookupStatusSignal(SpnValue.Version_Major.value, Integer.class, val -> (int)val, "VersionMajor", false, refresh);
199        return retval;
200    }
201        
202    /**
203     * App Minor Version number.
204     * 
205     * <ul>
206     *   <li> <b>Minimum Value:</b> 0
207     *   <li> <b>Maximum Value:</b> 255
208     *   <li> <b>Default Value:</b> 0
209     *   <li> <b>Units:</b> 
210     * </ul>
211     * 
212     * Default Rates:
213     * <ul>
214     *   <li> <b>CAN:</b> 4.0 Hz
215     * </ul>
216     * <p>
217     * This refreshes and returns a cached StatusSignal object.
218     * 
219     * @return VersionMinor Status Signal Object
220     */
221    public StatusSignal<Integer> getVersionMinor()
222    {
223        return getVersionMinor(true);
224    }
225    
226    /**
227     * App Minor Version number.
228     * 
229     * <ul>
230     *   <li> <b>Minimum Value:</b> 0
231     *   <li> <b>Maximum Value:</b> 255
232     *   <li> <b>Default Value:</b> 0
233     *   <li> <b>Units:</b> 
234     * </ul>
235     * 
236     * Default Rates:
237     * <ul>
238     *   <li> <b>CAN:</b> 4.0 Hz
239     * </ul>
240     * <p>
241     * This refreshes and returns a cached StatusSignal object.
242     * 
243     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
244     * @return VersionMinor Status Signal Object
245     */
246    public StatusSignal<Integer> getVersionMinor(boolean refresh)
247    {
248        @SuppressWarnings("unchecked")
249        var retval = super.lookupStatusSignal(SpnValue.Version_Minor.value, Integer.class, val -> (int)val, "VersionMinor", false, refresh);
250        return retval;
251    }
252        
253    /**
254     * App Bugfix Version number.
255     * 
256     * <ul>
257     *   <li> <b>Minimum Value:</b> 0
258     *   <li> <b>Maximum Value:</b> 255
259     *   <li> <b>Default Value:</b> 0
260     *   <li> <b>Units:</b> 
261     * </ul>
262     * 
263     * Default Rates:
264     * <ul>
265     *   <li> <b>CAN:</b> 4.0 Hz
266     * </ul>
267     * <p>
268     * This refreshes and returns a cached StatusSignal object.
269     * 
270     * @return VersionBugfix Status Signal Object
271     */
272    public StatusSignal<Integer> getVersionBugfix()
273    {
274        return getVersionBugfix(true);
275    }
276    
277    /**
278     * App Bugfix Version number.
279     * 
280     * <ul>
281     *   <li> <b>Minimum Value:</b> 0
282     *   <li> <b>Maximum Value:</b> 255
283     *   <li> <b>Default Value:</b> 0
284     *   <li> <b>Units:</b> 
285     * </ul>
286     * 
287     * Default Rates:
288     * <ul>
289     *   <li> <b>CAN:</b> 4.0 Hz
290     * </ul>
291     * <p>
292     * This refreshes and returns a cached StatusSignal object.
293     * 
294     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
295     * @return VersionBugfix Status Signal Object
296     */
297    public StatusSignal<Integer> getVersionBugfix(boolean refresh)
298    {
299        @SuppressWarnings("unchecked")
300        var retval = super.lookupStatusSignal(SpnValue.Version_Bugfix.value, Integer.class, val -> (int)val, "VersionBugfix", false, refresh);
301        return retval;
302    }
303        
304    /**
305     * App Build Version number.
306     * 
307     * <ul>
308     *   <li> <b>Minimum Value:</b> 0
309     *   <li> <b>Maximum Value:</b> 255
310     *   <li> <b>Default Value:</b> 0
311     *   <li> <b>Units:</b> 
312     * </ul>
313     * 
314     * Default Rates:
315     * <ul>
316     *   <li> <b>CAN:</b> 4.0 Hz
317     * </ul>
318     * <p>
319     * This refreshes and returns a cached StatusSignal object.
320     * 
321     * @return VersionBuild Status Signal Object
322     */
323    public StatusSignal<Integer> getVersionBuild()
324    {
325        return getVersionBuild(true);
326    }
327    
328    /**
329     * App Build Version number.
330     * 
331     * <ul>
332     *   <li> <b>Minimum Value:</b> 0
333     *   <li> <b>Maximum Value:</b> 255
334     *   <li> <b>Default Value:</b> 0
335     *   <li> <b>Units:</b> 
336     * </ul>
337     * 
338     * Default Rates:
339     * <ul>
340     *   <li> <b>CAN:</b> 4.0 Hz
341     * </ul>
342     * <p>
343     * This refreshes and returns a cached StatusSignal object.
344     * 
345     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
346     * @return VersionBuild Status Signal Object
347     */
348    public StatusSignal<Integer> getVersionBuild(boolean refresh)
349    {
350        @SuppressWarnings("unchecked")
351        var retval = super.lookupStatusSignal(SpnValue.Version_Build.value, Integer.class, val -> (int)val, "VersionBuild", false, refresh);
352        return retval;
353    }
354        
355    /**
356     * Full Version of firmware in device.  The format is a four byte
357     * value.
358     * 
359     * <ul>
360     *   <li> <b>Minimum Value:</b> 0
361     *   <li> <b>Maximum Value:</b> 4294967295
362     *   <li> <b>Default Value:</b> 0
363     *   <li> <b>Units:</b> 
364     * </ul>
365     * 
366     * Default Rates:
367     * <ul>
368     *   <li> <b>CAN:</b> 4.0 Hz
369     * </ul>
370     * <p>
371     * This refreshes and returns a cached StatusSignal object.
372     * 
373     * @return Version Status Signal Object
374     */
375    public StatusSignal<Integer> getVersion()
376    {
377        return getVersion(true);
378    }
379    
380    /**
381     * Full Version of firmware in device.  The format is a four byte
382     * value.
383     * 
384     * <ul>
385     *   <li> <b>Minimum Value:</b> 0
386     *   <li> <b>Maximum Value:</b> 4294967295
387     *   <li> <b>Default Value:</b> 0
388     *   <li> <b>Units:</b> 
389     * </ul>
390     * 
391     * Default Rates:
392     * <ul>
393     *   <li> <b>CAN:</b> 4.0 Hz
394     * </ul>
395     * <p>
396     * This refreshes and returns a cached StatusSignal object.
397     * 
398     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
399     * @return Version Status Signal Object
400     */
401    public StatusSignal<Integer> getVersion(boolean refresh)
402    {
403        @SuppressWarnings("unchecked")
404        var retval = super.lookupStatusSignal(SpnValue.Version_Full.value, Integer.class, val -> (int)val, "Version", false, refresh);
405        return retval;
406    }
407        
408    /**
409     * Integer representing all fault flags reported by the device.
410     * <p>
411     * These are device specific and are not used directly in typical
412     * applications. Use the signal specific GetFault_*() methods instead.
413     * 
414     * <ul>
415     *   <li> <b>Minimum Value:</b> 0
416     *   <li> <b>Maximum Value:</b> 4294967295
417     *   <li> <b>Default Value:</b> 0
418     *   <li> <b>Units:</b> 
419     * </ul>
420     * 
421     * Default Rates:
422     * <ul>
423     *   <li> <b>CAN:</b> 4.0 Hz
424     * </ul>
425     * <p>
426     * This refreshes and returns a cached StatusSignal object.
427     * 
428     * @return FaultField Status Signal Object
429     */
430    public StatusSignal<Integer> getFaultField()
431    {
432        return getFaultField(true);
433    }
434    
435    /**
436     * Integer representing all fault flags reported by the device.
437     * <p>
438     * These are device specific and are not used directly in typical
439     * applications. Use the signal specific GetFault_*() methods instead.
440     * 
441     * <ul>
442     *   <li> <b>Minimum Value:</b> 0
443     *   <li> <b>Maximum Value:</b> 4294967295
444     *   <li> <b>Default Value:</b> 0
445     *   <li> <b>Units:</b> 
446     * </ul>
447     * 
448     * Default Rates:
449     * <ul>
450     *   <li> <b>CAN:</b> 4.0 Hz
451     * </ul>
452     * <p>
453     * This refreshes and returns a cached StatusSignal object.
454     * 
455     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
456     * @return FaultField Status Signal Object
457     */
458    public StatusSignal<Integer> getFaultField(boolean refresh)
459    {
460        @SuppressWarnings("unchecked")
461        var retval = super.lookupStatusSignal(SpnValue.AllFaults.value, Integer.class, val -> (int)val, "FaultField", true, refresh);
462        return retval;
463    }
464        
465    /**
466     * Integer representing all (persistent) sticky fault flags reported
467     * by the device.
468     * <p>
469     * These are device specific and are not used directly in typical
470     * applications. Use the signal specific GetStickyFault_*() methods
471     * instead.
472     * 
473     * <ul>
474     *   <li> <b>Minimum Value:</b> 0
475     *   <li> <b>Maximum Value:</b> 4294967295
476     *   <li> <b>Default Value:</b> 0
477     *   <li> <b>Units:</b> 
478     * </ul>
479     * 
480     * Default Rates:
481     * <ul>
482     *   <li> <b>CAN:</b> 4.0 Hz
483     * </ul>
484     * <p>
485     * This refreshes and returns a cached StatusSignal object.
486     * 
487     * @return StickyFaultField Status Signal Object
488     */
489    public StatusSignal<Integer> getStickyFaultField()
490    {
491        return getStickyFaultField(true);
492    }
493    
494    /**
495     * Integer representing all (persistent) sticky fault flags reported
496     * by the device.
497     * <p>
498     * These are device specific and are not used directly in typical
499     * applications. Use the signal specific GetStickyFault_*() methods
500     * instead.
501     * 
502     * <ul>
503     *   <li> <b>Minimum Value:</b> 0
504     *   <li> <b>Maximum Value:</b> 4294967295
505     *   <li> <b>Default Value:</b> 0
506     *   <li> <b>Units:</b> 
507     * </ul>
508     * 
509     * Default Rates:
510     * <ul>
511     *   <li> <b>CAN:</b> 4.0 Hz
512     * </ul>
513     * <p>
514     * This refreshes and returns a cached StatusSignal object.
515     * 
516     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
517     * @return StickyFaultField Status Signal Object
518     */
519    public StatusSignal<Integer> getStickyFaultField(boolean refresh)
520    {
521        @SuppressWarnings("unchecked")
522        var retval = super.lookupStatusSignal(SpnValue.AllStickyFaults.value, Integer.class, val -> (int)val, "StickyFaultField", true, refresh);
523        return retval;
524    }
525        
526    /**
527     * Current reported yaw of the Pigeon2.
528     * 
529     * <ul>
530     *   <li> <b>Minimum Value:</b> -368640.0
531     *   <li> <b>Maximum Value:</b> 368639.99725341797
532     *   <li> <b>Default Value:</b> 0
533     *   <li> <b>Units:</b> deg
534     * </ul>
535     * 
536     * Default Rates:
537     * <ul>
538     *   <li> <b>CAN 2.0:</b> 100.0 Hz
539     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
540     * </ul>
541     * <p>
542     * This refreshes and returns a cached StatusSignal object.
543     * 
544     * @return Yaw Status Signal Object
545     */
546    public StatusSignal<Angle> getYaw()
547    {
548        return getYaw(true);
549    }
550    
551    /**
552     * Current reported yaw of the Pigeon2.
553     * 
554     * <ul>
555     *   <li> <b>Minimum Value:</b> -368640.0
556     *   <li> <b>Maximum Value:</b> 368639.99725341797
557     *   <li> <b>Default Value:</b> 0
558     *   <li> <b>Units:</b> deg
559     * </ul>
560     * 
561     * Default Rates:
562     * <ul>
563     *   <li> <b>CAN 2.0:</b> 100.0 Hz
564     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
565     * </ul>
566     * <p>
567     * This refreshes and returns a cached StatusSignal object.
568     * 
569     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
570     * @return Yaw Status Signal Object
571     */
572    public StatusSignal<Angle> getYaw(boolean refresh)
573    {
574        @SuppressWarnings("unchecked")
575        var retval = super.lookupStatusSignal(SpnValue.Pigeon2Yaw.value, Angle.class, val -> Degrees.of(val), "Yaw", true, refresh);
576        return retval;
577    }
578        
579    /**
580     * Current reported pitch of the Pigeon2.
581     * 
582     * <ul>
583     *   <li> <b>Minimum Value:</b> -90.0
584     *   <li> <b>Maximum Value:</b> 89.9560546875
585     *   <li> <b>Default Value:</b> 0
586     *   <li> <b>Units:</b> deg
587     * </ul>
588     * 
589     * Default Rates:
590     * <ul>
591     *   <li> <b>CAN 2.0:</b> 100.0 Hz
592     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
593     * </ul>
594     * <p>
595     * This refreshes and returns a cached StatusSignal object.
596     * 
597     * @return Pitch Status Signal Object
598     */
599    public StatusSignal<Angle> getPitch()
600    {
601        return getPitch(true);
602    }
603    
604    /**
605     * Current reported pitch of the Pigeon2.
606     * 
607     * <ul>
608     *   <li> <b>Minimum Value:</b> -90.0
609     *   <li> <b>Maximum Value:</b> 89.9560546875
610     *   <li> <b>Default Value:</b> 0
611     *   <li> <b>Units:</b> deg
612     * </ul>
613     * 
614     * Default Rates:
615     * <ul>
616     *   <li> <b>CAN 2.0:</b> 100.0 Hz
617     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
618     * </ul>
619     * <p>
620     * This refreshes and returns a cached StatusSignal object.
621     * 
622     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
623     * @return Pitch Status Signal Object
624     */
625    public StatusSignal<Angle> getPitch(boolean refresh)
626    {
627        @SuppressWarnings("unchecked")
628        var retval = super.lookupStatusSignal(SpnValue.Pigeon2Pitch.value, Angle.class, val -> Degrees.of(val), "Pitch", true, refresh);
629        return retval;
630    }
631        
632    /**
633     * Current reported roll of the Pigeon2.
634     * 
635     * <ul>
636     *   <li> <b>Minimum Value:</b> -180.0
637     *   <li> <b>Maximum Value:</b> 179.9560546875
638     *   <li> <b>Default Value:</b> 0
639     *   <li> <b>Units:</b> deg
640     * </ul>
641     * 
642     * Default Rates:
643     * <ul>
644     *   <li> <b>CAN 2.0:</b> 100.0 Hz
645     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
646     * </ul>
647     * <p>
648     * This refreshes and returns a cached StatusSignal object.
649     * 
650     * @return Roll Status Signal Object
651     */
652    public StatusSignal<Angle> getRoll()
653    {
654        return getRoll(true);
655    }
656    
657    /**
658     * Current reported roll of the Pigeon2.
659     * 
660     * <ul>
661     *   <li> <b>Minimum Value:</b> -180.0
662     *   <li> <b>Maximum Value:</b> 179.9560546875
663     *   <li> <b>Default Value:</b> 0
664     *   <li> <b>Units:</b> deg
665     * </ul>
666     * 
667     * Default Rates:
668     * <ul>
669     *   <li> <b>CAN 2.0:</b> 100.0 Hz
670     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
671     * </ul>
672     * <p>
673     * This refreshes and returns a cached StatusSignal object.
674     * 
675     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
676     * @return Roll Status Signal Object
677     */
678    public StatusSignal<Angle> getRoll(boolean refresh)
679    {
680        @SuppressWarnings("unchecked")
681        var retval = super.lookupStatusSignal(SpnValue.Pigeon2Roll.value, Angle.class, val -> Degrees.of(val), "Roll", true, refresh);
682        return retval;
683    }
684        
685    /**
686     * The W component of the reported Quaternion.
687     * 
688     * <ul>
689     *   <li> <b>Minimum Value:</b> -1.0001220852154804
690     *   <li> <b>Maximum Value:</b> 1.0
691     *   <li> <b>Default Value:</b> 0
692     *   <li> <b>Units:</b> 
693     * </ul>
694     * 
695     * Default Rates:
696     * <ul>
697     *   <li> <b>CAN 2.0:</b> 50.0 Hz
698     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
699     * </ul>
700     * <p>
701     * This refreshes and returns a cached StatusSignal object.
702     * 
703     * @return QuatW Status Signal Object
704     */
705    public StatusSignal<Double> getQuatW()
706    {
707        return getQuatW(true);
708    }
709    
710    /**
711     * The W component of the reported Quaternion.
712     * 
713     * <ul>
714     *   <li> <b>Minimum Value:</b> -1.0001220852154804
715     *   <li> <b>Maximum Value:</b> 1.0
716     *   <li> <b>Default Value:</b> 0
717     *   <li> <b>Units:</b> 
718     * </ul>
719     * 
720     * Default Rates:
721     * <ul>
722     *   <li> <b>CAN 2.0:</b> 50.0 Hz
723     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
724     * </ul>
725     * <p>
726     * This refreshes and returns a cached StatusSignal object.
727     * 
728     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
729     * @return QuatW Status Signal Object
730     */
731    public StatusSignal<Double> getQuatW(boolean refresh)
732    {
733        @SuppressWarnings("unchecked")
734        var retval = super.lookupStatusSignal(SpnValue.Pigeon2QuatW.value, Double.class, val -> val, "QuatW", true, refresh);
735        return retval;
736    }
737        
738    /**
739     * The X component of the reported Quaternion.
740     * 
741     * <ul>
742     *   <li> <b>Minimum Value:</b> -1.0001220852154804
743     *   <li> <b>Maximum Value:</b> 1.0
744     *   <li> <b>Default Value:</b> 0
745     *   <li> <b>Units:</b> 
746     * </ul>
747     * 
748     * Default Rates:
749     * <ul>
750     *   <li> <b>CAN 2.0:</b> 50.0 Hz
751     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
752     * </ul>
753     * <p>
754     * This refreshes and returns a cached StatusSignal object.
755     * 
756     * @return QuatX Status Signal Object
757     */
758    public StatusSignal<Double> getQuatX()
759    {
760        return getQuatX(true);
761    }
762    
763    /**
764     * The X component of the reported Quaternion.
765     * 
766     * <ul>
767     *   <li> <b>Minimum Value:</b> -1.0001220852154804
768     *   <li> <b>Maximum Value:</b> 1.0
769     *   <li> <b>Default Value:</b> 0
770     *   <li> <b>Units:</b> 
771     * </ul>
772     * 
773     * Default Rates:
774     * <ul>
775     *   <li> <b>CAN 2.0:</b> 50.0 Hz
776     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
777     * </ul>
778     * <p>
779     * This refreshes and returns a cached StatusSignal object.
780     * 
781     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
782     * @return QuatX Status Signal Object
783     */
784    public StatusSignal<Double> getQuatX(boolean refresh)
785    {
786        @SuppressWarnings("unchecked")
787        var retval = super.lookupStatusSignal(SpnValue.Pigeon2QuatX.value, Double.class, val -> val, "QuatX", true, refresh);
788        return retval;
789    }
790        
791    /**
792     * The Y component of the reported Quaternion.
793     * 
794     * <ul>
795     *   <li> <b>Minimum Value:</b> -1.0001220852154804
796     *   <li> <b>Maximum Value:</b> 1.0
797     *   <li> <b>Default Value:</b> 0
798     *   <li> <b>Units:</b> 
799     * </ul>
800     * 
801     * Default Rates:
802     * <ul>
803     *   <li> <b>CAN 2.0:</b> 50.0 Hz
804     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
805     * </ul>
806     * <p>
807     * This refreshes and returns a cached StatusSignal object.
808     * 
809     * @return QuatY Status Signal Object
810     */
811    public StatusSignal<Double> getQuatY()
812    {
813        return getQuatY(true);
814    }
815    
816    /**
817     * The Y component of the reported Quaternion.
818     * 
819     * <ul>
820     *   <li> <b>Minimum Value:</b> -1.0001220852154804
821     *   <li> <b>Maximum Value:</b> 1.0
822     *   <li> <b>Default Value:</b> 0
823     *   <li> <b>Units:</b> 
824     * </ul>
825     * 
826     * Default Rates:
827     * <ul>
828     *   <li> <b>CAN 2.0:</b> 50.0 Hz
829     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
830     * </ul>
831     * <p>
832     * This refreshes and returns a cached StatusSignal object.
833     * 
834     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
835     * @return QuatY Status Signal Object
836     */
837    public StatusSignal<Double> getQuatY(boolean refresh)
838    {
839        @SuppressWarnings("unchecked")
840        var retval = super.lookupStatusSignal(SpnValue.Pigeon2QuatY.value, Double.class, val -> val, "QuatY", true, refresh);
841        return retval;
842    }
843        
844    /**
845     * The Z component of the reported Quaternion.
846     * 
847     * <ul>
848     *   <li> <b>Minimum Value:</b> -1.0001220852154804
849     *   <li> <b>Maximum Value:</b> 1.0
850     *   <li> <b>Default Value:</b> 0
851     *   <li> <b>Units:</b> 
852     * </ul>
853     * 
854     * Default Rates:
855     * <ul>
856     *   <li> <b>CAN 2.0:</b> 50.0 Hz
857     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
858     * </ul>
859     * <p>
860     * This refreshes and returns a cached StatusSignal object.
861     * 
862     * @return QuatZ Status Signal Object
863     */
864    public StatusSignal<Double> getQuatZ()
865    {
866        return getQuatZ(true);
867    }
868    
869    /**
870     * The Z component of the reported Quaternion.
871     * 
872     * <ul>
873     *   <li> <b>Minimum Value:</b> -1.0001220852154804
874     *   <li> <b>Maximum Value:</b> 1.0
875     *   <li> <b>Default Value:</b> 0
876     *   <li> <b>Units:</b> 
877     * </ul>
878     * 
879     * Default Rates:
880     * <ul>
881     *   <li> <b>CAN 2.0:</b> 50.0 Hz
882     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
883     * </ul>
884     * <p>
885     * This refreshes and returns a cached StatusSignal object.
886     * 
887     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
888     * @return QuatZ Status Signal Object
889     */
890    public StatusSignal<Double> getQuatZ(boolean refresh)
891    {
892        @SuppressWarnings("unchecked")
893        var retval = super.lookupStatusSignal(SpnValue.Pigeon2QuatZ.value, Double.class, val -> val, "QuatZ", true, refresh);
894        return retval;
895    }
896        
897    /**
898     * The X component of the gravity vector.
899     * <p>
900     * This is the X component of the reported gravity-vector. The gravity
901     * vector is not the acceleration experienced by the Pigeon2, rather
902     * it is where the Pigeon2 believes "Down" is. This can be used for
903     * mechanisms that are linearly related to gravity, such as an arm
904     * pivoting about a point, as the contribution of gravity to the arm
905     * is directly proportional to the contribution of gravity about one
906     * of these primary axis.
907     * 
908     * <ul>
909     *   <li> <b>Minimum Value:</b> -1.000030518509476
910     *   <li> <b>Maximum Value:</b> 1.0
911     *   <li> <b>Default Value:</b> 0
912     *   <li> <b>Units:</b> 
913     * </ul>
914     * 
915     * Default Rates:
916     * <ul>
917     *   <li> <b>CAN 2.0:</b> 10.0 Hz
918     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
919     * </ul>
920     * <p>
921     * This refreshes and returns a cached StatusSignal object.
922     * 
923     * @return GravityVectorX Status Signal Object
924     */
925    public StatusSignal<Double> getGravityVectorX()
926    {
927        return getGravityVectorX(true);
928    }
929    
930    /**
931     * The X component of the gravity vector.
932     * <p>
933     * This is the X component of the reported gravity-vector. The gravity
934     * vector is not the acceleration experienced by the Pigeon2, rather
935     * it is where the Pigeon2 believes "Down" is. This can be used for
936     * mechanisms that are linearly related to gravity, such as an arm
937     * pivoting about a point, as the contribution of gravity to the arm
938     * is directly proportional to the contribution of gravity about one
939     * of these primary axis.
940     * 
941     * <ul>
942     *   <li> <b>Minimum Value:</b> -1.000030518509476
943     *   <li> <b>Maximum Value:</b> 1.0
944     *   <li> <b>Default Value:</b> 0
945     *   <li> <b>Units:</b> 
946     * </ul>
947     * 
948     * Default Rates:
949     * <ul>
950     *   <li> <b>CAN 2.0:</b> 10.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 GravityVectorX Status Signal Object
958     */
959    public StatusSignal<Double> getGravityVectorX(boolean refresh)
960    {
961        @SuppressWarnings("unchecked")
962        var retval = super.lookupStatusSignal(SpnValue.Pigeon2GravityVectorX.value, Double.class, val -> val, "GravityVectorX", true, refresh);
963        return retval;
964    }
965        
966    /**
967     * The Y component of the gravity vector.
968     * <p>
969     * This is the X component of the reported gravity-vector. The gravity
970     * vector is not the acceleration experienced by the Pigeon2, rather
971     * it is where the Pigeon2 believes "Down" is. This can be used for
972     * mechanisms that are linearly related to gravity, such as an arm
973     * pivoting about a point, as the contribution of gravity to the arm
974     * is directly proportional to the contribution of gravity about one
975     * of these primary axis.
976     * 
977     * <ul>
978     *   <li> <b>Minimum Value:</b> -1.000030518509476
979     *   <li> <b>Maximum Value:</b> 1.0
980     *   <li> <b>Default Value:</b> 0
981     *   <li> <b>Units:</b> 
982     * </ul>
983     * 
984     * Default Rates:
985     * <ul>
986     *   <li> <b>CAN 2.0:</b> 10.0 Hz
987     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
988     * </ul>
989     * <p>
990     * This refreshes and returns a cached StatusSignal object.
991     * 
992     * @return GravityVectorY Status Signal Object
993     */
994    public StatusSignal<Double> getGravityVectorY()
995    {
996        return getGravityVectorY(true);
997    }
998    
999    /**
1000     * The Y component of the gravity vector.
1001     * <p>
1002     * This is the X component of the reported gravity-vector. The gravity
1003     * vector is not the acceleration experienced by the Pigeon2, rather
1004     * it is where the Pigeon2 believes "Down" is. This can be used for
1005     * mechanisms that are linearly related to gravity, such as an arm
1006     * pivoting about a point, as the contribution of gravity to the arm
1007     * is directly proportional to the contribution of gravity about one
1008     * of these primary axis.
1009     * 
1010     * <ul>
1011     *   <li> <b>Minimum Value:</b> -1.000030518509476
1012     *   <li> <b>Maximum Value:</b> 1.0
1013     *   <li> <b>Default Value:</b> 0
1014     *   <li> <b>Units:</b> 
1015     * </ul>
1016     * 
1017     * Default Rates:
1018     * <ul>
1019     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1020     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1021     * </ul>
1022     * <p>
1023     * This refreshes and returns a cached StatusSignal object.
1024     * 
1025     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1026     * @return GravityVectorY Status Signal Object
1027     */
1028    public StatusSignal<Double> getGravityVectorY(boolean refresh)
1029    {
1030        @SuppressWarnings("unchecked")
1031        var retval = super.lookupStatusSignal(SpnValue.Pigeon2GravityVectorY.value, Double.class, val -> val, "GravityVectorY", true, refresh);
1032        return retval;
1033    }
1034        
1035    /**
1036     * The Z component of the gravity vector.
1037     * <p>
1038     * This is the Z component of the reported gravity-vector. The gravity
1039     * vector is not the acceleration experienced by the Pigeon2, rather
1040     * it is where the Pigeon2 believes "Down" is. This can be used for
1041     * mechanisms that are linearly related to gravity, such as an arm
1042     * pivoting about a point, as the contribution of gravity to the arm
1043     * is directly proportional to the contribution of gravity about one
1044     * of these primary axis.
1045     * 
1046     * <ul>
1047     *   <li> <b>Minimum Value:</b> -1.000030518509476
1048     *   <li> <b>Maximum Value:</b> 1.0
1049     *   <li> <b>Default Value:</b> 0
1050     *   <li> <b>Units:</b> 
1051     * </ul>
1052     * 
1053     * Default Rates:
1054     * <ul>
1055     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1056     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1057     * </ul>
1058     * <p>
1059     * This refreshes and returns a cached StatusSignal object.
1060     * 
1061     * @return GravityVectorZ Status Signal Object
1062     */
1063    public StatusSignal<Double> getGravityVectorZ()
1064    {
1065        return getGravityVectorZ(true);
1066    }
1067    
1068    /**
1069     * The Z component of the gravity vector.
1070     * <p>
1071     * This is the Z component of the reported gravity-vector. The gravity
1072     * vector is not the acceleration experienced by the Pigeon2, rather
1073     * it is where the Pigeon2 believes "Down" is. This can be used for
1074     * mechanisms that are linearly related to gravity, such as an arm
1075     * pivoting about a point, as the contribution of gravity to the arm
1076     * is directly proportional to the contribution of gravity about one
1077     * of these primary axis.
1078     * 
1079     * <ul>
1080     *   <li> <b>Minimum Value:</b> -1.000030518509476
1081     *   <li> <b>Maximum Value:</b> 1.0
1082     *   <li> <b>Default Value:</b> 0
1083     *   <li> <b>Units:</b> 
1084     * </ul>
1085     * 
1086     * Default Rates:
1087     * <ul>
1088     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1089     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1090     * </ul>
1091     * <p>
1092     * This refreshes and returns a cached StatusSignal object.
1093     * 
1094     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1095     * @return GravityVectorZ Status Signal Object
1096     */
1097    public StatusSignal<Double> getGravityVectorZ(boolean refresh)
1098    {
1099        @SuppressWarnings("unchecked")
1100        var retval = super.lookupStatusSignal(SpnValue.Pigeon2GravityVectorZ.value, Double.class, val -> val, "GravityVectorZ", true, refresh);
1101        return retval;
1102    }
1103        
1104    /**
1105     * Temperature of the Pigeon 2.
1106     * 
1107     * <ul>
1108     *   <li> <b>Minimum Value:</b> -128.0
1109     *   <li> <b>Maximum Value:</b> 127.99609375
1110     *   <li> <b>Default Value:</b> 0
1111     *   <li> <b>Units:</b> ℃
1112     * </ul>
1113     * 
1114     * Default Rates:
1115     * <ul>
1116     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1117     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1118     * </ul>
1119     * <p>
1120     * This refreshes and returns a cached StatusSignal object.
1121     * 
1122     * @return Temperature Status Signal Object
1123     */
1124    public StatusSignal<Temperature> getTemperature()
1125    {
1126        return getTemperature(true);
1127    }
1128    
1129    /**
1130     * Temperature of the Pigeon 2.
1131     * 
1132     * <ul>
1133     *   <li> <b>Minimum Value:</b> -128.0
1134     *   <li> <b>Maximum Value:</b> 127.99609375
1135     *   <li> <b>Default Value:</b> 0
1136     *   <li> <b>Units:</b> ℃
1137     * </ul>
1138     * 
1139     * Default Rates:
1140     * <ul>
1141     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1142     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1143     * </ul>
1144     * <p>
1145     * This refreshes and returns a cached StatusSignal object.
1146     * 
1147     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1148     * @return Temperature Status Signal Object
1149     */
1150    public StatusSignal<Temperature> getTemperature(boolean refresh)
1151    {
1152        @SuppressWarnings("unchecked")
1153        var retval = super.lookupStatusSignal(SpnValue.Pigeon2Temperature.value, Temperature.class, val -> Celsius.of(val), "Temperature", true, refresh);
1154        return retval;
1155    }
1156        
1157    /**
1158     * Whether the no-motion calibration feature is enabled.
1159     * 
1160     * <ul>
1161     *   <li> <b>Default Value:</b> 0
1162     * </ul>
1163     * 
1164     * Default Rates:
1165     * <ul>
1166     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1167     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1168     * </ul>
1169     * <p>
1170     * This refreshes and returns a cached StatusSignal object.
1171     * 
1172     * @return NoMotionEnabled Status Signal Object
1173     */
1174    public StatusSignal<Boolean> getNoMotionEnabled()
1175    {
1176        return getNoMotionEnabled(true);
1177    }
1178    
1179    /**
1180     * Whether the no-motion calibration feature is enabled.
1181     * 
1182     * <ul>
1183     *   <li> <b>Default Value:</b> 0
1184     * </ul>
1185     * 
1186     * Default Rates:
1187     * <ul>
1188     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1189     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1190     * </ul>
1191     * <p>
1192     * This refreshes and returns a cached StatusSignal object.
1193     * 
1194     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1195     * @return NoMotionEnabled Status Signal Object
1196     */
1197    public StatusSignal<Boolean> getNoMotionEnabled(boolean refresh)
1198    {
1199        @SuppressWarnings("unchecked")
1200        var retval = super.lookupStatusSignal(SpnValue.Pigeon2NoMotionCalEnabled.value, Boolean.class, val -> val != 0, "NoMotionEnabled", true, refresh);
1201        return retval;
1202    }
1203        
1204    /**
1205     * The number of times a no-motion event occurred, wraps at 15.
1206     * 
1207     * <ul>
1208     *   <li> <b>Minimum Value:</b> 0
1209     *   <li> <b>Maximum Value:</b> 15
1210     *   <li> <b>Default Value:</b> 0
1211     *   <li> <b>Units:</b> 
1212     * </ul>
1213     * 
1214     * Default Rates:
1215     * <ul>
1216     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1217     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1218     * </ul>
1219     * <p>
1220     * This refreshes and returns a cached StatusSignal object.
1221     * 
1222     * @return NoMotionCount Status Signal Object
1223     */
1224    public StatusSignal<Double> getNoMotionCount()
1225    {
1226        return getNoMotionCount(true);
1227    }
1228    
1229    /**
1230     * The number of times a no-motion event occurred, wraps at 15.
1231     * 
1232     * <ul>
1233     *   <li> <b>Minimum Value:</b> 0
1234     *   <li> <b>Maximum Value:</b> 15
1235     *   <li> <b>Default Value:</b> 0
1236     *   <li> <b>Units:</b> 
1237     * </ul>
1238     * 
1239     * Default Rates:
1240     * <ul>
1241     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1242     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1243     * </ul>
1244     * <p>
1245     * This refreshes and returns a cached StatusSignal object.
1246     * 
1247     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1248     * @return NoMotionCount Status Signal Object
1249     */
1250    public StatusSignal<Double> getNoMotionCount(boolean refresh)
1251    {
1252        @SuppressWarnings("unchecked")
1253        var retval = super.lookupStatusSignal(SpnValue.Pigeon2NoMotionCount.value, Double.class, val -> val, "NoMotionCount", true, refresh);
1254        return retval;
1255    }
1256        
1257    /**
1258     * Whether the temperature-compensation feature is disabled.
1259     * 
1260     * <ul>
1261     *   <li> <b>Default Value:</b> 0
1262     * </ul>
1263     * 
1264     * Default Rates:
1265     * <ul>
1266     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1267     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1268     * </ul>
1269     * <p>
1270     * This refreshes and returns a cached StatusSignal object.
1271     * 
1272     * @return TemperatureCompensationDisabled Status Signal Object
1273     */
1274    public StatusSignal<Boolean> getTemperatureCompensationDisabled()
1275    {
1276        return getTemperatureCompensationDisabled(true);
1277    }
1278    
1279    /**
1280     * Whether the temperature-compensation feature is disabled.
1281     * 
1282     * <ul>
1283     *   <li> <b>Default Value:</b> 0
1284     * </ul>
1285     * 
1286     * Default Rates:
1287     * <ul>
1288     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1289     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1290     * </ul>
1291     * <p>
1292     * This refreshes and returns a cached StatusSignal object.
1293     * 
1294     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1295     * @return TemperatureCompensationDisabled Status Signal Object
1296     */
1297    public StatusSignal<Boolean> getTemperatureCompensationDisabled(boolean refresh)
1298    {
1299        @SuppressWarnings("unchecked")
1300        var retval = super.lookupStatusSignal(SpnValue.Pigeon2TempCompDisabled.value, Boolean.class, val -> val != 0, "TemperatureCompensationDisabled", true, refresh);
1301        return retval;
1302    }
1303        
1304    /**
1305     * How long the Pigeon 2's been up in seconds, caps at 255 seconds.
1306     * 
1307     * <ul>
1308     *   <li> <b>Minimum Value:</b> 0
1309     *   <li> <b>Maximum Value:</b> 255
1310     *   <li> <b>Default Value:</b> 0
1311     *   <li> <b>Units:</b> s
1312     * </ul>
1313     * 
1314     * Default Rates:
1315     * <ul>
1316     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1317     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1318     * </ul>
1319     * <p>
1320     * This refreshes and returns a cached StatusSignal object.
1321     * 
1322     * @return UpTime Status Signal Object
1323     */
1324    public StatusSignal<Time> getUpTime()
1325    {
1326        return getUpTime(true);
1327    }
1328    
1329    /**
1330     * How long the Pigeon 2's been up in seconds, caps at 255 seconds.
1331     * 
1332     * <ul>
1333     *   <li> <b>Minimum Value:</b> 0
1334     *   <li> <b>Maximum Value:</b> 255
1335     *   <li> <b>Default Value:</b> 0
1336     *   <li> <b>Units:</b> s
1337     * </ul>
1338     * 
1339     * Default Rates:
1340     * <ul>
1341     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1342     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1343     * </ul>
1344     * <p>
1345     * This refreshes and returns a cached StatusSignal object.
1346     * 
1347     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1348     * @return UpTime Status Signal Object
1349     */
1350    public StatusSignal<Time> getUpTime(boolean refresh)
1351    {
1352        @SuppressWarnings("unchecked")
1353        var retval = super.lookupStatusSignal(SpnValue.Pigeon2UpTime.value, Time.class, val -> Seconds.of(val), "UpTime", true, refresh);
1354        return retval;
1355    }
1356        
1357    /**
1358     * The accumulated gyro about the X axis without any sensor fusing.
1359     * 
1360     * <ul>
1361     *   <li> <b>Minimum Value:</b> -23040.0
1362     *   <li> <b>Maximum Value:</b> 23039.9560546875
1363     *   <li> <b>Default Value:</b> 0
1364     *   <li> <b>Units:</b> deg
1365     * </ul>
1366     * 
1367     * Default Rates:
1368     * <ul>
1369     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1370     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1371     * </ul>
1372     * <p>
1373     * This refreshes and returns a cached StatusSignal object.
1374     * 
1375     * @return AccumGyroX Status Signal Object
1376     */
1377    public StatusSignal<Angle> getAccumGyroX()
1378    {
1379        return getAccumGyroX(true);
1380    }
1381    
1382    /**
1383     * The accumulated gyro about the X axis without any sensor fusing.
1384     * 
1385     * <ul>
1386     *   <li> <b>Minimum Value:</b> -23040.0
1387     *   <li> <b>Maximum Value:</b> 23039.9560546875
1388     *   <li> <b>Default Value:</b> 0
1389     *   <li> <b>Units:</b> deg
1390     * </ul>
1391     * 
1392     * Default Rates:
1393     * <ul>
1394     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1395     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1396     * </ul>
1397     * <p>
1398     * This refreshes and returns a cached StatusSignal object.
1399     * 
1400     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1401     * @return AccumGyroX Status Signal Object
1402     */
1403    public StatusSignal<Angle> getAccumGyroX(boolean refresh)
1404    {
1405        @SuppressWarnings("unchecked")
1406        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AccumGyroX.value, Angle.class, val -> Degrees.of(val), "AccumGyroX", true, refresh);
1407        return retval;
1408    }
1409        
1410    /**
1411     * The accumulated gyro about the Y axis without any sensor fusing.
1412     * 
1413     * <ul>
1414     *   <li> <b>Minimum Value:</b> -23040.0
1415     *   <li> <b>Maximum Value:</b> 23039.9560546875
1416     *   <li> <b>Default Value:</b> 0
1417     *   <li> <b>Units:</b> deg
1418     * </ul>
1419     * 
1420     * Default Rates:
1421     * <ul>
1422     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1423     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1424     * </ul>
1425     * <p>
1426     * This refreshes and returns a cached StatusSignal object.
1427     * 
1428     * @return AccumGyroY Status Signal Object
1429     */
1430    public StatusSignal<Angle> getAccumGyroY()
1431    {
1432        return getAccumGyroY(true);
1433    }
1434    
1435    /**
1436     * The accumulated gyro about the Y axis without any sensor fusing.
1437     * 
1438     * <ul>
1439     *   <li> <b>Minimum Value:</b> -23040.0
1440     *   <li> <b>Maximum Value:</b> 23039.9560546875
1441     *   <li> <b>Default Value:</b> 0
1442     *   <li> <b>Units:</b> deg
1443     * </ul>
1444     * 
1445     * Default Rates:
1446     * <ul>
1447     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1448     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1449     * </ul>
1450     * <p>
1451     * This refreshes and returns a cached StatusSignal object.
1452     * 
1453     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1454     * @return AccumGyroY Status Signal Object
1455     */
1456    public StatusSignal<Angle> getAccumGyroY(boolean refresh)
1457    {
1458        @SuppressWarnings("unchecked")
1459        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AccumGyroY.value, Angle.class, val -> Degrees.of(val), "AccumGyroY", true, refresh);
1460        return retval;
1461    }
1462        
1463    /**
1464     * The accumulated gyro about the Z axis without any sensor fusing.
1465     * 
1466     * <ul>
1467     *   <li> <b>Minimum Value:</b> -23040.0
1468     *   <li> <b>Maximum Value:</b> 23039.9560546875
1469     *   <li> <b>Default Value:</b> 0
1470     *   <li> <b>Units:</b> deg
1471     * </ul>
1472     * 
1473     * Default Rates:
1474     * <ul>
1475     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1476     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1477     * </ul>
1478     * <p>
1479     * This refreshes and returns a cached StatusSignal object.
1480     * 
1481     * @return AccumGyroZ Status Signal Object
1482     */
1483    public StatusSignal<Angle> getAccumGyroZ()
1484    {
1485        return getAccumGyroZ(true);
1486    }
1487    
1488    /**
1489     * The accumulated gyro about the Z axis without any sensor fusing.
1490     * 
1491     * <ul>
1492     *   <li> <b>Minimum Value:</b> -23040.0
1493     *   <li> <b>Maximum Value:</b> 23039.9560546875
1494     *   <li> <b>Default Value:</b> 0
1495     *   <li> <b>Units:</b> deg
1496     * </ul>
1497     * 
1498     * Default Rates:
1499     * <ul>
1500     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1501     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1502     * </ul>
1503     * <p>
1504     * This refreshes and returns a cached StatusSignal object.
1505     * 
1506     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1507     * @return AccumGyroZ Status Signal Object
1508     */
1509    public StatusSignal<Angle> getAccumGyroZ(boolean refresh)
1510    {
1511        @SuppressWarnings("unchecked")
1512        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AccumGyroZ.value, Angle.class, val -> Degrees.of(val), "AccumGyroZ", true, refresh);
1513        return retval;
1514    }
1515        
1516    /**
1517     * The angular velocity (ω) of the Pigeon 2 about the X axis with
1518     * respect to the world frame.  This value is mount-calibrated.
1519     * 
1520     * <ul>
1521     *   <li> <b>Minimum Value:</b> -2048.0
1522     *   <li> <b>Maximum Value:</b> 2047.99609375
1523     *   <li> <b>Default Value:</b> 0
1524     *   <li> <b>Units:</b> dps
1525     * </ul>
1526     * 
1527     * Default Rates:
1528     * <ul>
1529     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1530     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1531     * </ul>
1532     * <p>
1533     * This refreshes and returns a cached StatusSignal object.
1534     * 
1535     * @return AngularVelocityXWorld Status Signal Object
1536     */
1537    public StatusSignal<AngularVelocity> getAngularVelocityXWorld()
1538    {
1539        return getAngularVelocityXWorld(true);
1540    }
1541    
1542    /**
1543     * The angular velocity (ω) of the Pigeon 2 about the X axis with
1544     * respect to the world frame.  This value is mount-calibrated.
1545     * 
1546     * <ul>
1547     *   <li> <b>Minimum Value:</b> -2048.0
1548     *   <li> <b>Maximum Value:</b> 2047.99609375
1549     *   <li> <b>Default Value:</b> 0
1550     *   <li> <b>Units:</b> dps
1551     * </ul>
1552     * 
1553     * Default Rates:
1554     * <ul>
1555     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1556     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1557     * </ul>
1558     * <p>
1559     * This refreshes and returns a cached StatusSignal object.
1560     * 
1561     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1562     * @return AngularVelocityXWorld Status Signal Object
1563     */
1564    public StatusSignal<AngularVelocity> getAngularVelocityXWorld(boolean refresh)
1565    {
1566        @SuppressWarnings("unchecked")
1567        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityXWorld.value, AngularVelocity.class, val -> DegreesPerSecond.of(val), "AngularVelocityXWorld", true, refresh);
1568        return retval;
1569    }
1570        
1571    /**
1572     * The angular velocity (ω) of the Pigeon 2 about the Y axis with
1573     * respect to the world frame.  This value is mount-calibrated.
1574     * 
1575     * <ul>
1576     *   <li> <b>Minimum Value:</b> -2048.0
1577     *   <li> <b>Maximum Value:</b> 2047.99609375
1578     *   <li> <b>Default Value:</b> 0
1579     *   <li> <b>Units:</b> dps
1580     * </ul>
1581     * 
1582     * Default Rates:
1583     * <ul>
1584     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1585     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1586     * </ul>
1587     * <p>
1588     * This refreshes and returns a cached StatusSignal object.
1589     * 
1590     * @return AngularVelocityYWorld Status Signal Object
1591     */
1592    public StatusSignal<AngularVelocity> getAngularVelocityYWorld()
1593    {
1594        return getAngularVelocityYWorld(true);
1595    }
1596    
1597    /**
1598     * The angular velocity (ω) of the Pigeon 2 about the Y axis with
1599     * respect to the world frame.  This value is mount-calibrated.
1600     * 
1601     * <ul>
1602     *   <li> <b>Minimum Value:</b> -2048.0
1603     *   <li> <b>Maximum Value:</b> 2047.99609375
1604     *   <li> <b>Default Value:</b> 0
1605     *   <li> <b>Units:</b> dps
1606     * </ul>
1607     * 
1608     * Default Rates:
1609     * <ul>
1610     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1611     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1612     * </ul>
1613     * <p>
1614     * This refreshes and returns a cached StatusSignal object.
1615     * 
1616     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1617     * @return AngularVelocityYWorld Status Signal Object
1618     */
1619    public StatusSignal<AngularVelocity> getAngularVelocityYWorld(boolean refresh)
1620    {
1621        @SuppressWarnings("unchecked")
1622        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityYWorld.value, AngularVelocity.class, val -> DegreesPerSecond.of(val), "AngularVelocityYWorld", true, refresh);
1623        return retval;
1624    }
1625        
1626    /**
1627     * The angular velocity (ω) of the Pigeon 2 about the Z axis with
1628     * respect to the world frame.  This value is mount-calibrated.
1629     * 
1630     * <ul>
1631     *   <li> <b>Minimum Value:</b> -2048.0
1632     *   <li> <b>Maximum Value:</b> 2047.99609375
1633     *   <li> <b>Default Value:</b> 0
1634     *   <li> <b>Units:</b> dps
1635     * </ul>
1636     * 
1637     * Default Rates:
1638     * <ul>
1639     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1640     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1641     * </ul>
1642     * <p>
1643     * This refreshes and returns a cached StatusSignal object.
1644     * 
1645     * @return AngularVelocityZWorld Status Signal Object
1646     */
1647    public StatusSignal<AngularVelocity> getAngularVelocityZWorld()
1648    {
1649        return getAngularVelocityZWorld(true);
1650    }
1651    
1652    /**
1653     * The angular velocity (ω) of the Pigeon 2 about the Z axis with
1654     * respect to the world frame.  This value is mount-calibrated.
1655     * 
1656     * <ul>
1657     *   <li> <b>Minimum Value:</b> -2048.0
1658     *   <li> <b>Maximum Value:</b> 2047.99609375
1659     *   <li> <b>Default Value:</b> 0
1660     *   <li> <b>Units:</b> dps
1661     * </ul>
1662     * 
1663     * Default Rates:
1664     * <ul>
1665     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1666     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1667     * </ul>
1668     * <p>
1669     * This refreshes and returns a cached StatusSignal object.
1670     * 
1671     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1672     * @return AngularVelocityZWorld Status Signal Object
1673     */
1674    public StatusSignal<AngularVelocity> getAngularVelocityZWorld(boolean refresh)
1675    {
1676        @SuppressWarnings("unchecked")
1677        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityZWorld.value, AngularVelocity.class, val -> DegreesPerSecond.of(val), "AngularVelocityZWorld", true, refresh);
1678        return retval;
1679    }
1680        
1681    /**
1682     * The acceleration measured by Pigeon2 in the X direction.
1683     * <p>
1684     * This value includes the acceleration due to gravity. If this is
1685     * undesirable, get the gravity vector and subtract out the
1686     * contribution in this direction.
1687     * 
1688     * <ul>
1689     *   <li> <b>Minimum Value:</b> -2.0
1690     *   <li> <b>Maximum Value:</b> 1.99993896484375
1691     *   <li> <b>Default Value:</b> 0
1692     *   <li> <b>Units:</b> g
1693     * </ul>
1694     * 
1695     * Default Rates:
1696     * <ul>
1697     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1698     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1699     * </ul>
1700     * <p>
1701     * This refreshes and returns a cached StatusSignal object.
1702     * 
1703     * @return AccelerationX Status Signal Object
1704     */
1705    public StatusSignal<LinearAcceleration> getAccelerationX()
1706    {
1707        return getAccelerationX(true);
1708    }
1709    
1710    /**
1711     * The acceleration measured by Pigeon2 in the X direction.
1712     * <p>
1713     * This value includes the acceleration due to gravity. If this is
1714     * undesirable, get the gravity vector and subtract out the
1715     * contribution in this direction.
1716     * 
1717     * <ul>
1718     *   <li> <b>Minimum Value:</b> -2.0
1719     *   <li> <b>Maximum Value:</b> 1.99993896484375
1720     *   <li> <b>Default Value:</b> 0
1721     *   <li> <b>Units:</b> g
1722     * </ul>
1723     * 
1724     * Default Rates:
1725     * <ul>
1726     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1727     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1728     * </ul>
1729     * <p>
1730     * This refreshes and returns a cached StatusSignal object.
1731     * 
1732     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1733     * @return AccelerationX Status Signal Object
1734     */
1735    public StatusSignal<LinearAcceleration> getAccelerationX(boolean refresh)
1736    {
1737        @SuppressWarnings("unchecked")
1738        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AccelerationX.value, LinearAcceleration.class, val -> Gs.of(val), "AccelerationX", true, refresh);
1739        return retval;
1740    }
1741        
1742    /**
1743     * The acceleration measured by Pigeon2 in the Y direction.
1744     * <p>
1745     * This value includes the acceleration due to gravity. If this is
1746     * undesirable, get the gravity vector and subtract out the
1747     * contribution in this direction.
1748     * 
1749     * <ul>
1750     *   <li> <b>Minimum Value:</b> -2.0
1751     *   <li> <b>Maximum Value:</b> 1.99993896484375
1752     *   <li> <b>Default Value:</b> 0
1753     *   <li> <b>Units:</b> g
1754     * </ul>
1755     * 
1756     * Default Rates:
1757     * <ul>
1758     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1759     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1760     * </ul>
1761     * <p>
1762     * This refreshes and returns a cached StatusSignal object.
1763     * 
1764     * @return AccelerationY Status Signal Object
1765     */
1766    public StatusSignal<LinearAcceleration> getAccelerationY()
1767    {
1768        return getAccelerationY(true);
1769    }
1770    
1771    /**
1772     * The acceleration measured by Pigeon2 in the Y direction.
1773     * <p>
1774     * This value includes the acceleration due to gravity. If this is
1775     * undesirable, get the gravity vector and subtract out the
1776     * contribution in this direction.
1777     * 
1778     * <ul>
1779     *   <li> <b>Minimum Value:</b> -2.0
1780     *   <li> <b>Maximum Value:</b> 1.99993896484375
1781     *   <li> <b>Default Value:</b> 0
1782     *   <li> <b>Units:</b> g
1783     * </ul>
1784     * 
1785     * Default Rates:
1786     * <ul>
1787     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1788     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1789     * </ul>
1790     * <p>
1791     * This refreshes and returns a cached StatusSignal object.
1792     * 
1793     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1794     * @return AccelerationY Status Signal Object
1795     */
1796    public StatusSignal<LinearAcceleration> getAccelerationY(boolean refresh)
1797    {
1798        @SuppressWarnings("unchecked")
1799        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AccelerationY.value, LinearAcceleration.class, val -> Gs.of(val), "AccelerationY", true, refresh);
1800        return retval;
1801    }
1802        
1803    /**
1804     * The acceleration measured by Pigeon2 in the Z direction.
1805     * <p>
1806     * This value includes the acceleration due to gravity. If this is
1807     * undesirable, get the gravity vector and subtract out the
1808     * contribution in this direction.
1809     * 
1810     * <ul>
1811     *   <li> <b>Minimum Value:</b> -2.0
1812     *   <li> <b>Maximum Value:</b> 1.99993896484375
1813     *   <li> <b>Default Value:</b> 0
1814     *   <li> <b>Units:</b> g
1815     * </ul>
1816     * 
1817     * Default Rates:
1818     * <ul>
1819     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1820     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1821     * </ul>
1822     * <p>
1823     * This refreshes and returns a cached StatusSignal object.
1824     * 
1825     * @return AccelerationZ Status Signal Object
1826     */
1827    public StatusSignal<LinearAcceleration> getAccelerationZ()
1828    {
1829        return getAccelerationZ(true);
1830    }
1831    
1832    /**
1833     * The acceleration measured by Pigeon2 in the Z direction.
1834     * <p>
1835     * This value includes the acceleration due to gravity. If this is
1836     * undesirable, get the gravity vector and subtract out the
1837     * contribution in this direction.
1838     * 
1839     * <ul>
1840     *   <li> <b>Minimum Value:</b> -2.0
1841     *   <li> <b>Maximum Value:</b> 1.99993896484375
1842     *   <li> <b>Default Value:</b> 0
1843     *   <li> <b>Units:</b> g
1844     * </ul>
1845     * 
1846     * Default Rates:
1847     * <ul>
1848     *   <li> <b>CAN 2.0:</b> 10.0 Hz
1849     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1850     * </ul>
1851     * <p>
1852     * This refreshes and returns a cached StatusSignal object.
1853     * 
1854     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1855     * @return AccelerationZ Status Signal Object
1856     */
1857    public StatusSignal<LinearAcceleration> getAccelerationZ(boolean refresh)
1858    {
1859        @SuppressWarnings("unchecked")
1860        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AccelerationZ.value, LinearAcceleration.class, val -> Gs.of(val), "AccelerationZ", true, refresh);
1861        return retval;
1862    }
1863        
1864    /**
1865     * Measured supply voltage to the Pigeon2.
1866     * 
1867     * <ul>
1868     *   <li> <b>Minimum Value:</b> 0.0
1869     *   <li> <b>Maximum Value:</b> 31.99951171875
1870     *   <li> <b>Default Value:</b> 0
1871     *   <li> <b>Units:</b> V
1872     * </ul>
1873     * 
1874     * Default Rates:
1875     * <ul>
1876     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1877     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1878     * </ul>
1879     * <p>
1880     * This refreshes and returns a cached StatusSignal object.
1881     * 
1882     * @return SupplyVoltage Status Signal Object
1883     */
1884    public StatusSignal<Voltage> getSupplyVoltage()
1885    {
1886        return getSupplyVoltage(true);
1887    }
1888    
1889    /**
1890     * Measured supply voltage to the Pigeon2.
1891     * 
1892     * <ul>
1893     *   <li> <b>Minimum Value:</b> 0.0
1894     *   <li> <b>Maximum Value:</b> 31.99951171875
1895     *   <li> <b>Default Value:</b> 0
1896     *   <li> <b>Units:</b> V
1897     * </ul>
1898     * 
1899     * Default Rates:
1900     * <ul>
1901     *   <li> <b>CAN 2.0:</b> 4.0 Hz
1902     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
1903     * </ul>
1904     * <p>
1905     * This refreshes and returns a cached StatusSignal object.
1906     * 
1907     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1908     * @return SupplyVoltage Status Signal Object
1909     */
1910    public StatusSignal<Voltage> getSupplyVoltage(boolean refresh)
1911    {
1912        @SuppressWarnings("unchecked")
1913        var retval = super.lookupStatusSignal(SpnValue.Pigeon2_SupplyVoltage.value, Voltage.class, val -> Volts.of(val), "SupplyVoltage", true, refresh);
1914        return retval;
1915    }
1916        
1917    /**
1918     * The angular velocity (ω) of the Pigeon 2 about the device's X axis.
1919     * <p>
1920     * This value is not mount-calibrated.
1921     * 
1922     * <ul>
1923     *   <li> <b>Minimum Value:</b> -1998.048780487805
1924     *   <li> <b>Maximum Value:</b> 1997.987804878049
1925     *   <li> <b>Default Value:</b> 0
1926     *   <li> <b>Units:</b> dps
1927     * </ul>
1928     * 
1929     * Default Rates:
1930     * <ul>
1931     *   <li> <b>CAN:</b> 4.0 Hz
1932     * </ul>
1933     * <p>
1934     * This refreshes and returns a cached StatusSignal object.
1935     * 
1936     * @return AngularVelocityXDevice Status Signal Object
1937     */
1938    public StatusSignal<AngularVelocity> getAngularVelocityXDevice()
1939    {
1940        return getAngularVelocityXDevice(true);
1941    }
1942    
1943    /**
1944     * The angular velocity (ω) of the Pigeon 2 about the device's X axis.
1945     * <p>
1946     * This value is not mount-calibrated.
1947     * 
1948     * <ul>
1949     *   <li> <b>Minimum Value:</b> -1998.048780487805
1950     *   <li> <b>Maximum Value:</b> 1997.987804878049
1951     *   <li> <b>Default Value:</b> 0
1952     *   <li> <b>Units:</b> dps
1953     * </ul>
1954     * 
1955     * Default Rates:
1956     * <ul>
1957     *   <li> <b>CAN:</b> 4.0 Hz
1958     * </ul>
1959     * <p>
1960     * This refreshes and returns a cached StatusSignal object.
1961     * 
1962     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
1963     * @return AngularVelocityXDevice Status Signal Object
1964     */
1965    public StatusSignal<AngularVelocity> getAngularVelocityXDevice(boolean refresh)
1966    {
1967        @SuppressWarnings("unchecked")
1968        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityX.value, AngularVelocity.class, val -> DegreesPerSecond.of(val), "AngularVelocityXDevice", true, refresh);
1969        return retval;
1970    }
1971        
1972    /**
1973     * The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
1974     * <p>
1975     * This value is not mount-calibrated.
1976     * 
1977     * <ul>
1978     *   <li> <b>Minimum Value:</b> -1998.048780487805
1979     *   <li> <b>Maximum Value:</b> 1997.987804878049
1980     *   <li> <b>Default Value:</b> 0
1981     *   <li> <b>Units:</b> dps
1982     * </ul>
1983     * 
1984     * Default Rates:
1985     * <ul>
1986     *   <li> <b>CAN:</b> 4.0 Hz
1987     * </ul>
1988     * <p>
1989     * This refreshes and returns a cached StatusSignal object.
1990     * 
1991     * @return AngularVelocityYDevice Status Signal Object
1992     */
1993    public StatusSignal<AngularVelocity> getAngularVelocityYDevice()
1994    {
1995        return getAngularVelocityYDevice(true);
1996    }
1997    
1998    /**
1999     * The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
2000     * <p>
2001     * This value is not mount-calibrated.
2002     * 
2003     * <ul>
2004     *   <li> <b>Minimum Value:</b> -1998.048780487805
2005     *   <li> <b>Maximum Value:</b> 1997.987804878049
2006     *   <li> <b>Default Value:</b> 0
2007     *   <li> <b>Units:</b> dps
2008     * </ul>
2009     * 
2010     * Default Rates:
2011     * <ul>
2012     *   <li> <b>CAN:</b> 4.0 Hz
2013     * </ul>
2014     * <p>
2015     * This refreshes and returns a cached StatusSignal object.
2016     * 
2017     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2018     * @return AngularVelocityYDevice Status Signal Object
2019     */
2020    public StatusSignal<AngularVelocity> getAngularVelocityYDevice(boolean refresh)
2021    {
2022        @SuppressWarnings("unchecked")
2023        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityY.value, AngularVelocity.class, val -> DegreesPerSecond.of(val), "AngularVelocityYDevice", true, refresh);
2024        return retval;
2025    }
2026        
2027    /**
2028     * The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
2029     * <p>
2030     * This value is not mount-calibrated.
2031     * 
2032     * <ul>
2033     *   <li> <b>Minimum Value:</b> -1998.048780487805
2034     *   <li> <b>Maximum Value:</b> 1997.987804878049
2035     *   <li> <b>Default Value:</b> 0
2036     *   <li> <b>Units:</b> dps
2037     * </ul>
2038     * 
2039     * Default Rates:
2040     * <ul>
2041     *   <li> <b>CAN:</b> 4.0 Hz
2042     * </ul>
2043     * <p>
2044     * This refreshes and returns a cached StatusSignal object.
2045     * 
2046     * @return AngularVelocityZDevice Status Signal Object
2047     */
2048    public StatusSignal<AngularVelocity> getAngularVelocityZDevice()
2049    {
2050        return getAngularVelocityZDevice(true);
2051    }
2052    
2053    /**
2054     * The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
2055     * <p>
2056     * This value is not mount-calibrated.
2057     * 
2058     * <ul>
2059     *   <li> <b>Minimum Value:</b> -1998.048780487805
2060     *   <li> <b>Maximum Value:</b> 1997.987804878049
2061     *   <li> <b>Default Value:</b> 0
2062     *   <li> <b>Units:</b> dps
2063     * </ul>
2064     * 
2065     * Default Rates:
2066     * <ul>
2067     *   <li> <b>CAN:</b> 4.0 Hz
2068     * </ul>
2069     * <p>
2070     * This refreshes and returns a cached StatusSignal object.
2071     * 
2072     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2073     * @return AngularVelocityZDevice Status Signal Object
2074     */
2075    public StatusSignal<AngularVelocity> getAngularVelocityZDevice(boolean refresh)
2076    {
2077        @SuppressWarnings("unchecked")
2078        var retval = super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityZ.value, AngularVelocity.class, val -> DegreesPerSecond.of(val), "AngularVelocityZDevice", true, refresh);
2079        return retval;
2080    }
2081        
2082    /**
2083     * The biased magnitude of the magnetic field measured by the Pigeon 2
2084     * in the X direction. This is only valid after performing a
2085     * magnetometer calibration.
2086     * 
2087     * <ul>
2088     *   <li> <b>Minimum Value:</b> -19660.8
2089     *   <li> <b>Maximum Value:</b> 19660.2
2090     *   <li> <b>Default Value:</b> 0
2091     *   <li> <b>Units:</b> uT
2092     * </ul>
2093     * 
2094     * Default Rates:
2095     * <ul>
2096     *   <li> <b>CAN:</b> 4.0 Hz
2097     * </ul>
2098     * <p>
2099     * This refreshes and returns a cached StatusSignal object.
2100     * 
2101     * @return MagneticFieldX Status Signal Object
2102     */
2103    public StatusSignal<Double> getMagneticFieldX()
2104    {
2105        return getMagneticFieldX(true);
2106    }
2107    
2108    /**
2109     * The biased magnitude of the magnetic field measured by the Pigeon 2
2110     * in the X direction. This is only valid after performing a
2111     * magnetometer calibration.
2112     * 
2113     * <ul>
2114     *   <li> <b>Minimum Value:</b> -19660.8
2115     *   <li> <b>Maximum Value:</b> 19660.2
2116     *   <li> <b>Default Value:</b> 0
2117     *   <li> <b>Units:</b> uT
2118     * </ul>
2119     * 
2120     * Default Rates:
2121     * <ul>
2122     *   <li> <b>CAN:</b> 4.0 Hz
2123     * </ul>
2124     * <p>
2125     * This refreshes and returns a cached StatusSignal object.
2126     * 
2127     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2128     * @return MagneticFieldX Status Signal Object
2129     */
2130    public StatusSignal<Double> getMagneticFieldX(boolean refresh)
2131    {
2132        @SuppressWarnings("unchecked")
2133        var retval = super.lookupStatusSignal(SpnValue.Pigeon2MagneticFieldX.value, Double.class, val -> val, "MagneticFieldX", true, refresh);
2134        return retval;
2135    }
2136        
2137    /**
2138     * The biased magnitude of the magnetic field measured by the Pigeon 2
2139     * in the Y direction. This is only valid after performing a
2140     * magnetometer calibration.
2141     * 
2142     * <ul>
2143     *   <li> <b>Minimum Value:</b> -19660.8
2144     *   <li> <b>Maximum Value:</b> 19660.2
2145     *   <li> <b>Default Value:</b> 0
2146     *   <li> <b>Units:</b> uT
2147     * </ul>
2148     * 
2149     * Default Rates:
2150     * <ul>
2151     *   <li> <b>CAN:</b> 4.0 Hz
2152     * </ul>
2153     * <p>
2154     * This refreshes and returns a cached StatusSignal object.
2155     * 
2156     * @return MagneticFieldY Status Signal Object
2157     */
2158    public StatusSignal<Double> getMagneticFieldY()
2159    {
2160        return getMagneticFieldY(true);
2161    }
2162    
2163    /**
2164     * The biased magnitude of the magnetic field measured by the Pigeon 2
2165     * in the Y direction. This is only valid after performing a
2166     * magnetometer calibration.
2167     * 
2168     * <ul>
2169     *   <li> <b>Minimum Value:</b> -19660.8
2170     *   <li> <b>Maximum Value:</b> 19660.2
2171     *   <li> <b>Default Value:</b> 0
2172     *   <li> <b>Units:</b> uT
2173     * </ul>
2174     * 
2175     * Default Rates:
2176     * <ul>
2177     *   <li> <b>CAN:</b> 4.0 Hz
2178     * </ul>
2179     * <p>
2180     * This refreshes and returns a cached StatusSignal object.
2181     * 
2182     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2183     * @return MagneticFieldY Status Signal Object
2184     */
2185    public StatusSignal<Double> getMagneticFieldY(boolean refresh)
2186    {
2187        @SuppressWarnings("unchecked")
2188        var retval = super.lookupStatusSignal(SpnValue.Pigeon2MagneticFieldY.value, Double.class, val -> val, "MagneticFieldY", true, refresh);
2189        return retval;
2190    }
2191        
2192    /**
2193     * The biased magnitude of the magnetic field measured by the Pigeon 2
2194     * in the Z direction. This is only valid after performing a
2195     * magnetometer calibration.
2196     * 
2197     * <ul>
2198     *   <li> <b>Minimum Value:</b> -19660.8
2199     *   <li> <b>Maximum Value:</b> 19660.2
2200     *   <li> <b>Default Value:</b> 0
2201     *   <li> <b>Units:</b> uT
2202     * </ul>
2203     * 
2204     * Default Rates:
2205     * <ul>
2206     *   <li> <b>CAN:</b> 4.0 Hz
2207     * </ul>
2208     * <p>
2209     * This refreshes and returns a cached StatusSignal object.
2210     * 
2211     * @return MagneticFieldZ Status Signal Object
2212     */
2213    public StatusSignal<Double> getMagneticFieldZ()
2214    {
2215        return getMagneticFieldZ(true);
2216    }
2217    
2218    /**
2219     * The biased magnitude of the magnetic field measured by the Pigeon 2
2220     * in the Z direction. This is only valid after performing a
2221     * magnetometer calibration.
2222     * 
2223     * <ul>
2224     *   <li> <b>Minimum Value:</b> -19660.8
2225     *   <li> <b>Maximum Value:</b> 19660.2
2226     *   <li> <b>Default Value:</b> 0
2227     *   <li> <b>Units:</b> uT
2228     * </ul>
2229     * 
2230     * Default Rates:
2231     * <ul>
2232     *   <li> <b>CAN:</b> 4.0 Hz
2233     * </ul>
2234     * <p>
2235     * This refreshes and returns a cached StatusSignal object.
2236     * 
2237     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2238     * @return MagneticFieldZ Status Signal Object
2239     */
2240    public StatusSignal<Double> getMagneticFieldZ(boolean refresh)
2241    {
2242        @SuppressWarnings("unchecked")
2243        var retval = super.lookupStatusSignal(SpnValue.Pigeon2MagneticFieldZ.value, Double.class, val -> val, "MagneticFieldZ", true, refresh);
2244        return retval;
2245    }
2246        
2247    /**
2248     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
2249     * the X direction. This is only valid after performing a magnetometer
2250     * calibration.
2251     * 
2252     * <ul>
2253     *   <li> <b>Minimum Value:</b> -19660.8
2254     *   <li> <b>Maximum Value:</b> 19660.2
2255     *   <li> <b>Default Value:</b> 0
2256     *   <li> <b>Units:</b> uT
2257     * </ul>
2258     * 
2259     * Default Rates:
2260     * <ul>
2261     *   <li> <b>CAN:</b> 4.0 Hz
2262     * </ul>
2263     * <p>
2264     * This refreshes and returns a cached StatusSignal object.
2265     * 
2266     * @return RawMagneticFieldX Status Signal Object
2267     */
2268    public StatusSignal<Double> getRawMagneticFieldX()
2269    {
2270        return getRawMagneticFieldX(true);
2271    }
2272    
2273    /**
2274     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
2275     * the X direction. This is only valid after performing a magnetometer
2276     * calibration.
2277     * 
2278     * <ul>
2279     *   <li> <b>Minimum Value:</b> -19660.8
2280     *   <li> <b>Maximum Value:</b> 19660.2
2281     *   <li> <b>Default Value:</b> 0
2282     *   <li> <b>Units:</b> uT
2283     * </ul>
2284     * 
2285     * Default Rates:
2286     * <ul>
2287     *   <li> <b>CAN:</b> 4.0 Hz
2288     * </ul>
2289     * <p>
2290     * This refreshes and returns a cached StatusSignal object.
2291     * 
2292     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2293     * @return RawMagneticFieldX Status Signal Object
2294     */
2295    public StatusSignal<Double> getRawMagneticFieldX(boolean refresh)
2296    {
2297        @SuppressWarnings("unchecked")
2298        var retval = super.lookupStatusSignal(SpnValue.Pigeon2RawMagneticFieldX.value, Double.class, val -> val, "RawMagneticFieldX", true, refresh);
2299        return retval;
2300    }
2301        
2302    /**
2303     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
2304     * the Y direction. This is only valid after performing a magnetometer
2305     * calibration.
2306     * 
2307     * <ul>
2308     *   <li> <b>Minimum Value:</b> -19660.8
2309     *   <li> <b>Maximum Value:</b> 19660.2
2310     *   <li> <b>Default Value:</b> 0
2311     *   <li> <b>Units:</b> uT
2312     * </ul>
2313     * 
2314     * Default Rates:
2315     * <ul>
2316     *   <li> <b>CAN:</b> 4.0 Hz
2317     * </ul>
2318     * <p>
2319     * This refreshes and returns a cached StatusSignal object.
2320     * 
2321     * @return RawMagneticFieldY Status Signal Object
2322     */
2323    public StatusSignal<Double> getRawMagneticFieldY()
2324    {
2325        return getRawMagneticFieldY(true);
2326    }
2327    
2328    /**
2329     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
2330     * the Y direction. This is only valid after performing a magnetometer
2331     * calibration.
2332     * 
2333     * <ul>
2334     *   <li> <b>Minimum Value:</b> -19660.8
2335     *   <li> <b>Maximum Value:</b> 19660.2
2336     *   <li> <b>Default Value:</b> 0
2337     *   <li> <b>Units:</b> uT
2338     * </ul>
2339     * 
2340     * Default Rates:
2341     * <ul>
2342     *   <li> <b>CAN:</b> 4.0 Hz
2343     * </ul>
2344     * <p>
2345     * This refreshes and returns a cached StatusSignal object.
2346     * 
2347     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2348     * @return RawMagneticFieldY Status Signal Object
2349     */
2350    public StatusSignal<Double> getRawMagneticFieldY(boolean refresh)
2351    {
2352        @SuppressWarnings("unchecked")
2353        var retval = super.lookupStatusSignal(SpnValue.Pigeon2RawMagneticFieldY.value, Double.class, val -> val, "RawMagneticFieldY", true, refresh);
2354        return retval;
2355    }
2356        
2357    /**
2358     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
2359     * the Z direction. This is only valid after performing a magnetometer
2360     * calibration.
2361     * 
2362     * <ul>
2363     *   <li> <b>Minimum Value:</b> -19660.8
2364     *   <li> <b>Maximum Value:</b> 19660.2
2365     *   <li> <b>Default Value:</b> 0
2366     *   <li> <b>Units:</b> uT
2367     * </ul>
2368     * 
2369     * Default Rates:
2370     * <ul>
2371     *   <li> <b>CAN:</b> 4.0 Hz
2372     * </ul>
2373     * <p>
2374     * This refreshes and returns a cached StatusSignal object.
2375     * 
2376     * @return RawMagneticFieldZ Status Signal Object
2377     */
2378    public StatusSignal<Double> getRawMagneticFieldZ()
2379    {
2380        return getRawMagneticFieldZ(true);
2381    }
2382    
2383    /**
2384     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
2385     * the Z direction. This is only valid after performing a magnetometer
2386     * calibration.
2387     * 
2388     * <ul>
2389     *   <li> <b>Minimum Value:</b> -19660.8
2390     *   <li> <b>Maximum Value:</b> 19660.2
2391     *   <li> <b>Default Value:</b> 0
2392     *   <li> <b>Units:</b> uT
2393     * </ul>
2394     * 
2395     * Default Rates:
2396     * <ul>
2397     *   <li> <b>CAN:</b> 4.0 Hz
2398     * </ul>
2399     * <p>
2400     * This refreshes and returns a cached StatusSignal object.
2401     * 
2402     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2403     * @return RawMagneticFieldZ Status Signal Object
2404     */
2405    public StatusSignal<Double> getRawMagneticFieldZ(boolean refresh)
2406    {
2407        @SuppressWarnings("unchecked")
2408        var retval = super.lookupStatusSignal(SpnValue.Pigeon2RawMagneticFieldZ.value, Double.class, val -> val, "RawMagneticFieldZ", true, refresh);
2409        return retval;
2410    }
2411        
2412    /**
2413     * Whether the device is Phoenix Pro licensed.
2414     * 
2415     * <ul>
2416     *   <li> <b>Default Value:</b> False
2417     * </ul>
2418     * 
2419     * Default Rates:
2420     * <ul>
2421     *   <li> <b>CAN:</b> 4.0 Hz
2422     * </ul>
2423     * <p>
2424     * This refreshes and returns a cached StatusSignal object.
2425     * 
2426     * @return IsProLicensed Status Signal Object
2427     */
2428    public StatusSignal<Boolean> getIsProLicensed()
2429    {
2430        return getIsProLicensed(true);
2431    }
2432    
2433    /**
2434     * Whether the device is Phoenix Pro licensed.
2435     * 
2436     * <ul>
2437     *   <li> <b>Default Value:</b> False
2438     * </ul>
2439     * 
2440     * Default Rates:
2441     * <ul>
2442     *   <li> <b>CAN:</b> 4.0 Hz
2443     * </ul>
2444     * <p>
2445     * This refreshes and returns a cached StatusSignal object.
2446     * 
2447     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2448     * @return IsProLicensed Status Signal Object
2449     */
2450    public StatusSignal<Boolean> getIsProLicensed(boolean refresh)
2451    {
2452        @SuppressWarnings("unchecked")
2453        var retval = super.lookupStatusSignal(SpnValue.Version_IsProLicensed.value, Boolean.class, val -> val != 0, "IsProLicensed", true, refresh);
2454        return retval;
2455    }
2456        
2457    /**
2458     * Hardware fault occurred
2459     * 
2460     * <ul>
2461     *   <li> <b>Default Value:</b> False
2462     * </ul>
2463     * 
2464     * Default Rates:
2465     * <ul>
2466     *   <li> <b>CAN:</b> 4.0 Hz
2467     * </ul>
2468     * <p>
2469     * This refreshes and returns a cached StatusSignal object.
2470     * 
2471     * @return Fault_Hardware Status Signal Object
2472     */
2473    public StatusSignal<Boolean> getFault_Hardware()
2474    {
2475        return getFault_Hardware(true);
2476    }
2477    
2478    /**
2479     * Hardware fault occurred
2480     * 
2481     * <ul>
2482     *   <li> <b>Default Value:</b> False
2483     * </ul>
2484     * 
2485     * Default Rates:
2486     * <ul>
2487     *   <li> <b>CAN:</b> 4.0 Hz
2488     * </ul>
2489     * <p>
2490     * This refreshes and returns a cached StatusSignal object.
2491     * 
2492     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2493     * @return Fault_Hardware Status Signal Object
2494     */
2495    public StatusSignal<Boolean> getFault_Hardware(boolean refresh)
2496    {
2497        @SuppressWarnings("unchecked")
2498        var retval = super.lookupStatusSignal(SpnValue.Fault_Hardware.value, Boolean.class, val -> val != 0, "Fault_Hardware", true, refresh);
2499        return retval;
2500    }
2501        
2502    /**
2503     * Hardware fault occurred
2504     * 
2505     * <ul>
2506     *   <li> <b>Default Value:</b> False
2507     * </ul>
2508     * 
2509     * Default Rates:
2510     * <ul>
2511     *   <li> <b>CAN:</b> 4.0 Hz
2512     * </ul>
2513     * <p>
2514     * This refreshes and returns a cached StatusSignal object.
2515     * 
2516     * @return StickyFault_Hardware Status Signal Object
2517     */
2518    public StatusSignal<Boolean> getStickyFault_Hardware()
2519    {
2520        return getStickyFault_Hardware(true);
2521    }
2522    
2523    /**
2524     * Hardware fault occurred
2525     * 
2526     * <ul>
2527     *   <li> <b>Default Value:</b> False
2528     * </ul>
2529     * 
2530     * Default Rates:
2531     * <ul>
2532     *   <li> <b>CAN:</b> 4.0 Hz
2533     * </ul>
2534     * <p>
2535     * This refreshes and returns a cached StatusSignal object.
2536     * 
2537     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2538     * @return StickyFault_Hardware Status Signal Object
2539     */
2540    public StatusSignal<Boolean> getStickyFault_Hardware(boolean refresh)
2541    {
2542        @SuppressWarnings("unchecked")
2543        var retval = super.lookupStatusSignal(SpnValue.StickyFault_Hardware.value, Boolean.class, val -> val != 0, "StickyFault_Hardware", true, refresh);
2544        return retval;
2545    }
2546        
2547    /**
2548     * Device supply voltage dropped to near brownout levels
2549     * 
2550     * <ul>
2551     *   <li> <b>Default Value:</b> False
2552     * </ul>
2553     * 
2554     * Default Rates:
2555     * <ul>
2556     *   <li> <b>CAN:</b> 4.0 Hz
2557     * </ul>
2558     * <p>
2559     * This refreshes and returns a cached StatusSignal object.
2560     * 
2561     * @return Fault_Undervoltage Status Signal Object
2562     */
2563    public StatusSignal<Boolean> getFault_Undervoltage()
2564    {
2565        return getFault_Undervoltage(true);
2566    }
2567    
2568    /**
2569     * Device supply voltage dropped to near brownout levels
2570     * 
2571     * <ul>
2572     *   <li> <b>Default Value:</b> False
2573     * </ul>
2574     * 
2575     * Default Rates:
2576     * <ul>
2577     *   <li> <b>CAN:</b> 4.0 Hz
2578     * </ul>
2579     * <p>
2580     * This refreshes and returns a cached StatusSignal object.
2581     * 
2582     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2583     * @return Fault_Undervoltage Status Signal Object
2584     */
2585    public StatusSignal<Boolean> getFault_Undervoltage(boolean refresh)
2586    {
2587        @SuppressWarnings("unchecked")
2588        var retval = super.lookupStatusSignal(SpnValue.Fault_Undervoltage.value, Boolean.class, val -> val != 0, "Fault_Undervoltage", true, refresh);
2589        return retval;
2590    }
2591        
2592    /**
2593     * Device supply voltage dropped to near brownout levels
2594     * 
2595     * <ul>
2596     *   <li> <b>Default Value:</b> False
2597     * </ul>
2598     * 
2599     * Default Rates:
2600     * <ul>
2601     *   <li> <b>CAN:</b> 4.0 Hz
2602     * </ul>
2603     * <p>
2604     * This refreshes and returns a cached StatusSignal object.
2605     * 
2606     * @return StickyFault_Undervoltage Status Signal Object
2607     */
2608    public StatusSignal<Boolean> getStickyFault_Undervoltage()
2609    {
2610        return getStickyFault_Undervoltage(true);
2611    }
2612    
2613    /**
2614     * Device supply voltage dropped to near brownout levels
2615     * 
2616     * <ul>
2617     *   <li> <b>Default Value:</b> False
2618     * </ul>
2619     * 
2620     * Default Rates:
2621     * <ul>
2622     *   <li> <b>CAN:</b> 4.0 Hz
2623     * </ul>
2624     * <p>
2625     * This refreshes and returns a cached StatusSignal object.
2626     * 
2627     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2628     * @return StickyFault_Undervoltage Status Signal Object
2629     */
2630    public StatusSignal<Boolean> getStickyFault_Undervoltage(boolean refresh)
2631    {
2632        @SuppressWarnings("unchecked")
2633        var retval = super.lookupStatusSignal(SpnValue.StickyFault_Undervoltage.value, Boolean.class, val -> val != 0, "StickyFault_Undervoltage", true, refresh);
2634        return retval;
2635    }
2636        
2637    /**
2638     * Device boot while detecting the enable signal
2639     * 
2640     * <ul>
2641     *   <li> <b>Default Value:</b> False
2642     * </ul>
2643     * 
2644     * Default Rates:
2645     * <ul>
2646     *   <li> <b>CAN:</b> 4.0 Hz
2647     * </ul>
2648     * <p>
2649     * This refreshes and returns a cached StatusSignal object.
2650     * 
2651     * @return Fault_BootDuringEnable Status Signal Object
2652     */
2653    public StatusSignal<Boolean> getFault_BootDuringEnable()
2654    {
2655        return getFault_BootDuringEnable(true);
2656    }
2657    
2658    /**
2659     * Device boot while detecting the enable signal
2660     * 
2661     * <ul>
2662     *   <li> <b>Default Value:</b> False
2663     * </ul>
2664     * 
2665     * Default Rates:
2666     * <ul>
2667     *   <li> <b>CAN:</b> 4.0 Hz
2668     * </ul>
2669     * <p>
2670     * This refreshes and returns a cached StatusSignal object.
2671     * 
2672     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2673     * @return Fault_BootDuringEnable Status Signal Object
2674     */
2675    public StatusSignal<Boolean> getFault_BootDuringEnable(boolean refresh)
2676    {
2677        @SuppressWarnings("unchecked")
2678        var retval = super.lookupStatusSignal(SpnValue.Fault_BootDuringEnable.value, Boolean.class, val -> val != 0, "Fault_BootDuringEnable", true, refresh);
2679        return retval;
2680    }
2681        
2682    /**
2683     * Device boot while detecting the enable signal
2684     * 
2685     * <ul>
2686     *   <li> <b>Default Value:</b> False
2687     * </ul>
2688     * 
2689     * Default Rates:
2690     * <ul>
2691     *   <li> <b>CAN:</b> 4.0 Hz
2692     * </ul>
2693     * <p>
2694     * This refreshes and returns a cached StatusSignal object.
2695     * 
2696     * @return StickyFault_BootDuringEnable Status Signal Object
2697     */
2698    public StatusSignal<Boolean> getStickyFault_BootDuringEnable()
2699    {
2700        return getStickyFault_BootDuringEnable(true);
2701    }
2702    
2703    /**
2704     * Device boot while detecting the enable signal
2705     * 
2706     * <ul>
2707     *   <li> <b>Default Value:</b> False
2708     * </ul>
2709     * 
2710     * Default Rates:
2711     * <ul>
2712     *   <li> <b>CAN:</b> 4.0 Hz
2713     * </ul>
2714     * <p>
2715     * This refreshes and returns a cached StatusSignal object.
2716     * 
2717     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2718     * @return StickyFault_BootDuringEnable Status Signal Object
2719     */
2720    public StatusSignal<Boolean> getStickyFault_BootDuringEnable(boolean refresh)
2721    {
2722        @SuppressWarnings("unchecked")
2723        var retval = super.lookupStatusSignal(SpnValue.StickyFault_BootDuringEnable.value, Boolean.class, val -> val != 0, "StickyFault_BootDuringEnable", true, refresh);
2724        return retval;
2725    }
2726        
2727    /**
2728     * An unlicensed feature is in use, device may not behave as expected.
2729     * 
2730     * <ul>
2731     *   <li> <b>Default Value:</b> False
2732     * </ul>
2733     * 
2734     * Default Rates:
2735     * <ul>
2736     *   <li> <b>CAN:</b> 4.0 Hz
2737     * </ul>
2738     * <p>
2739     * This refreshes and returns a cached StatusSignal object.
2740     * 
2741     * @return Fault_UnlicensedFeatureInUse Status Signal Object
2742     */
2743    public StatusSignal<Boolean> getFault_UnlicensedFeatureInUse()
2744    {
2745        return getFault_UnlicensedFeatureInUse(true);
2746    }
2747    
2748    /**
2749     * An unlicensed feature is in use, device may not behave as expected.
2750     * 
2751     * <ul>
2752     *   <li> <b>Default Value:</b> False
2753     * </ul>
2754     * 
2755     * Default Rates:
2756     * <ul>
2757     *   <li> <b>CAN:</b> 4.0 Hz
2758     * </ul>
2759     * <p>
2760     * This refreshes and returns a cached StatusSignal object.
2761     * 
2762     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2763     * @return Fault_UnlicensedFeatureInUse Status Signal Object
2764     */
2765    public StatusSignal<Boolean> getFault_UnlicensedFeatureInUse(boolean refresh)
2766    {
2767        @SuppressWarnings("unchecked")
2768        var retval = super.lookupStatusSignal(SpnValue.Fault_UnlicensedFeatureInUse.value, Boolean.class, val -> val != 0, "Fault_UnlicensedFeatureInUse", true, refresh);
2769        return retval;
2770    }
2771        
2772    /**
2773     * An unlicensed feature is in use, device may not behave as expected.
2774     * 
2775     * <ul>
2776     *   <li> <b>Default Value:</b> False
2777     * </ul>
2778     * 
2779     * Default Rates:
2780     * <ul>
2781     *   <li> <b>CAN:</b> 4.0 Hz
2782     * </ul>
2783     * <p>
2784     * This refreshes and returns a cached StatusSignal object.
2785     * 
2786     * @return StickyFault_UnlicensedFeatureInUse Status Signal Object
2787     */
2788    public StatusSignal<Boolean> getStickyFault_UnlicensedFeatureInUse()
2789    {
2790        return getStickyFault_UnlicensedFeatureInUse(true);
2791    }
2792    
2793    /**
2794     * An unlicensed feature is in use, device may not behave as expected.
2795     * 
2796     * <ul>
2797     *   <li> <b>Default Value:</b> False
2798     * </ul>
2799     * 
2800     * Default Rates:
2801     * <ul>
2802     *   <li> <b>CAN:</b> 4.0 Hz
2803     * </ul>
2804     * <p>
2805     * This refreshes and returns a cached StatusSignal object.
2806     * 
2807     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2808     * @return StickyFault_UnlicensedFeatureInUse Status Signal Object
2809     */
2810    public StatusSignal<Boolean> getStickyFault_UnlicensedFeatureInUse(boolean refresh)
2811    {
2812        @SuppressWarnings("unchecked")
2813        var retval = super.lookupStatusSignal(SpnValue.StickyFault_UnlicensedFeatureInUse.value, Boolean.class, val -> val != 0, "StickyFault_UnlicensedFeatureInUse", true, refresh);
2814        return retval;
2815    }
2816        
2817    /**
2818     * Bootup checks failed: Accelerometer
2819     * 
2820     * <ul>
2821     *   <li> <b>Default Value:</b> False
2822     * </ul>
2823     * 
2824     * Default Rates:
2825     * <ul>
2826     *   <li> <b>CAN:</b> 4.0 Hz
2827     * </ul>
2828     * <p>
2829     * This refreshes and returns a cached StatusSignal object.
2830     * 
2831     * @return Fault_BootupAccelerometer Status Signal Object
2832     */
2833    public StatusSignal<Boolean> getFault_BootupAccelerometer()
2834    {
2835        return getFault_BootupAccelerometer(true);
2836    }
2837    
2838    /**
2839     * Bootup checks failed: Accelerometer
2840     * 
2841     * <ul>
2842     *   <li> <b>Default Value:</b> False
2843     * </ul>
2844     * 
2845     * Default Rates:
2846     * <ul>
2847     *   <li> <b>CAN:</b> 4.0 Hz
2848     * </ul>
2849     * <p>
2850     * This refreshes and returns a cached StatusSignal object.
2851     * 
2852     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2853     * @return Fault_BootupAccelerometer Status Signal Object
2854     */
2855    public StatusSignal<Boolean> getFault_BootupAccelerometer(boolean refresh)
2856    {
2857        @SuppressWarnings("unchecked")
2858        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootupAccel.value, Boolean.class, val -> val != 0, "Fault_BootupAccelerometer", true, refresh);
2859        return retval;
2860    }
2861        
2862    /**
2863     * Bootup checks failed: Accelerometer
2864     * 
2865     * <ul>
2866     *   <li> <b>Default Value:</b> False
2867     * </ul>
2868     * 
2869     * Default Rates:
2870     * <ul>
2871     *   <li> <b>CAN:</b> 4.0 Hz
2872     * </ul>
2873     * <p>
2874     * This refreshes and returns a cached StatusSignal object.
2875     * 
2876     * @return StickyFault_BootupAccelerometer Status Signal Object
2877     */
2878    public StatusSignal<Boolean> getStickyFault_BootupAccelerometer()
2879    {
2880        return getStickyFault_BootupAccelerometer(true);
2881    }
2882    
2883    /**
2884     * Bootup checks failed: Accelerometer
2885     * 
2886     * <ul>
2887     *   <li> <b>Default Value:</b> False
2888     * </ul>
2889     * 
2890     * Default Rates:
2891     * <ul>
2892     *   <li> <b>CAN:</b> 4.0 Hz
2893     * </ul>
2894     * <p>
2895     * This refreshes and returns a cached StatusSignal object.
2896     * 
2897     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2898     * @return StickyFault_BootupAccelerometer Status Signal Object
2899     */
2900    public StatusSignal<Boolean> getStickyFault_BootupAccelerometer(boolean refresh)
2901    {
2902        @SuppressWarnings("unchecked")
2903        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootupAccel.value, Boolean.class, val -> val != 0, "StickyFault_BootupAccelerometer", true, refresh);
2904        return retval;
2905    }
2906        
2907    /**
2908     * Bootup checks failed: Gyroscope
2909     * 
2910     * <ul>
2911     *   <li> <b>Default Value:</b> False
2912     * </ul>
2913     * 
2914     * Default Rates:
2915     * <ul>
2916     *   <li> <b>CAN:</b> 4.0 Hz
2917     * </ul>
2918     * <p>
2919     * This refreshes and returns a cached StatusSignal object.
2920     * 
2921     * @return Fault_BootupGyroscope Status Signal Object
2922     */
2923    public StatusSignal<Boolean> getFault_BootupGyroscope()
2924    {
2925        return getFault_BootupGyroscope(true);
2926    }
2927    
2928    /**
2929     * Bootup checks failed: Gyroscope
2930     * 
2931     * <ul>
2932     *   <li> <b>Default Value:</b> False
2933     * </ul>
2934     * 
2935     * Default Rates:
2936     * <ul>
2937     *   <li> <b>CAN:</b> 4.0 Hz
2938     * </ul>
2939     * <p>
2940     * This refreshes and returns a cached StatusSignal object.
2941     * 
2942     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2943     * @return Fault_BootupGyroscope Status Signal Object
2944     */
2945    public StatusSignal<Boolean> getFault_BootupGyroscope(boolean refresh)
2946    {
2947        @SuppressWarnings("unchecked")
2948        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootupGyros.value, Boolean.class, val -> val != 0, "Fault_BootupGyroscope", true, refresh);
2949        return retval;
2950    }
2951        
2952    /**
2953     * Bootup checks failed: Gyroscope
2954     * 
2955     * <ul>
2956     *   <li> <b>Default Value:</b> False
2957     * </ul>
2958     * 
2959     * Default Rates:
2960     * <ul>
2961     *   <li> <b>CAN:</b> 4.0 Hz
2962     * </ul>
2963     * <p>
2964     * This refreshes and returns a cached StatusSignal object.
2965     * 
2966     * @return StickyFault_BootupGyroscope Status Signal Object
2967     */
2968    public StatusSignal<Boolean> getStickyFault_BootupGyroscope()
2969    {
2970        return getStickyFault_BootupGyroscope(true);
2971    }
2972    
2973    /**
2974     * Bootup checks failed: Gyroscope
2975     * 
2976     * <ul>
2977     *   <li> <b>Default Value:</b> False
2978     * </ul>
2979     * 
2980     * Default Rates:
2981     * <ul>
2982     *   <li> <b>CAN:</b> 4.0 Hz
2983     * </ul>
2984     * <p>
2985     * This refreshes and returns a cached StatusSignal object.
2986     * 
2987     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
2988     * @return StickyFault_BootupGyroscope Status Signal Object
2989     */
2990    public StatusSignal<Boolean> getStickyFault_BootupGyroscope(boolean refresh)
2991    {
2992        @SuppressWarnings("unchecked")
2993        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootupGyros.value, Boolean.class, val -> val != 0, "StickyFault_BootupGyroscope", true, refresh);
2994        return retval;
2995    }
2996        
2997    /**
2998     * Bootup checks failed: Magnetometer
2999     * 
3000     * <ul>
3001     *   <li> <b>Default Value:</b> False
3002     * </ul>
3003     * 
3004     * Default Rates:
3005     * <ul>
3006     *   <li> <b>CAN:</b> 4.0 Hz
3007     * </ul>
3008     * <p>
3009     * This refreshes and returns a cached StatusSignal object.
3010     * 
3011     * @return Fault_BootupMagnetometer Status Signal Object
3012     */
3013    public StatusSignal<Boolean> getFault_BootupMagnetometer()
3014    {
3015        return getFault_BootupMagnetometer(true);
3016    }
3017    
3018    /**
3019     * Bootup checks failed: Magnetometer
3020     * 
3021     * <ul>
3022     *   <li> <b>Default Value:</b> False
3023     * </ul>
3024     * 
3025     * Default Rates:
3026     * <ul>
3027     *   <li> <b>CAN:</b> 4.0 Hz
3028     * </ul>
3029     * <p>
3030     * This refreshes and returns a cached StatusSignal object.
3031     * 
3032     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3033     * @return Fault_BootupMagnetometer Status Signal Object
3034     */
3035    public StatusSignal<Boolean> getFault_BootupMagnetometer(boolean refresh)
3036    {
3037        @SuppressWarnings("unchecked")
3038        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootupMagne.value, Boolean.class, val -> val != 0, "Fault_BootupMagnetometer", true, refresh);
3039        return retval;
3040    }
3041        
3042    /**
3043     * Bootup checks failed: Magnetometer
3044     * 
3045     * <ul>
3046     *   <li> <b>Default Value:</b> False
3047     * </ul>
3048     * 
3049     * Default Rates:
3050     * <ul>
3051     *   <li> <b>CAN:</b> 4.0 Hz
3052     * </ul>
3053     * <p>
3054     * This refreshes and returns a cached StatusSignal object.
3055     * 
3056     * @return StickyFault_BootupMagnetometer Status Signal Object
3057     */
3058    public StatusSignal<Boolean> getStickyFault_BootupMagnetometer()
3059    {
3060        return getStickyFault_BootupMagnetometer(true);
3061    }
3062    
3063    /**
3064     * Bootup checks failed: Magnetometer
3065     * 
3066     * <ul>
3067     *   <li> <b>Default Value:</b> False
3068     * </ul>
3069     * 
3070     * Default Rates:
3071     * <ul>
3072     *   <li> <b>CAN:</b> 4.0 Hz
3073     * </ul>
3074     * <p>
3075     * This refreshes and returns a cached StatusSignal object.
3076     * 
3077     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3078     * @return StickyFault_BootupMagnetometer Status Signal Object
3079     */
3080    public StatusSignal<Boolean> getStickyFault_BootupMagnetometer(boolean refresh)
3081    {
3082        @SuppressWarnings("unchecked")
3083        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootupMagne.value, Boolean.class, val -> val != 0, "StickyFault_BootupMagnetometer", true, refresh);
3084        return retval;
3085    }
3086        
3087    /**
3088     * Motion Detected during bootup.
3089     * 
3090     * <ul>
3091     *   <li> <b>Default Value:</b> False
3092     * </ul>
3093     * 
3094     * Default Rates:
3095     * <ul>
3096     *   <li> <b>CAN:</b> 4.0 Hz
3097     * </ul>
3098     * <p>
3099     * This refreshes and returns a cached StatusSignal object.
3100     * 
3101     * @return Fault_BootIntoMotion Status Signal Object
3102     */
3103    public StatusSignal<Boolean> getFault_BootIntoMotion()
3104    {
3105        return getFault_BootIntoMotion(true);
3106    }
3107    
3108    /**
3109     * Motion Detected during bootup.
3110     * 
3111     * <ul>
3112     *   <li> <b>Default Value:</b> False
3113     * </ul>
3114     * 
3115     * Default Rates:
3116     * <ul>
3117     *   <li> <b>CAN:</b> 4.0 Hz
3118     * </ul>
3119     * <p>
3120     * This refreshes and returns a cached StatusSignal object.
3121     * 
3122     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3123     * @return Fault_BootIntoMotion Status Signal Object
3124     */
3125    public StatusSignal<Boolean> getFault_BootIntoMotion(boolean refresh)
3126    {
3127        @SuppressWarnings("unchecked")
3128        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootIntoMotion.value, Boolean.class, val -> val != 0, "Fault_BootIntoMotion", true, refresh);
3129        return retval;
3130    }
3131        
3132    /**
3133     * Motion Detected during bootup.
3134     * 
3135     * <ul>
3136     *   <li> <b>Default Value:</b> False
3137     * </ul>
3138     * 
3139     * Default Rates:
3140     * <ul>
3141     *   <li> <b>CAN:</b> 4.0 Hz
3142     * </ul>
3143     * <p>
3144     * This refreshes and returns a cached StatusSignal object.
3145     * 
3146     * @return StickyFault_BootIntoMotion Status Signal Object
3147     */
3148    public StatusSignal<Boolean> getStickyFault_BootIntoMotion()
3149    {
3150        return getStickyFault_BootIntoMotion(true);
3151    }
3152    
3153    /**
3154     * Motion Detected during bootup.
3155     * 
3156     * <ul>
3157     *   <li> <b>Default Value:</b> False
3158     * </ul>
3159     * 
3160     * Default Rates:
3161     * <ul>
3162     *   <li> <b>CAN:</b> 4.0 Hz
3163     * </ul>
3164     * <p>
3165     * This refreshes and returns a cached StatusSignal object.
3166     * 
3167     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3168     * @return StickyFault_BootIntoMotion Status Signal Object
3169     */
3170    public StatusSignal<Boolean> getStickyFault_BootIntoMotion(boolean refresh)
3171    {
3172        @SuppressWarnings("unchecked")
3173        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootIntoMotion.value, Boolean.class, val -> val != 0, "StickyFault_BootIntoMotion", true, refresh);
3174        return retval;
3175    }
3176        
3177    /**
3178     * Motion stack data acquisition was slower than expected
3179     * 
3180     * <ul>
3181     *   <li> <b>Default Value:</b> False
3182     * </ul>
3183     * 
3184     * Default Rates:
3185     * <ul>
3186     *   <li> <b>CAN:</b> 4.0 Hz
3187     * </ul>
3188     * <p>
3189     * This refreshes and returns a cached StatusSignal object.
3190     * 
3191     * @return Fault_DataAcquiredLate Status Signal Object
3192     */
3193    public StatusSignal<Boolean> getFault_DataAcquiredLate()
3194    {
3195        return getFault_DataAcquiredLate(true);
3196    }
3197    
3198    /**
3199     * Motion stack data acquisition was slower than expected
3200     * 
3201     * <ul>
3202     *   <li> <b>Default Value:</b> False
3203     * </ul>
3204     * 
3205     * Default Rates:
3206     * <ul>
3207     *   <li> <b>CAN:</b> 4.0 Hz
3208     * </ul>
3209     * <p>
3210     * This refreshes and returns a cached StatusSignal object.
3211     * 
3212     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3213     * @return Fault_DataAcquiredLate Status Signal Object
3214     */
3215    public StatusSignal<Boolean> getFault_DataAcquiredLate(boolean refresh)
3216    {
3217        @SuppressWarnings("unchecked")
3218        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_DataAcquiredLate.value, Boolean.class, val -> val != 0, "Fault_DataAcquiredLate", true, refresh);
3219        return retval;
3220    }
3221        
3222    /**
3223     * Motion stack data acquisition was slower than expected
3224     * 
3225     * <ul>
3226     *   <li> <b>Default Value:</b> False
3227     * </ul>
3228     * 
3229     * Default Rates:
3230     * <ul>
3231     *   <li> <b>CAN:</b> 4.0 Hz
3232     * </ul>
3233     * <p>
3234     * This refreshes and returns a cached StatusSignal object.
3235     * 
3236     * @return StickyFault_DataAcquiredLate Status Signal Object
3237     */
3238    public StatusSignal<Boolean> getStickyFault_DataAcquiredLate()
3239    {
3240        return getStickyFault_DataAcquiredLate(true);
3241    }
3242    
3243    /**
3244     * Motion stack data acquisition was slower than expected
3245     * 
3246     * <ul>
3247     *   <li> <b>Default Value:</b> False
3248     * </ul>
3249     * 
3250     * Default Rates:
3251     * <ul>
3252     *   <li> <b>CAN:</b> 4.0 Hz
3253     * </ul>
3254     * <p>
3255     * This refreshes and returns a cached StatusSignal object.
3256     * 
3257     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3258     * @return StickyFault_DataAcquiredLate Status Signal Object
3259     */
3260    public StatusSignal<Boolean> getStickyFault_DataAcquiredLate(boolean refresh)
3261    {
3262        @SuppressWarnings("unchecked")
3263        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_DataAcquiredLate.value, Boolean.class, val -> val != 0, "StickyFault_DataAcquiredLate", true, refresh);
3264        return retval;
3265    }
3266        
3267    /**
3268     * Motion stack loop time was slower than expected.
3269     * 
3270     * <ul>
3271     *   <li> <b>Default Value:</b> False
3272     * </ul>
3273     * 
3274     * Default Rates:
3275     * <ul>
3276     *   <li> <b>CAN:</b> 4.0 Hz
3277     * </ul>
3278     * <p>
3279     * This refreshes and returns a cached StatusSignal object.
3280     * 
3281     * @return Fault_LoopTimeSlow Status Signal Object
3282     */
3283    public StatusSignal<Boolean> getFault_LoopTimeSlow()
3284    {
3285        return getFault_LoopTimeSlow(true);
3286    }
3287    
3288    /**
3289     * Motion stack loop time was slower than expected.
3290     * 
3291     * <ul>
3292     *   <li> <b>Default Value:</b> False
3293     * </ul>
3294     * 
3295     * Default Rates:
3296     * <ul>
3297     *   <li> <b>CAN:</b> 4.0 Hz
3298     * </ul>
3299     * <p>
3300     * This refreshes and returns a cached StatusSignal object.
3301     * 
3302     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3303     * @return Fault_LoopTimeSlow Status Signal Object
3304     */
3305    public StatusSignal<Boolean> getFault_LoopTimeSlow(boolean refresh)
3306    {
3307        @SuppressWarnings("unchecked")
3308        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_LoopTimeSlow.value, Boolean.class, val -> val != 0, "Fault_LoopTimeSlow", true, refresh);
3309        return retval;
3310    }
3311        
3312    /**
3313     * Motion stack loop time was slower than expected.
3314     * 
3315     * <ul>
3316     *   <li> <b>Default Value:</b> False
3317     * </ul>
3318     * 
3319     * Default Rates:
3320     * <ul>
3321     *   <li> <b>CAN:</b> 4.0 Hz
3322     * </ul>
3323     * <p>
3324     * This refreshes and returns a cached StatusSignal object.
3325     * 
3326     * @return StickyFault_LoopTimeSlow Status Signal Object
3327     */
3328    public StatusSignal<Boolean> getStickyFault_LoopTimeSlow()
3329    {
3330        return getStickyFault_LoopTimeSlow(true);
3331    }
3332    
3333    /**
3334     * Motion stack loop time was slower than expected.
3335     * 
3336     * <ul>
3337     *   <li> <b>Default Value:</b> False
3338     * </ul>
3339     * 
3340     * Default Rates:
3341     * <ul>
3342     *   <li> <b>CAN:</b> 4.0 Hz
3343     * </ul>
3344     * <p>
3345     * This refreshes and returns a cached StatusSignal object.
3346     * 
3347     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3348     * @return StickyFault_LoopTimeSlow Status Signal Object
3349     */
3350    public StatusSignal<Boolean> getStickyFault_LoopTimeSlow(boolean refresh)
3351    {
3352        @SuppressWarnings("unchecked")
3353        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_LoopTimeSlow.value, Boolean.class, val -> val != 0, "StickyFault_LoopTimeSlow", true, refresh);
3354        return retval;
3355    }
3356        
3357    /**
3358     * Magnetometer values are saturated
3359     * 
3360     * <ul>
3361     *   <li> <b>Default Value:</b> False
3362     * </ul>
3363     * 
3364     * Default Rates:
3365     * <ul>
3366     *   <li> <b>CAN:</b> 4.0 Hz
3367     * </ul>
3368     * <p>
3369     * This refreshes and returns a cached StatusSignal object.
3370     * 
3371     * @return Fault_SaturatedMagnetometer Status Signal Object
3372     */
3373    public StatusSignal<Boolean> getFault_SaturatedMagnetometer()
3374    {
3375        return getFault_SaturatedMagnetometer(true);
3376    }
3377    
3378    /**
3379     * Magnetometer values are saturated
3380     * 
3381     * <ul>
3382     *   <li> <b>Default Value:</b> False
3383     * </ul>
3384     * 
3385     * Default Rates:
3386     * <ul>
3387     *   <li> <b>CAN:</b> 4.0 Hz
3388     * </ul>
3389     * <p>
3390     * This refreshes and returns a cached StatusSignal object.
3391     * 
3392     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3393     * @return Fault_SaturatedMagnetometer Status Signal Object
3394     */
3395    public StatusSignal<Boolean> getFault_SaturatedMagnetometer(boolean refresh)
3396    {
3397        @SuppressWarnings("unchecked")
3398        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_SaturatedMagne.value, Boolean.class, val -> val != 0, "Fault_SaturatedMagnetometer", true, refresh);
3399        return retval;
3400    }
3401        
3402    /**
3403     * Magnetometer values are saturated
3404     * 
3405     * <ul>
3406     *   <li> <b>Default Value:</b> False
3407     * </ul>
3408     * 
3409     * Default Rates:
3410     * <ul>
3411     *   <li> <b>CAN:</b> 4.0 Hz
3412     * </ul>
3413     * <p>
3414     * This refreshes and returns a cached StatusSignal object.
3415     * 
3416     * @return StickyFault_SaturatedMagnetometer Status Signal Object
3417     */
3418    public StatusSignal<Boolean> getStickyFault_SaturatedMagnetometer()
3419    {
3420        return getStickyFault_SaturatedMagnetometer(true);
3421    }
3422    
3423    /**
3424     * Magnetometer values are saturated
3425     * 
3426     * <ul>
3427     *   <li> <b>Default Value:</b> False
3428     * </ul>
3429     * 
3430     * Default Rates:
3431     * <ul>
3432     *   <li> <b>CAN:</b> 4.0 Hz
3433     * </ul>
3434     * <p>
3435     * This refreshes and returns a cached StatusSignal object.
3436     * 
3437     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3438     * @return StickyFault_SaturatedMagnetometer Status Signal Object
3439     */
3440    public StatusSignal<Boolean> getStickyFault_SaturatedMagnetometer(boolean refresh)
3441    {
3442        @SuppressWarnings("unchecked")
3443        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_SaturatedMagne.value, Boolean.class, val -> val != 0, "StickyFault_SaturatedMagnetometer", true, refresh);
3444        return retval;
3445    }
3446        
3447    /**
3448     * Accelerometer values are saturated
3449     * 
3450     * <ul>
3451     *   <li> <b>Default Value:</b> False
3452     * </ul>
3453     * 
3454     * Default Rates:
3455     * <ul>
3456     *   <li> <b>CAN:</b> 4.0 Hz
3457     * </ul>
3458     * <p>
3459     * This refreshes and returns a cached StatusSignal object.
3460     * 
3461     * @return Fault_SaturatedAccelerometer Status Signal Object
3462     */
3463    public StatusSignal<Boolean> getFault_SaturatedAccelerometer()
3464    {
3465        return getFault_SaturatedAccelerometer(true);
3466    }
3467    
3468    /**
3469     * Accelerometer values are saturated
3470     * 
3471     * <ul>
3472     *   <li> <b>Default Value:</b> False
3473     * </ul>
3474     * 
3475     * Default Rates:
3476     * <ul>
3477     *   <li> <b>CAN:</b> 4.0 Hz
3478     * </ul>
3479     * <p>
3480     * This refreshes and returns a cached StatusSignal object.
3481     * 
3482     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3483     * @return Fault_SaturatedAccelerometer Status Signal Object
3484     */
3485    public StatusSignal<Boolean> getFault_SaturatedAccelerometer(boolean refresh)
3486    {
3487        @SuppressWarnings("unchecked")
3488        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_SaturatedAccel.value, Boolean.class, val -> val != 0, "Fault_SaturatedAccelerometer", true, refresh);
3489        return retval;
3490    }
3491        
3492    /**
3493     * Accelerometer values are saturated
3494     * 
3495     * <ul>
3496     *   <li> <b>Default Value:</b> False
3497     * </ul>
3498     * 
3499     * Default Rates:
3500     * <ul>
3501     *   <li> <b>CAN:</b> 4.0 Hz
3502     * </ul>
3503     * <p>
3504     * This refreshes and returns a cached StatusSignal object.
3505     * 
3506     * @return StickyFault_SaturatedAccelerometer Status Signal Object
3507     */
3508    public StatusSignal<Boolean> getStickyFault_SaturatedAccelerometer()
3509    {
3510        return getStickyFault_SaturatedAccelerometer(true);
3511    }
3512    
3513    /**
3514     * Accelerometer values are saturated
3515     * 
3516     * <ul>
3517     *   <li> <b>Default Value:</b> False
3518     * </ul>
3519     * 
3520     * Default Rates:
3521     * <ul>
3522     *   <li> <b>CAN:</b> 4.0 Hz
3523     * </ul>
3524     * <p>
3525     * This refreshes and returns a cached StatusSignal object.
3526     * 
3527     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3528     * @return StickyFault_SaturatedAccelerometer Status Signal Object
3529     */
3530    public StatusSignal<Boolean> getStickyFault_SaturatedAccelerometer(boolean refresh)
3531    {
3532        @SuppressWarnings("unchecked")
3533        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_SaturatedAccel.value, Boolean.class, val -> val != 0, "StickyFault_SaturatedAccelerometer", true, refresh);
3534        return retval;
3535    }
3536        
3537    /**
3538     * Gyroscope values are saturated
3539     * 
3540     * <ul>
3541     *   <li> <b>Default Value:</b> False
3542     * </ul>
3543     * 
3544     * Default Rates:
3545     * <ul>
3546     *   <li> <b>CAN:</b> 4.0 Hz
3547     * </ul>
3548     * <p>
3549     * This refreshes and returns a cached StatusSignal object.
3550     * 
3551     * @return Fault_SaturatedGyroscope Status Signal Object
3552     */
3553    public StatusSignal<Boolean> getFault_SaturatedGyroscope()
3554    {
3555        return getFault_SaturatedGyroscope(true);
3556    }
3557    
3558    /**
3559     * Gyroscope values are saturated
3560     * 
3561     * <ul>
3562     *   <li> <b>Default Value:</b> False
3563     * </ul>
3564     * 
3565     * Default Rates:
3566     * <ul>
3567     *   <li> <b>CAN:</b> 4.0 Hz
3568     * </ul>
3569     * <p>
3570     * This refreshes and returns a cached StatusSignal object.
3571     * 
3572     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3573     * @return Fault_SaturatedGyroscope Status Signal Object
3574     */
3575    public StatusSignal<Boolean> getFault_SaturatedGyroscope(boolean refresh)
3576    {
3577        @SuppressWarnings("unchecked")
3578        var retval = super.lookupStatusSignal(SpnValue.Fault_PIGEON2_SaturatedGyros.value, Boolean.class, val -> val != 0, "Fault_SaturatedGyroscope", true, refresh);
3579        return retval;
3580    }
3581        
3582    /**
3583     * Gyroscope values are saturated
3584     * 
3585     * <ul>
3586     *   <li> <b>Default Value:</b> False
3587     * </ul>
3588     * 
3589     * Default Rates:
3590     * <ul>
3591     *   <li> <b>CAN:</b> 4.0 Hz
3592     * </ul>
3593     * <p>
3594     * This refreshes and returns a cached StatusSignal object.
3595     * 
3596     * @return StickyFault_SaturatedGyroscope Status Signal Object
3597     */
3598    public StatusSignal<Boolean> getStickyFault_SaturatedGyroscope()
3599    {
3600        return getStickyFault_SaturatedGyroscope(true);
3601    }
3602    
3603    /**
3604     * Gyroscope values are saturated
3605     * 
3606     * <ul>
3607     *   <li> <b>Default Value:</b> False
3608     * </ul>
3609     * 
3610     * Default Rates:
3611     * <ul>
3612     *   <li> <b>CAN:</b> 4.0 Hz
3613     * </ul>
3614     * <p>
3615     * This refreshes and returns a cached StatusSignal object.
3616     * 
3617     * @param refresh Whether to refresh the StatusSignal before returning it; defaults to true
3618     * @return StickyFault_SaturatedGyroscope Status Signal Object
3619     */
3620    public StatusSignal<Boolean> getStickyFault_SaturatedGyroscope(boolean refresh)
3621    {
3622        @SuppressWarnings("unchecked")
3623        var retval = super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_SaturatedGyros.value, Boolean.class, val -> val != 0, "StickyFault_SaturatedGyroscope", true, refresh);
3624        return retval;
3625    }
3626
3627    
3628
3629    /**
3630     * Control device with generic control request object.
3631     * <p>
3632     * User must make sure the specified object is castable to a valid control request,
3633     * otherwise this function will fail at run-time and return the NotSupported StatusCode
3634     *
3635     * @param request Control object to request of the device
3636     * @return Status Code of the request, 0 is OK
3637     */
3638    public StatusCode setControl(ControlRequest request)
3639    {
3640        
3641        return StatusCode.NotSupported;
3642    }
3643
3644    
3645    /**
3646     * The yaw to set the Pigeon2 to right now.
3647     * <p>
3648     * This will wait up to 0.100 seconds (100ms) by default.
3649     * 
3650     * @param newValue Value to set to. Units are in deg.
3651     * @return StatusCode of the set command
3652     */
3653    public StatusCode setYaw(double newValue) {
3654        return setYaw(newValue, 0.100);
3655    }
3656    /**
3657     * The yaw to set the Pigeon2 to right now.
3658     * 
3659     * @param newValue Value to set to. Units are in deg.
3660     * @param timeoutSeconds Maximum time to wait up to in seconds.
3661     * @return StatusCode of the set command
3662     */
3663    public StatusCode setYaw(double newValue, double timeoutSeconds) {
3664        return getConfigurator().setYaw(newValue, timeoutSeconds);
3665    }
3666    
3667    /**
3668     * The yaw to set the Pigeon2 to right now.
3669     * <p>
3670     * This will wait up to 0.100 seconds (100ms) by default.
3671     * 
3672     * @param newValue Value to set to. Units are in deg.
3673     * @return StatusCode of the set command
3674     */
3675    public StatusCode setYaw(Angle newValue) {
3676        return setYaw(newValue.in(Degrees));
3677    }
3678    /**
3679     * The yaw to set the Pigeon2 to right now.
3680     * 
3681     * @param newValue Value to set to. Units are in deg.
3682     * @param timeoutSeconds Maximum time to wait up to in seconds.
3683     * @return StatusCode of the set command
3684     */
3685    public StatusCode setYaw(Angle newValue, double timeoutSeconds) {
3686        return setYaw(newValue.in(Degrees), timeoutSeconds);
3687    }
3688    
3689    /**
3690     * Clear the sticky faults in the device.
3691     * <p>
3692     * This typically has no impact on the device functionality.  Instead,
3693     * it just clears telemetry faults that are accessible via API and
3694     * Tuner Self-Test.
3695     * <p>
3696     * This will wait up to 0.100 seconds (100ms) by default.
3697     * 
3698     * @return StatusCode of the set command
3699     */
3700    public StatusCode clearStickyFaults() {
3701        return clearStickyFaults(0.100);
3702    }
3703    /**
3704     * Clear the sticky faults in the device.
3705     * <p>
3706     * This typically has no impact on the device functionality.  Instead,
3707     * it just clears telemetry faults that are accessible via API and
3708     * Tuner Self-Test.
3709     * 
3710     * @param timeoutSeconds Maximum time to wait up to in seconds.
3711     * @return StatusCode of the set command
3712     */
3713    public StatusCode clearStickyFaults(double timeoutSeconds) {
3714        return getConfigurator().clearStickyFaults(timeoutSeconds);
3715    }
3716    
3717    /**
3718     * Clear sticky fault: Hardware fault occurred
3719     * <p>
3720     * This will wait up to 0.100 seconds (100ms) by default.
3721     * 
3722     * @return StatusCode of the set command
3723     */
3724    public StatusCode clearStickyFault_Hardware() {
3725        return clearStickyFault_Hardware(0.100);
3726    }
3727    /**
3728     * Clear sticky fault: Hardware fault occurred
3729     * 
3730     * @param timeoutSeconds Maximum time to wait up to in seconds.
3731     * @return StatusCode of the set command
3732     */
3733    public StatusCode clearStickyFault_Hardware(double timeoutSeconds) {
3734        return getConfigurator().clearStickyFault_Hardware(timeoutSeconds);
3735    }
3736    
3737    /**
3738     * Clear sticky fault: Device supply voltage dropped to near brownout
3739     * levels
3740     * <p>
3741     * This will wait up to 0.100 seconds (100ms) by default.
3742     * 
3743     * @return StatusCode of the set command
3744     */
3745    public StatusCode clearStickyFault_Undervoltage() {
3746        return clearStickyFault_Undervoltage(0.100);
3747    }
3748    /**
3749     * Clear sticky fault: Device supply voltage dropped to near brownout
3750     * levels
3751     * 
3752     * @param timeoutSeconds Maximum time to wait up to in seconds.
3753     * @return StatusCode of the set command
3754     */
3755    public StatusCode clearStickyFault_Undervoltage(double timeoutSeconds) {
3756        return getConfigurator().clearStickyFault_Undervoltage(timeoutSeconds);
3757    }
3758    
3759    /**
3760     * Clear sticky fault: Device boot while detecting the enable signal
3761     * <p>
3762     * This will wait up to 0.100 seconds (100ms) by default.
3763     * 
3764     * @return StatusCode of the set command
3765     */
3766    public StatusCode clearStickyFault_BootDuringEnable() {
3767        return clearStickyFault_BootDuringEnable(0.100);
3768    }
3769    /**
3770     * Clear sticky fault: Device boot while detecting the enable signal
3771     * 
3772     * @param timeoutSeconds Maximum time to wait up to in seconds.
3773     * @return StatusCode of the set command
3774     */
3775    public StatusCode clearStickyFault_BootDuringEnable(double timeoutSeconds) {
3776        return getConfigurator().clearStickyFault_BootDuringEnable(timeoutSeconds);
3777    }
3778    
3779    /**
3780     * Clear sticky fault: An unlicensed feature is in use, device may not
3781     * behave as expected.
3782     * <p>
3783     * This will wait up to 0.100 seconds (100ms) by default.
3784     * 
3785     * @return StatusCode of the set command
3786     */
3787    public StatusCode clearStickyFault_UnlicensedFeatureInUse() {
3788        return clearStickyFault_UnlicensedFeatureInUse(0.100);
3789    }
3790    /**
3791     * Clear sticky fault: An unlicensed feature is in use, device may not
3792     * behave as expected.
3793     * 
3794     * @param timeoutSeconds Maximum time to wait up to in seconds.
3795     * @return StatusCode of the set command
3796     */
3797    public StatusCode clearStickyFault_UnlicensedFeatureInUse(double timeoutSeconds) {
3798        return getConfigurator().clearStickyFault_UnlicensedFeatureInUse(timeoutSeconds);
3799    }
3800    
3801    /**
3802     * Clear sticky fault: Bootup checks failed: Accelerometer
3803     * <p>
3804     * This will wait up to 0.100 seconds (100ms) by default.
3805     * 
3806     * @return StatusCode of the set command
3807     */
3808    public StatusCode clearStickyFault_BootupAccelerometer() {
3809        return clearStickyFault_BootupAccelerometer(0.100);
3810    }
3811    /**
3812     * Clear sticky fault: Bootup checks failed: Accelerometer
3813     * 
3814     * @param timeoutSeconds Maximum time to wait up to in seconds.
3815     * @return StatusCode of the set command
3816     */
3817    public StatusCode clearStickyFault_BootupAccelerometer(double timeoutSeconds) {
3818        return getConfigurator().clearStickyFault_BootupAccelerometer(timeoutSeconds);
3819    }
3820    
3821    /**
3822     * Clear sticky fault: Bootup checks failed: Gyroscope
3823     * <p>
3824     * This will wait up to 0.100 seconds (100ms) by default.
3825     * 
3826     * @return StatusCode of the set command
3827     */
3828    public StatusCode clearStickyFault_BootupGyroscope() {
3829        return clearStickyFault_BootupGyroscope(0.100);
3830    }
3831    /**
3832     * Clear sticky fault: Bootup checks failed: Gyroscope
3833     * 
3834     * @param timeoutSeconds Maximum time to wait up to in seconds.
3835     * @return StatusCode of the set command
3836     */
3837    public StatusCode clearStickyFault_BootupGyroscope(double timeoutSeconds) {
3838        return getConfigurator().clearStickyFault_BootupGyroscope(timeoutSeconds);
3839    }
3840    
3841    /**
3842     * Clear sticky fault: Bootup checks failed: Magnetometer
3843     * <p>
3844     * This will wait up to 0.100 seconds (100ms) by default.
3845     * 
3846     * @return StatusCode of the set command
3847     */
3848    public StatusCode clearStickyFault_BootupMagnetometer() {
3849        return clearStickyFault_BootupMagnetometer(0.100);
3850    }
3851    /**
3852     * Clear sticky fault: Bootup checks failed: Magnetometer
3853     * 
3854     * @param timeoutSeconds Maximum time to wait up to in seconds.
3855     * @return StatusCode of the set command
3856     */
3857    public StatusCode clearStickyFault_BootupMagnetometer(double timeoutSeconds) {
3858        return getConfigurator().clearStickyFault_BootupMagnetometer(timeoutSeconds);
3859    }
3860    
3861    /**
3862     * Clear sticky fault: Motion Detected during bootup.
3863     * <p>
3864     * This will wait up to 0.100 seconds (100ms) by default.
3865     * 
3866     * @return StatusCode of the set command
3867     */
3868    public StatusCode clearStickyFault_BootIntoMotion() {
3869        return clearStickyFault_BootIntoMotion(0.100);
3870    }
3871    /**
3872     * Clear sticky fault: Motion Detected during bootup.
3873     * 
3874     * @param timeoutSeconds Maximum time to wait up to in seconds.
3875     * @return StatusCode of the set command
3876     */
3877    public StatusCode clearStickyFault_BootIntoMotion(double timeoutSeconds) {
3878        return getConfigurator().clearStickyFault_BootIntoMotion(timeoutSeconds);
3879    }
3880    
3881    /**
3882     * Clear sticky fault: Motion stack data acquisition was slower than
3883     * expected
3884     * <p>
3885     * This will wait up to 0.100 seconds (100ms) by default.
3886     * 
3887     * @return StatusCode of the set command
3888     */
3889    public StatusCode clearStickyFault_DataAcquiredLate() {
3890        return clearStickyFault_DataAcquiredLate(0.100);
3891    }
3892    /**
3893     * Clear sticky fault: Motion stack data acquisition was slower than
3894     * expected
3895     * 
3896     * @param timeoutSeconds Maximum time to wait up to in seconds.
3897     * @return StatusCode of the set command
3898     */
3899    public StatusCode clearStickyFault_DataAcquiredLate(double timeoutSeconds) {
3900        return getConfigurator().clearStickyFault_DataAcquiredLate(timeoutSeconds);
3901    }
3902    
3903    /**
3904     * Clear sticky fault: Motion stack loop time was slower than
3905     * expected.
3906     * <p>
3907     * This will wait up to 0.100 seconds (100ms) by default.
3908     * 
3909     * @return StatusCode of the set command
3910     */
3911    public StatusCode clearStickyFault_LoopTimeSlow() {
3912        return clearStickyFault_LoopTimeSlow(0.100);
3913    }
3914    /**
3915     * Clear sticky fault: Motion stack loop time was slower than
3916     * expected.
3917     * 
3918     * @param timeoutSeconds Maximum time to wait up to in seconds.
3919     * @return StatusCode of the set command
3920     */
3921    public StatusCode clearStickyFault_LoopTimeSlow(double timeoutSeconds) {
3922        return getConfigurator().clearStickyFault_LoopTimeSlow(timeoutSeconds);
3923    }
3924    
3925    /**
3926     * Clear sticky fault: Magnetometer values are saturated
3927     * <p>
3928     * This will wait up to 0.100 seconds (100ms) by default.
3929     * 
3930     * @return StatusCode of the set command
3931     */
3932    public StatusCode clearStickyFault_SaturatedMagnetometer() {
3933        return clearStickyFault_SaturatedMagnetometer(0.100);
3934    }
3935    /**
3936     * Clear sticky fault: Magnetometer values are saturated
3937     * 
3938     * @param timeoutSeconds Maximum time to wait up to in seconds.
3939     * @return StatusCode of the set command
3940     */
3941    public StatusCode clearStickyFault_SaturatedMagnetometer(double timeoutSeconds) {
3942        return getConfigurator().clearStickyFault_SaturatedMagnetometer(timeoutSeconds);
3943    }
3944    
3945    /**
3946     * Clear sticky fault: Accelerometer values are saturated
3947     * <p>
3948     * This will wait up to 0.100 seconds (100ms) by default.
3949     * 
3950     * @return StatusCode of the set command
3951     */
3952    public StatusCode clearStickyFault_SaturatedAccelerometer() {
3953        return clearStickyFault_SaturatedAccelerometer(0.100);
3954    }
3955    /**
3956     * Clear sticky fault: Accelerometer values are saturated
3957     * 
3958     * @param timeoutSeconds Maximum time to wait up to in seconds.
3959     * @return StatusCode of the set command
3960     */
3961    public StatusCode clearStickyFault_SaturatedAccelerometer(double timeoutSeconds) {
3962        return getConfigurator().clearStickyFault_SaturatedAccelerometer(timeoutSeconds);
3963    }
3964    
3965    /**
3966     * Clear sticky fault: Gyroscope values are saturated
3967     * <p>
3968     * This will wait up to 0.100 seconds (100ms) by default.
3969     * 
3970     * @return StatusCode of the set command
3971     */
3972    public StatusCode clearStickyFault_SaturatedGyroscope() {
3973        return clearStickyFault_SaturatedGyroscope(0.100);
3974    }
3975    /**
3976     * Clear sticky fault: Gyroscope values are saturated
3977     * 
3978     * @param timeoutSeconds Maximum time to wait up to in seconds.
3979     * @return StatusCode of the set command
3980     */
3981    public StatusCode clearStickyFault_SaturatedGyroscope(double timeoutSeconds) {
3982        return getConfigurator().clearStickyFault_SaturatedGyroscope(timeoutSeconds);
3983    }
3984}
3985