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.*;
018
019/**
020 * Class description for the Pigeon 2 IMU sensor that measures orientation.
021 * 
022 * <pre>
023 * // Constants used in Pigeon2 construction
024 * final int kPigeon2Id = 0;
025 * final String kPigeon2CANbus = "canivore";
026 * 
027 * // Construct the Pigeon 2
028 * Pigeon2 pigeon = new Pigeon2(kPigeon2Id, kPigeon2CANbus);
029 * 
030 * // Configure the Pigeon2 for basic use
031 * Pigeon2Configuration configs = new Pigeon2Configuration();
032 * // This Pigeon is mounted X-up, so we should mount-pose with Pitch at 90 degrees
033 * configs.MountPose.MountPoseYaw = 0;
034 * configs.MountPose.MountPosePitch = 90;
035 * configs.MountPose.MountPoseRoll = 0;
036 * // This Pigeon has no need to trim the gyro
037 * configs.GyroTrim.GyroScalarX = 0;
038 * configs.GyroTrim.GyroScalarY = 0;
039 * configs.GyroTrim.GyroScalarZ = 0;
040 * // We want the thermal comp and no-motion cal enabled, with the compass disabled for best behavior
041 * configs.Pigeon2Features.DisableNoMotionCalibration = false;
042 * configs.Pigeon2Features.DisableTemperatureCompensation = false;
043 * configs.Pigeon2Features.EnableCompass = false;
044 * 
045 * // Write these configs to the Pigeon2
046 * pigeon.getConfigurator().apply(configs);
047 * 
048 * // Set the yaw to 0 degrees for initial use
049 * pigeon.setYaw(0);
050 * 
051 * // Get Yaw Pitch Roll StatusSignals
052 * var yaw = pigeon.getYaw();
053 * var pitch = pigeon.getPitch();
054 * var roll = pigeon.getRoll();
055 * 
056 * // Refresh and print these values
057 * System.out.println("Yaw is " + yaw.refresh().toString());
058 * System.out.println("Pitch is " + pitch.refresh().toString());
059 * System.out.println("Roll is " + roll.refresh().toString());
060 * </pre>
061 */
062public class CorePigeon2 extends ParentDevice
063{
064    private Pigeon2Configurator _configurator;
065
066    
067
068    /**
069     * Constructs a new Pigeon 2 sensor object.
070     * <p>
071     * Constructs the device using the default CAN bus for the system:
072     * <ul>
073     *   <li>"rio" on roboRIO
074     *   <li>"can0" on Linux
075     *   <li>"*" on Windows
076     * </ul>
077     *
078     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
079     */
080    public CorePigeon2(int deviceId)
081    {
082        this(deviceId, "");
083    }
084    /**
085     * Constructs a new Pigeon 2 sensor object.
086     *
087     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
088     * @param canbus      Name of the CAN bus this device is on. Possible CAN bus strings are:
089     *                    <ul>
090     *                      <li>"rio" for the native roboRIO CAN bus
091     *                      <li>CANivore name or serial number
092     *                      <li>SocketCAN interface (non-FRC Linux only)
093     *                      <li>"*" for any CANivore seen by the program
094     *                      <li>empty string (default) to select the default for the system:
095     *                      <ul>
096     *                        <li>"rio" on roboRIO
097     *                        <li>"can0" on Linux
098     *                        <li>"*" on Windows
099     *                      </ul>
100     *                    </ul>
101     */
102    public CorePigeon2(int deviceId, String canbus)
103    {
104        super(deviceId, "pigeon 2", canbus);
105        _configurator = new Pigeon2Configurator(this.deviceIdentifier);
106        PlatformJNI.JNI_SimCreate(DeviceType.PRO_Pigeon2Type.value, deviceId);
107    }
108
109    /**
110     * Gets the configurator to use with this device's configs
111     *
112     * @return Configurator for this object
113     */
114    public Pigeon2Configurator getConfigurator()
115    {
116        return this._configurator;
117    }
118
119
120    private Pigeon2SimState _simState = null;
121    /**
122     * Get the simulation state for this device.
123     * <p>
124     * This function reuses an allocated simulation state
125     * object, so it is safe to call this function multiple
126     * times in a robot loop.
127     *
128     * @return Simulation state
129     */
130    public Pigeon2SimState getSimState() {
131        if (_simState == null)
132            _simState = new Pigeon2SimState(this);
133        return _simState;
134    }
135
136
137        
138    /**
139     * App Major Version number.
140     * 
141     * <ul>
142     *   <li> <b>Minimum Value:</b> 0
143     *   <li> <b>Maximum Value:</b> 255
144     *   <li> <b>Default Value:</b> 0
145     *   <li> <b>Units:</b> 
146     * </ul>
147     * 
148     * Default Rates:
149     * <ul>
150     *   <li> <b>CAN:</b> 4.0 Hz
151     * </ul>
152     * 
153     * This refreshes and returns a cached StatusSignal object.
154     * 
155     * @return VersionMajor Status Signal Object
156     */
157    public StatusSignal<Integer> getVersionMajor()
158    {
159        return super.lookupStatusSignal(SpnValue.Version_Major.value, Integer.class, "VersionMajor", false);
160    }
161        
162    /**
163     * App Minor Version number.
164     * 
165     * <ul>
166     *   <li> <b>Minimum Value:</b> 0
167     *   <li> <b>Maximum Value:</b> 255
168     *   <li> <b>Default Value:</b> 0
169     *   <li> <b>Units:</b> 
170     * </ul>
171     * 
172     * Default Rates:
173     * <ul>
174     *   <li> <b>CAN:</b> 4.0 Hz
175     * </ul>
176     * 
177     * This refreshes and returns a cached StatusSignal object.
178     * 
179     * @return VersionMinor Status Signal Object
180     */
181    public StatusSignal<Integer> getVersionMinor()
182    {
183        return super.lookupStatusSignal(SpnValue.Version_Minor.value, Integer.class, "VersionMinor", false);
184    }
185        
186    /**
187     * App Bugfix Version number.
188     * 
189     * <ul>
190     *   <li> <b>Minimum Value:</b> 0
191     *   <li> <b>Maximum Value:</b> 255
192     *   <li> <b>Default Value:</b> 0
193     *   <li> <b>Units:</b> 
194     * </ul>
195     * 
196     * Default Rates:
197     * <ul>
198     *   <li> <b>CAN:</b> 4.0 Hz
199     * </ul>
200     * 
201     * This refreshes and returns a cached StatusSignal object.
202     * 
203     * @return VersionBugfix Status Signal Object
204     */
205    public StatusSignal<Integer> getVersionBugfix()
206    {
207        return super.lookupStatusSignal(SpnValue.Version_Bugfix.value, Integer.class, "VersionBugfix", false);
208    }
209        
210    /**
211     * App Build Version number.
212     * 
213     * <ul>
214     *   <li> <b>Minimum Value:</b> 0
215     *   <li> <b>Maximum Value:</b> 255
216     *   <li> <b>Default Value:</b> 0
217     *   <li> <b>Units:</b> 
218     * </ul>
219     * 
220     * Default Rates:
221     * <ul>
222     *   <li> <b>CAN:</b> 4.0 Hz
223     * </ul>
224     * 
225     * This refreshes and returns a cached StatusSignal object.
226     * 
227     * @return VersionBuild Status Signal Object
228     */
229    public StatusSignal<Integer> getVersionBuild()
230    {
231        return super.lookupStatusSignal(SpnValue.Version_Build.value, Integer.class, "VersionBuild", false);
232    }
233        
234    /**
235     * Full Version.  The format is a four byte value.
236     * <p>
237     * Full Version of firmware in device. The format is a four byte
238     * value.
239     * 
240     * <ul>
241     *   <li> <b>Minimum Value:</b> 0
242     *   <li> <b>Maximum Value:</b> 4294967295
243     *   <li> <b>Default Value:</b> 0
244     *   <li> <b>Units:</b> 
245     * </ul>
246     * 
247     * Default Rates:
248     * <ul>
249     *   <li> <b>CAN:</b> 4.0 Hz
250     * </ul>
251     * 
252     * This refreshes and returns a cached StatusSignal object.
253     * 
254     * @return Version Status Signal Object
255     */
256    public StatusSignal<Integer> getVersion()
257    {
258        return super.lookupStatusSignal(SpnValue.Version_Full.value, Integer.class, "Version", false);
259    }
260        
261    /**
262     * Integer representing all faults
263     * <p>
264     * This returns the fault flags reported by the device. These are
265     * device specific and are not used directly in typical applications.
266     * Use the signal specific GetFault_*() methods instead.  
267     * 
268     * <ul>
269     *   <li> <b>Minimum Value:</b> 0
270     *   <li> <b>Maximum Value:</b> 16777215
271     *   <li> <b>Default Value:</b> 0
272     *   <li> <b>Units:</b> 
273     * </ul>
274     * 
275     * Default Rates:
276     * <ul>
277     *   <li> <b>CAN:</b> 4.0 Hz
278     * </ul>
279     * 
280     * This refreshes and returns a cached StatusSignal object.
281     * 
282     * @return FaultField Status Signal Object
283     */
284    public StatusSignal<Integer> getFaultField()
285    {
286        return super.lookupStatusSignal(SpnValue.AllFaults.value, Integer.class, "FaultField", true);
287    }
288        
289    /**
290     * Integer representing all sticky faults
291     * <p>
292     * This returns the persistent "sticky" fault flags reported by the
293     * device. These are device specific and are not used directly in
294     * typical applications. Use the signal specific GetStickyFault_*()
295     * methods instead.  
296     * 
297     * <ul>
298     *   <li> <b>Minimum Value:</b> 0
299     *   <li> <b>Maximum Value:</b> 16777215
300     *   <li> <b>Default Value:</b> 0
301     *   <li> <b>Units:</b> 
302     * </ul>
303     * 
304     * Default Rates:
305     * <ul>
306     *   <li> <b>CAN:</b> 4.0 Hz
307     * </ul>
308     * 
309     * This refreshes and returns a cached StatusSignal object.
310     * 
311     * @return StickyFaultField Status Signal Object
312     */
313    public StatusSignal<Integer> getStickyFaultField()
314    {
315        return super.lookupStatusSignal(SpnValue.AllStickyFaults.value, Integer.class, "StickyFaultField", true);
316    }
317        
318    /**
319     * Current reported yaw of the Pigeon2.
320     * 
321     * <ul>
322     *   <li> <b>Minimum Value:</b> -368640.0
323     *   <li> <b>Maximum Value:</b> 368639.99725341797
324     *   <li> <b>Default Value:</b> 0
325     *   <li> <b>Units:</b> deg
326     * </ul>
327     * 
328     * Default Rates:
329     * <ul>
330     *   <li> <b>CAN 2.0:</b> 100.0 Hz
331     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
332     * </ul>
333     * 
334     * This refreshes and returns a cached StatusSignal object.
335     * 
336     * @return Yaw Status Signal Object
337     */
338    public StatusSignal<Double> getYaw()
339    {
340        return super.lookupStatusSignal(SpnValue.Pigeon2Yaw.value, Double.class, "Yaw", true);
341    }
342        
343    /**
344     * Current reported pitch of the Pigeon2.
345     * 
346     * <ul>
347     *   <li> <b>Minimum Value:</b> -90.0
348     *   <li> <b>Maximum Value:</b> 89.9560546875
349     *   <li> <b>Default Value:</b> 0
350     *   <li> <b>Units:</b> deg
351     * </ul>
352     * 
353     * Default Rates:
354     * <ul>
355     *   <li> <b>CAN 2.0:</b> 100.0 Hz
356     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
357     * </ul>
358     * 
359     * This refreshes and returns a cached StatusSignal object.
360     * 
361     * @return Pitch Status Signal Object
362     */
363    public StatusSignal<Double> getPitch()
364    {
365        return super.lookupStatusSignal(SpnValue.Pigeon2Pitch.value, Double.class, "Pitch", true);
366    }
367        
368    /**
369     * Current reported roll of the Pigeon2.
370     * 
371     * <ul>
372     *   <li> <b>Minimum Value:</b> -180.0
373     *   <li> <b>Maximum Value:</b> 179.9560546875
374     *   <li> <b>Default Value:</b> 0
375     *   <li> <b>Units:</b> deg
376     * </ul>
377     * 
378     * Default Rates:
379     * <ul>
380     *   <li> <b>CAN 2.0:</b> 100.0 Hz
381     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
382     * </ul>
383     * 
384     * This refreshes and returns a cached StatusSignal object.
385     * 
386     * @return Roll Status Signal Object
387     */
388    public StatusSignal<Double> getRoll()
389    {
390        return super.lookupStatusSignal(SpnValue.Pigeon2Roll.value, Double.class, "Roll", true);
391    }
392        
393    /**
394     * The W component of the reported Quaternion.
395     * 
396     * <ul>
397     *   <li> <b>Minimum Value:</b> -1.0001220852154804
398     *   <li> <b>Maximum Value:</b> 1.0
399     *   <li> <b>Default Value:</b> 0
400     *   <li> <b>Units:</b> 
401     * </ul>
402     * 
403     * Default Rates:
404     * <ul>
405     *   <li> <b>CAN 2.0:</b> 50.0 Hz
406     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
407     * </ul>
408     * 
409     * This refreshes and returns a cached StatusSignal object.
410     * 
411     * @return QuatW Status Signal Object
412     */
413    public StatusSignal<Double> getQuatW()
414    {
415        return super.lookupStatusSignal(SpnValue.Pigeon2QuatW.value, Double.class, "QuatW", true);
416    }
417        
418    /**
419     * The X component of the reported Quaternion.
420     * 
421     * <ul>
422     *   <li> <b>Minimum Value:</b> -1.0001220852154804
423     *   <li> <b>Maximum Value:</b> 1.0
424     *   <li> <b>Default Value:</b> 0
425     *   <li> <b>Units:</b> 
426     * </ul>
427     * 
428     * Default Rates:
429     * <ul>
430     *   <li> <b>CAN 2.0:</b> 50.0 Hz
431     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
432     * </ul>
433     * 
434     * This refreshes and returns a cached StatusSignal object.
435     * 
436     * @return QuatX Status Signal Object
437     */
438    public StatusSignal<Double> getQuatX()
439    {
440        return super.lookupStatusSignal(SpnValue.Pigeon2QuatX.value, Double.class, "QuatX", true);
441    }
442        
443    /**
444     * The Y component of the reported Quaternion.
445     * 
446     * <ul>
447     *   <li> <b>Minimum Value:</b> -1.0001220852154804
448     *   <li> <b>Maximum Value:</b> 1.0
449     *   <li> <b>Default Value:</b> 0
450     *   <li> <b>Units:</b> 
451     * </ul>
452     * 
453     * Default Rates:
454     * <ul>
455     *   <li> <b>CAN 2.0:</b> 50.0 Hz
456     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
457     * </ul>
458     * 
459     * This refreshes and returns a cached StatusSignal object.
460     * 
461     * @return QuatY Status Signal Object
462     */
463    public StatusSignal<Double> getQuatY()
464    {
465        return super.lookupStatusSignal(SpnValue.Pigeon2QuatY.value, Double.class, "QuatY", true);
466    }
467        
468    /**
469     * The Z component of the reported Quaternion.
470     * 
471     * <ul>
472     *   <li> <b>Minimum Value:</b> -1.0001220852154804
473     *   <li> <b>Maximum Value:</b> 1.0
474     *   <li> <b>Default Value:</b> 0
475     *   <li> <b>Units:</b> 
476     * </ul>
477     * 
478     * Default Rates:
479     * <ul>
480     *   <li> <b>CAN 2.0:</b> 50.0 Hz
481     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
482     * </ul>
483     * 
484     * This refreshes and returns a cached StatusSignal object.
485     * 
486     * @return QuatZ Status Signal Object
487     */
488    public StatusSignal<Double> getQuatZ()
489    {
490        return super.lookupStatusSignal(SpnValue.Pigeon2QuatZ.value, Double.class, "QuatZ", true);
491    }
492        
493    /**
494     * The X component of the gravity vector.
495     * <p>
496     * This is the X component of the reported gravity-vector. The gravity
497     * vector is not the acceleration experienced by the Pigeon2, rather
498     * it is where the Pigeon2 believes "Down" is. This can be used for
499     * mechanisms that are linearly related to gravity, such as an arm
500     * pivoting about a point, as the contribution of gravity to the arm
501     * is directly proportional to the contribution of gravity about one
502     * of these primary axis.
503     * 
504     * <ul>
505     *   <li> <b>Minimum Value:</b> -1.000030518509476
506     *   <li> <b>Maximum Value:</b> 1.0
507     *   <li> <b>Default Value:</b> 0
508     *   <li> <b>Units:</b> 
509     * </ul>
510     * 
511     * Default Rates:
512     * <ul>
513     *   <li> <b>CAN 2.0:</b> 10.0 Hz
514     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
515     * </ul>
516     * 
517     * This refreshes and returns a cached StatusSignal object.
518     * 
519     * @return GravityVectorX Status Signal Object
520     */
521    public StatusSignal<Double> getGravityVectorX()
522    {
523        return super.lookupStatusSignal(SpnValue.Pigeon2GravityVectorX.value, Double.class, "GravityVectorX", true);
524    }
525        
526    /**
527     * The Y component of the gravity vector.
528     * <p>
529     * This is the X component of the reported gravity-vector. The gravity
530     * vector is not the acceleration experienced by the Pigeon2, rather
531     * it is where the Pigeon2 believes "Down" is. This can be used for
532     * mechanisms that are linearly related to gravity, such as an arm
533     * pivoting about a point, as the contribution of gravity to the arm
534     * is directly proportional to the contribution of gravity about one
535     * of these primary axis.
536     * 
537     * <ul>
538     *   <li> <b>Minimum Value:</b> -1.000030518509476
539     *   <li> <b>Maximum Value:</b> 1.0
540     *   <li> <b>Default Value:</b> 0
541     *   <li> <b>Units:</b> 
542     * </ul>
543     * 
544     * Default Rates:
545     * <ul>
546     *   <li> <b>CAN 2.0:</b> 10.0 Hz
547     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
548     * </ul>
549     * 
550     * This refreshes and returns a cached StatusSignal object.
551     * 
552     * @return GravityVectorY Status Signal Object
553     */
554    public StatusSignal<Double> getGravityVectorY()
555    {
556        return super.lookupStatusSignal(SpnValue.Pigeon2GravityVectorY.value, Double.class, "GravityVectorY", true);
557    }
558        
559    /**
560     * The Z component of the gravity vector.
561     * <p>
562     * This is the Z component of the reported gravity-vector. The gravity
563     * vector is not the acceleration experienced by the Pigeon2, rather
564     * it is where the Pigeon2 believes "Down" is. This can be used for
565     * mechanisms that are linearly related to gravity, such as an arm
566     * pivoting about a point, as the contribution of gravity to the arm
567     * is directly proportional to the contribution of gravity about one
568     * of these primary axis.
569     * 
570     * <ul>
571     *   <li> <b>Minimum Value:</b> -1.000030518509476
572     *   <li> <b>Maximum Value:</b> 1.0
573     *   <li> <b>Default Value:</b> 0
574     *   <li> <b>Units:</b> 
575     * </ul>
576     * 
577     * Default Rates:
578     * <ul>
579     *   <li> <b>CAN 2.0:</b> 10.0 Hz
580     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
581     * </ul>
582     * 
583     * This refreshes and returns a cached StatusSignal object.
584     * 
585     * @return GravityVectorZ Status Signal Object
586     */
587    public StatusSignal<Double> getGravityVectorZ()
588    {
589        return super.lookupStatusSignal(SpnValue.Pigeon2GravityVectorZ.value, Double.class, "GravityVectorZ", true);
590    }
591        
592    /**
593     * Temperature of the Pigeon 2.
594     * 
595     * <ul>
596     *   <li> <b>Minimum Value:</b> -128.0
597     *   <li> <b>Maximum Value:</b> 127.99609375
598     *   <li> <b>Default Value:</b> 0
599     *   <li> <b>Units:</b> ℃
600     * </ul>
601     * 
602     * Default Rates:
603     * <ul>
604     *   <li> <b>CAN 2.0:</b> 4.0 Hz
605     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
606     * </ul>
607     * 
608     * This refreshes and returns a cached StatusSignal object.
609     * 
610     * @return Temperature Status Signal Object
611     */
612    public StatusSignal<Double> getTemperature()
613    {
614        return super.lookupStatusSignal(SpnValue.Pigeon2Temperature.value, Double.class, "Temperature", true);
615    }
616        
617    /**
618     * Whether the no-motion calibration feature is enabled.
619     * 
620     * <ul>
621     *   <li> <b>Default Value:</b> 0
622     * </ul>
623     * 
624     * Default Rates:
625     * <ul>
626     *   <li> <b>CAN 2.0:</b> 4.0 Hz
627     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
628     * </ul>
629     * 
630     * This refreshes and returns a cached StatusSignal object.
631     * 
632     * @return NoMotionEnabled Status Signal Object
633     */
634    public StatusSignal<Boolean> getNoMotionEnabled()
635    {
636        return super.lookupStatusSignal(SpnValue.Pigeon2NoMotionCalEnabled.value, Boolean.class, "NoMotionEnabled", true);
637    }
638        
639    /**
640     * The number of times a no-motion event occurred, wraps at 15.
641     * 
642     * <ul>
643     *   <li> <b>Minimum Value:</b> 0
644     *   <li> <b>Maximum Value:</b> 15
645     *   <li> <b>Default Value:</b> 0
646     *   <li> <b>Units:</b> 
647     * </ul>
648     * 
649     * Default Rates:
650     * <ul>
651     *   <li> <b>CAN 2.0:</b> 4.0 Hz
652     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
653     * </ul>
654     * 
655     * This refreshes and returns a cached StatusSignal object.
656     * 
657     * @return NoMotionCount Status Signal Object
658     */
659    public StatusSignal<Double> getNoMotionCount()
660    {
661        return super.lookupStatusSignal(SpnValue.Pigeon2NoMotionCount.value, Double.class, "NoMotionCount", true);
662    }
663        
664    /**
665     * Whether the temperature-compensation feature is disabled.
666     * 
667     * <ul>
668     *   <li> <b>Default Value:</b> 0
669     * </ul>
670     * 
671     * Default Rates:
672     * <ul>
673     *   <li> <b>CAN 2.0:</b> 4.0 Hz
674     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
675     * </ul>
676     * 
677     * This refreshes and returns a cached StatusSignal object.
678     * 
679     * @return TemperatureCompensationDisabled Status Signal Object
680     */
681    public StatusSignal<Boolean> getTemperatureCompensationDisabled()
682    {
683        return super.lookupStatusSignal(SpnValue.Pigeon2TempCompDisabled.value, Boolean.class, "TemperatureCompensationDisabled", true);
684    }
685        
686    /**
687     * How long the Pigeon 2's been up in seconds, caps at 255 seconds.
688     * 
689     * <ul>
690     *   <li> <b>Minimum Value:</b> 0
691     *   <li> <b>Maximum Value:</b> 255
692     *   <li> <b>Default Value:</b> 0
693     *   <li> <b>Units:</b> s
694     * </ul>
695     * 
696     * Default Rates:
697     * <ul>
698     *   <li> <b>CAN 2.0:</b> 4.0 Hz
699     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
700     * </ul>
701     * 
702     * This refreshes and returns a cached StatusSignal object.
703     * 
704     * @return UpTime Status Signal Object
705     */
706    public StatusSignal<Double> getUpTime()
707    {
708        return super.lookupStatusSignal(SpnValue.Pigeon2UpTime.value, Double.class, "UpTime", true);
709    }
710        
711    /**
712     * The accumulated gyro about the X axis without any sensor fusing.
713     * 
714     * <ul>
715     *   <li> <b>Minimum Value:</b> -23040.0
716     *   <li> <b>Maximum Value:</b> 23039.9560546875
717     *   <li> <b>Default Value:</b> 0
718     *   <li> <b>Units:</b> deg
719     * </ul>
720     * 
721     * Default Rates:
722     * <ul>
723     *   <li> <b>CAN 2.0:</b> 4.0 Hz
724     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
725     * </ul>
726     * 
727     * This refreshes and returns a cached StatusSignal object.
728     * 
729     * @return AccumGyroX Status Signal Object
730     */
731    public StatusSignal<Double> getAccumGyroX()
732    {
733        return super.lookupStatusSignal(SpnValue.Pigeon2AccumGyroX.value, Double.class, "AccumGyroX", true);
734    }
735        
736    /**
737     * The accumulated gyro about the Y axis without any sensor fusing.
738     * 
739     * <ul>
740     *   <li> <b>Minimum Value:</b> -23040.0
741     *   <li> <b>Maximum Value:</b> 23039.9560546875
742     *   <li> <b>Default Value:</b> 0
743     *   <li> <b>Units:</b> deg
744     * </ul>
745     * 
746     * Default Rates:
747     * <ul>
748     *   <li> <b>CAN 2.0:</b> 4.0 Hz
749     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
750     * </ul>
751     * 
752     * This refreshes and returns a cached StatusSignal object.
753     * 
754     * @return AccumGyroY Status Signal Object
755     */
756    public StatusSignal<Double> getAccumGyroY()
757    {
758        return super.lookupStatusSignal(SpnValue.Pigeon2AccumGyroY.value, Double.class, "AccumGyroY", true);
759    }
760        
761    /**
762     * The accumulated gyro about the Z axis without any sensor fusing.
763     * 
764     * <ul>
765     *   <li> <b>Minimum Value:</b> -23040.0
766     *   <li> <b>Maximum Value:</b> 23039.9560546875
767     *   <li> <b>Default Value:</b> 0
768     *   <li> <b>Units:</b> deg
769     * </ul>
770     * 
771     * Default Rates:
772     * <ul>
773     *   <li> <b>CAN 2.0:</b> 4.0 Hz
774     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
775     * </ul>
776     * 
777     * This refreshes and returns a cached StatusSignal object.
778     * 
779     * @return AccumGyroZ Status Signal Object
780     */
781    public StatusSignal<Double> getAccumGyroZ()
782    {
783        return super.lookupStatusSignal(SpnValue.Pigeon2AccumGyroZ.value, Double.class, "AccumGyroZ", true);
784    }
785        
786    /**
787     * Angular Velocity world X
788     * <p>
789     * This is the X component of the angular velocity with respect to the
790     * world frame and is mount-calibrated.
791     * 
792     * <ul>
793     *   <li> <b>Minimum Value:</b> -2048.0
794     *   <li> <b>Maximum Value:</b> 2047.99609375
795     *   <li> <b>Default Value:</b> 0
796     *   <li> <b>Units:</b> dps
797     * </ul>
798     * 
799     * Default Rates:
800     * <ul>
801     *   <li> <b>CAN 2.0:</b> 10.0 Hz
802     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
803     * </ul>
804     * 
805     * This refreshes and returns a cached StatusSignal object.
806     * 
807     * @return AngularVelocityXWorld Status Signal Object
808     */
809    public StatusSignal<Double> getAngularVelocityXWorld()
810    {
811        return super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityXWorld.value, Double.class, "AngularVelocityXWorld", true);
812    }
813        
814    /**
815     * Angular Velocity Quaternion Y Component
816     * <p>
817     * This is the Y component of the angular velocity with respect to the
818     * world frame and is mount-calibrated.
819     * 
820     * <ul>
821     *   <li> <b>Minimum Value:</b> -2048.0
822     *   <li> <b>Maximum Value:</b> 2047.99609375
823     *   <li> <b>Default Value:</b> 0
824     *   <li> <b>Units:</b> dps
825     * </ul>
826     * 
827     * Default Rates:
828     * <ul>
829     *   <li> <b>CAN 2.0:</b> 10.0 Hz
830     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
831     * </ul>
832     * 
833     * This refreshes and returns a cached StatusSignal object.
834     * 
835     * @return AngularVelocityYWorld Status Signal Object
836     */
837    public StatusSignal<Double> getAngularVelocityYWorld()
838    {
839        return super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityYWorld.value, Double.class, "AngularVelocityYWorld", true);
840    }
841        
842    /**
843     * Angular Velocity Quaternion Z Component
844     * <p>
845     * This is the Z component of the angular velocity with respect to the
846     * world frame and is mount-calibrated.
847     * 
848     * <ul>
849     *   <li> <b>Minimum Value:</b> -2048.0
850     *   <li> <b>Maximum Value:</b> 2047.99609375
851     *   <li> <b>Default Value:</b> 0
852     *   <li> <b>Units:</b> dps
853     * </ul>
854     * 
855     * Default Rates:
856     * <ul>
857     *   <li> <b>CAN 2.0:</b> 10.0 Hz
858     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
859     * </ul>
860     * 
861     * This refreshes and returns a cached StatusSignal object.
862     * 
863     * @return AngularVelocityZWorld Status Signal Object
864     */
865    public StatusSignal<Double> getAngularVelocityZWorld()
866    {
867        return super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityZWorld.value, Double.class, "AngularVelocityZWorld", true);
868    }
869        
870    /**
871     * The acceleration measured by Pigeon2 in the X direction.
872     * <p>
873     * This value includes the acceleration due to gravity. If this is
874     * undesirable, get the gravity vector and subtract out the
875     * contribution in this direction.
876     * 
877     * <ul>
878     *   <li> <b>Minimum Value:</b> -2.0
879     *   <li> <b>Maximum Value:</b> 1.99993896484375
880     *   <li> <b>Default Value:</b> 0
881     *   <li> <b>Units:</b> g
882     * </ul>
883     * 
884     * Default Rates:
885     * <ul>
886     *   <li> <b>CAN 2.0:</b> 10.0 Hz
887     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
888     * </ul>
889     * 
890     * This refreshes and returns a cached StatusSignal object.
891     * 
892     * @return AccelerationX Status Signal Object
893     */
894    public StatusSignal<Double> getAccelerationX()
895    {
896        return super.lookupStatusSignal(SpnValue.Pigeon2AccelerationX.value, Double.class, "AccelerationX", true);
897    }
898        
899    /**
900     * The acceleration measured by Pigeon2 in the Y direction.
901     * <p>
902     * This value includes the acceleration due to gravity. If this is
903     * undesirable, get the gravity vector and subtract out the
904     * contribution in this direction.
905     * 
906     * <ul>
907     *   <li> <b>Minimum Value:</b> -2.0
908     *   <li> <b>Maximum Value:</b> 1.99993896484375
909     *   <li> <b>Default Value:</b> 0
910     *   <li> <b>Units:</b> g
911     * </ul>
912     * 
913     * Default Rates:
914     * <ul>
915     *   <li> <b>CAN 2.0:</b> 10.0 Hz
916     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
917     * </ul>
918     * 
919     * This refreshes and returns a cached StatusSignal object.
920     * 
921     * @return AccelerationY Status Signal Object
922     */
923    public StatusSignal<Double> getAccelerationY()
924    {
925        return super.lookupStatusSignal(SpnValue.Pigeon2AccelerationY.value, Double.class, "AccelerationY", true);
926    }
927        
928    /**
929     * The acceleration measured by Pigeon2 in the Z direction.
930     * <p>
931     * This value includes the acceleration due to gravity. If this is
932     * undesirable, get the gravity vector and subtract out the
933     * contribution in this direction.
934     * 
935     * <ul>
936     *   <li> <b>Minimum Value:</b> -2.0
937     *   <li> <b>Maximum Value:</b> 1.99993896484375
938     *   <li> <b>Default Value:</b> 0
939     *   <li> <b>Units:</b> g
940     * </ul>
941     * 
942     * Default Rates:
943     * <ul>
944     *   <li> <b>CAN 2.0:</b> 10.0 Hz
945     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
946     * </ul>
947     * 
948     * This refreshes and returns a cached StatusSignal object.
949     * 
950     * @return AccelerationZ Status Signal Object
951     */
952    public StatusSignal<Double> getAccelerationZ()
953    {
954        return super.lookupStatusSignal(SpnValue.Pigeon2AccelerationZ.value, Double.class, "AccelerationZ", true);
955    }
956        
957    /**
958     * Measured supply voltage to the Pigeon2.
959     * 
960     * <ul>
961     *   <li> <b>Minimum Value:</b> 0.0
962     *   <li> <b>Maximum Value:</b> 31.99951171875
963     *   <li> <b>Default Value:</b> 0
964     *   <li> <b>Units:</b> V
965     * </ul>
966     * 
967     * Default Rates:
968     * <ul>
969     *   <li> <b>CAN 2.0:</b> 4.0 Hz
970     *   <li> <b>CAN FD:</b> 100.0 Hz (TimeSynced with Pro)
971     * </ul>
972     * 
973     * This refreshes and returns a cached StatusSignal object.
974     * 
975     * @return SupplyVoltage Status Signal Object
976     */
977    public StatusSignal<Double> getSupplyVoltage()
978    {
979        return super.lookupStatusSignal(SpnValue.Pigeon2_SupplyVoltage.value, Double.class, "SupplyVoltage", true);
980    }
981        
982    /**
983     * The angular velocity (ω) of the Pigeon 2 about the device's X axis.
984     * <p>
985     * This value is not mount-calibrated
986     * 
987     * <ul>
988     *   <li> <b>Minimum Value:</b> -1998.048780487805
989     *   <li> <b>Maximum Value:</b> 1997.987804878049
990     *   <li> <b>Default Value:</b> 0
991     *   <li> <b>Units:</b> dps
992     * </ul>
993     * 
994     * Default Rates:
995     * <ul>
996     *   <li> <b>CAN:</b> 4.0 Hz
997     * </ul>
998     * 
999     * This refreshes and returns a cached StatusSignal object.
1000     * 
1001     * @return AngularVelocityXDevice Status Signal Object
1002     */
1003    public StatusSignal<Double> getAngularVelocityXDevice()
1004    {
1005        return super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityX.value, Double.class, "AngularVelocityXDevice", true);
1006    }
1007        
1008    /**
1009     * The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
1010     * <p>
1011     * This value is not mount-calibrated
1012     * 
1013     * <ul>
1014     *   <li> <b>Minimum Value:</b> -1998.048780487805
1015     *   <li> <b>Maximum Value:</b> 1997.987804878049
1016     *   <li> <b>Default Value:</b> 0
1017     *   <li> <b>Units:</b> dps
1018     * </ul>
1019     * 
1020     * Default Rates:
1021     * <ul>
1022     *   <li> <b>CAN:</b> 4.0 Hz
1023     * </ul>
1024     * 
1025     * This refreshes and returns a cached StatusSignal object.
1026     * 
1027     * @return AngularVelocityYDevice Status Signal Object
1028     */
1029    public StatusSignal<Double> getAngularVelocityYDevice()
1030    {
1031        return super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityY.value, Double.class, "AngularVelocityYDevice", true);
1032    }
1033        
1034    /**
1035     * The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
1036     * <p>
1037     * This value is not mount-calibrated
1038     * 
1039     * <ul>
1040     *   <li> <b>Minimum Value:</b> -1998.048780487805
1041     *   <li> <b>Maximum Value:</b> 1997.987804878049
1042     *   <li> <b>Default Value:</b> 0
1043     *   <li> <b>Units:</b> dps
1044     * </ul>
1045     * 
1046     * Default Rates:
1047     * <ul>
1048     *   <li> <b>CAN:</b> 4.0 Hz
1049     * </ul>
1050     * 
1051     * This refreshes and returns a cached StatusSignal object.
1052     * 
1053     * @return AngularVelocityZDevice Status Signal Object
1054     */
1055    public StatusSignal<Double> getAngularVelocityZDevice()
1056    {
1057        return super.lookupStatusSignal(SpnValue.Pigeon2AngularVelocityZ.value, Double.class, "AngularVelocityZDevice", true);
1058    }
1059        
1060    /**
1061     * The biased magnitude of the magnetic field measured by the Pigeon 2
1062     * in the X direction. This is only valid after performing a
1063     * magnetometer calibration.
1064     * 
1065     * <ul>
1066     *   <li> <b>Minimum Value:</b> -19660.8
1067     *   <li> <b>Maximum Value:</b> 19660.2
1068     *   <li> <b>Default Value:</b> 0
1069     *   <li> <b>Units:</b> uT
1070     * </ul>
1071     * 
1072     * Default Rates:
1073     * <ul>
1074     *   <li> <b>CAN:</b> 4.0 Hz
1075     * </ul>
1076     * 
1077     * This refreshes and returns a cached StatusSignal object.
1078     * 
1079     * @return MagneticFieldX Status Signal Object
1080     */
1081    public StatusSignal<Double> getMagneticFieldX()
1082    {
1083        return super.lookupStatusSignal(SpnValue.Pigeon2MagneticFieldX.value, Double.class, "MagneticFieldX", true);
1084    }
1085        
1086    /**
1087     * The biased magnitude of the magnetic field measured by the Pigeon 2
1088     * in the Y direction. This is only valid after performing a
1089     * magnetometer calibration.
1090     * 
1091     * <ul>
1092     *   <li> <b>Minimum Value:</b> -19660.8
1093     *   <li> <b>Maximum Value:</b> 19660.2
1094     *   <li> <b>Default Value:</b> 0
1095     *   <li> <b>Units:</b> uT
1096     * </ul>
1097     * 
1098     * Default Rates:
1099     * <ul>
1100     *   <li> <b>CAN:</b> 4.0 Hz
1101     * </ul>
1102     * 
1103     * This refreshes and returns a cached StatusSignal object.
1104     * 
1105     * @return MagneticFieldY Status Signal Object
1106     */
1107    public StatusSignal<Double> getMagneticFieldY()
1108    {
1109        return super.lookupStatusSignal(SpnValue.Pigeon2MagneticFieldY.value, Double.class, "MagneticFieldY", true);
1110    }
1111        
1112    /**
1113     * The biased magnitude of the magnetic field measured by the Pigeon 2
1114     * in the Z direction. This is only valid after performing a
1115     * magnetometer calibration.
1116     * 
1117     * <ul>
1118     *   <li> <b>Minimum Value:</b> -19660.8
1119     *   <li> <b>Maximum Value:</b> 19660.2
1120     *   <li> <b>Default Value:</b> 0
1121     *   <li> <b>Units:</b> uT
1122     * </ul>
1123     * 
1124     * Default Rates:
1125     * <ul>
1126     *   <li> <b>CAN:</b> 4.0 Hz
1127     * </ul>
1128     * 
1129     * This refreshes and returns a cached StatusSignal object.
1130     * 
1131     * @return MagneticFieldZ Status Signal Object
1132     */
1133    public StatusSignal<Double> getMagneticFieldZ()
1134    {
1135        return super.lookupStatusSignal(SpnValue.Pigeon2MagneticFieldZ.value, Double.class, "MagneticFieldZ", true);
1136    }
1137        
1138    /**
1139     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
1140     * the X direction. This is only valid after performing a magnetometer
1141     * calibration.
1142     * 
1143     * <ul>
1144     *   <li> <b>Minimum Value:</b> -19660.8
1145     *   <li> <b>Maximum Value:</b> 19660.2
1146     *   <li> <b>Default Value:</b> 0
1147     *   <li> <b>Units:</b> uT
1148     * </ul>
1149     * 
1150     * Default Rates:
1151     * <ul>
1152     *   <li> <b>CAN:</b> 4.0 Hz
1153     * </ul>
1154     * 
1155     * This refreshes and returns a cached StatusSignal object.
1156     * 
1157     * @return RawMagneticFieldX Status Signal Object
1158     */
1159    public StatusSignal<Double> getRawMagneticFieldX()
1160    {
1161        return super.lookupStatusSignal(SpnValue.Pigeon2RawMagneticFieldX.value, Double.class, "RawMagneticFieldX", true);
1162    }
1163        
1164    /**
1165     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
1166     * the Y direction. This is only valid after performing a magnetometer
1167     * calibration.
1168     * 
1169     * <ul>
1170     *   <li> <b>Minimum Value:</b> -19660.8
1171     *   <li> <b>Maximum Value:</b> 19660.2
1172     *   <li> <b>Default Value:</b> 0
1173     *   <li> <b>Units:</b> uT
1174     * </ul>
1175     * 
1176     * Default Rates:
1177     * <ul>
1178     *   <li> <b>CAN:</b> 4.0 Hz
1179     * </ul>
1180     * 
1181     * This refreshes and returns a cached StatusSignal object.
1182     * 
1183     * @return RawMagneticFieldY Status Signal Object
1184     */
1185    public StatusSignal<Double> getRawMagneticFieldY()
1186    {
1187        return super.lookupStatusSignal(SpnValue.Pigeon2RawMagneticFieldY.value, Double.class, "RawMagneticFieldY", true);
1188    }
1189        
1190    /**
1191     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
1192     * the Z direction. This is only valid after performing a magnetometer
1193     * calibration.
1194     * 
1195     * <ul>
1196     *   <li> <b>Minimum Value:</b> -19660.8
1197     *   <li> <b>Maximum Value:</b> 19660.2
1198     *   <li> <b>Default Value:</b> 0
1199     *   <li> <b>Units:</b> uT
1200     * </ul>
1201     * 
1202     * Default Rates:
1203     * <ul>
1204     *   <li> <b>CAN:</b> 4.0 Hz
1205     * </ul>
1206     * 
1207     * This refreshes and returns a cached StatusSignal object.
1208     * 
1209     * @return RawMagneticFieldZ Status Signal Object
1210     */
1211    public StatusSignal<Double> getRawMagneticFieldZ()
1212    {
1213        return super.lookupStatusSignal(SpnValue.Pigeon2RawMagneticFieldZ.value, Double.class, "RawMagneticFieldZ", true);
1214    }
1215        
1216    /**
1217     * Whether the device is Phoenix Pro licensed.
1218     * 
1219     * <ul>
1220     *   <li> <b>Default Value:</b> False
1221     * </ul>
1222     * 
1223     * Default Rates:
1224     * <ul>
1225     *   <li> <b>CAN:</b> 4.0 Hz
1226     * </ul>
1227     * 
1228     * This refreshes and returns a cached StatusSignal object.
1229     * 
1230     * @return IsProLicensed Status Signal Object
1231     */
1232    public StatusSignal<Boolean> getIsProLicensed()
1233    {
1234        return super.lookupStatusSignal(SpnValue.Version_IsProLicensed.value, Boolean.class, "IsProLicensed", true);
1235    }
1236        
1237    /**
1238     * Hardware fault occurred
1239     * 
1240     * <ul>
1241     *   <li> <b>Default Value:</b> False
1242     * </ul>
1243     * 
1244     * Default Rates:
1245     * <ul>
1246     *   <li> <b>CAN:</b> 4.0 Hz
1247     * </ul>
1248     * 
1249     * This refreshes and returns a cached StatusSignal object.
1250     * 
1251     * @return Fault_Hardware Status Signal Object
1252     */
1253    public StatusSignal<Boolean> getFault_Hardware()
1254    {
1255        return super.lookupStatusSignal(SpnValue.Fault_Hardware.value, Boolean.class, "Fault_Hardware", true);
1256    }
1257        
1258    /**
1259     * Hardware fault occurred
1260     * 
1261     * <ul>
1262     *   <li> <b>Default Value:</b> False
1263     * </ul>
1264     * 
1265     * Default Rates:
1266     * <ul>
1267     *   <li> <b>CAN:</b> 4.0 Hz
1268     * </ul>
1269     * 
1270     * This refreshes and returns a cached StatusSignal object.
1271     * 
1272     * @return StickyFault_Hardware Status Signal Object
1273     */
1274    public StatusSignal<Boolean> getStickyFault_Hardware()
1275    {
1276        return super.lookupStatusSignal(SpnValue.StickyFault_Hardware.value, Boolean.class, "StickyFault_Hardware", true);
1277    }
1278        
1279    /**
1280     * Device supply voltage dropped to near brownout levels
1281     * 
1282     * <ul>
1283     *   <li> <b>Default Value:</b> False
1284     * </ul>
1285     * 
1286     * Default Rates:
1287     * <ul>
1288     *   <li> <b>CAN:</b> 4.0 Hz
1289     * </ul>
1290     * 
1291     * This refreshes and returns a cached StatusSignal object.
1292     * 
1293     * @return Fault_Undervoltage Status Signal Object
1294     */
1295    public StatusSignal<Boolean> getFault_Undervoltage()
1296    {
1297        return super.lookupStatusSignal(SpnValue.Fault_Undervoltage.value, Boolean.class, "Fault_Undervoltage", true);
1298    }
1299        
1300    /**
1301     * Device supply voltage dropped to near brownout levels
1302     * 
1303     * <ul>
1304     *   <li> <b>Default Value:</b> False
1305     * </ul>
1306     * 
1307     * Default Rates:
1308     * <ul>
1309     *   <li> <b>CAN:</b> 4.0 Hz
1310     * </ul>
1311     * 
1312     * This refreshes and returns a cached StatusSignal object.
1313     * 
1314     * @return StickyFault_Undervoltage Status Signal Object
1315     */
1316    public StatusSignal<Boolean> getStickyFault_Undervoltage()
1317    {
1318        return super.lookupStatusSignal(SpnValue.StickyFault_Undervoltage.value, Boolean.class, "StickyFault_Undervoltage", true);
1319    }
1320        
1321    /**
1322     * Device boot while detecting the enable signal
1323     * 
1324     * <ul>
1325     *   <li> <b>Default Value:</b> False
1326     * </ul>
1327     * 
1328     * Default Rates:
1329     * <ul>
1330     *   <li> <b>CAN:</b> 4.0 Hz
1331     * </ul>
1332     * 
1333     * This refreshes and returns a cached StatusSignal object.
1334     * 
1335     * @return Fault_BootDuringEnable Status Signal Object
1336     */
1337    public StatusSignal<Boolean> getFault_BootDuringEnable()
1338    {
1339        return super.lookupStatusSignal(SpnValue.Fault_BootDuringEnable.value, Boolean.class, "Fault_BootDuringEnable", true);
1340    }
1341        
1342    /**
1343     * Device boot while detecting the enable signal
1344     * 
1345     * <ul>
1346     *   <li> <b>Default Value:</b> False
1347     * </ul>
1348     * 
1349     * Default Rates:
1350     * <ul>
1351     *   <li> <b>CAN:</b> 4.0 Hz
1352     * </ul>
1353     * 
1354     * This refreshes and returns a cached StatusSignal object.
1355     * 
1356     * @return StickyFault_BootDuringEnable Status Signal Object
1357     */
1358    public StatusSignal<Boolean> getStickyFault_BootDuringEnable()
1359    {
1360        return super.lookupStatusSignal(SpnValue.StickyFault_BootDuringEnable.value, Boolean.class, "StickyFault_BootDuringEnable", true);
1361    }
1362        
1363    /**
1364     * An unlicensed feature is in use, device may not behave as expected.
1365     * 
1366     * <ul>
1367     *   <li> <b>Default Value:</b> False
1368     * </ul>
1369     * 
1370     * Default Rates:
1371     * <ul>
1372     *   <li> <b>CAN:</b> 4.0 Hz
1373     * </ul>
1374     * 
1375     * This refreshes and returns a cached StatusSignal object.
1376     * 
1377     * @return Fault_UnlicensedFeatureInUse Status Signal Object
1378     */
1379    public StatusSignal<Boolean> getFault_UnlicensedFeatureInUse()
1380    {
1381        return super.lookupStatusSignal(SpnValue.Fault_UnlicensedFeatureInUse.value, Boolean.class, "Fault_UnlicensedFeatureInUse", true);
1382    }
1383        
1384    /**
1385     * An unlicensed feature is in use, device may not behave as expected.
1386     * 
1387     * <ul>
1388     *   <li> <b>Default Value:</b> False
1389     * </ul>
1390     * 
1391     * Default Rates:
1392     * <ul>
1393     *   <li> <b>CAN:</b> 4.0 Hz
1394     * </ul>
1395     * 
1396     * This refreshes and returns a cached StatusSignal object.
1397     * 
1398     * @return StickyFault_UnlicensedFeatureInUse Status Signal Object
1399     */
1400    public StatusSignal<Boolean> getStickyFault_UnlicensedFeatureInUse()
1401    {
1402        return super.lookupStatusSignal(SpnValue.StickyFault_UnlicensedFeatureInUse.value, Boolean.class, "StickyFault_UnlicensedFeatureInUse", true);
1403    }
1404        
1405    /**
1406     * Bootup checks failed: Accelerometer
1407     * 
1408     * <ul>
1409     *   <li> <b>Default Value:</b> False
1410     * </ul>
1411     * 
1412     * Default Rates:
1413     * <ul>
1414     *   <li> <b>CAN:</b> 4.0 Hz
1415     * </ul>
1416     * 
1417     * This refreshes and returns a cached StatusSignal object.
1418     * 
1419     * @return Fault_BootupAccelerometer Status Signal Object
1420     */
1421    public StatusSignal<Boolean> getFault_BootupAccelerometer()
1422    {
1423        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootupAccel.value, Boolean.class, "Fault_BootupAccelerometer", true);
1424    }
1425        
1426    /**
1427     * Bootup checks failed: Accelerometer
1428     * 
1429     * <ul>
1430     *   <li> <b>Default Value:</b> False
1431     * </ul>
1432     * 
1433     * Default Rates:
1434     * <ul>
1435     *   <li> <b>CAN:</b> 4.0 Hz
1436     * </ul>
1437     * 
1438     * This refreshes and returns a cached StatusSignal object.
1439     * 
1440     * @return StickyFault_BootupAccelerometer Status Signal Object
1441     */
1442    public StatusSignal<Boolean> getStickyFault_BootupAccelerometer()
1443    {
1444        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootupAccel.value, Boolean.class, "StickyFault_BootupAccelerometer", true);
1445    }
1446        
1447    /**
1448     * Bootup checks failed: Gyroscope
1449     * 
1450     * <ul>
1451     *   <li> <b>Default Value:</b> False
1452     * </ul>
1453     * 
1454     * Default Rates:
1455     * <ul>
1456     *   <li> <b>CAN:</b> 4.0 Hz
1457     * </ul>
1458     * 
1459     * This refreshes and returns a cached StatusSignal object.
1460     * 
1461     * @return Fault_BootupGyroscope Status Signal Object
1462     */
1463    public StatusSignal<Boolean> getFault_BootupGyroscope()
1464    {
1465        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootupGyros.value, Boolean.class, "Fault_BootupGyroscope", true);
1466    }
1467        
1468    /**
1469     * Bootup checks failed: Gyroscope
1470     * 
1471     * <ul>
1472     *   <li> <b>Default Value:</b> False
1473     * </ul>
1474     * 
1475     * Default Rates:
1476     * <ul>
1477     *   <li> <b>CAN:</b> 4.0 Hz
1478     * </ul>
1479     * 
1480     * This refreshes and returns a cached StatusSignal object.
1481     * 
1482     * @return StickyFault_BootupGyroscope Status Signal Object
1483     */
1484    public StatusSignal<Boolean> getStickyFault_BootupGyroscope()
1485    {
1486        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootupGyros.value, Boolean.class, "StickyFault_BootupGyroscope", true);
1487    }
1488        
1489    /**
1490     * Bootup checks failed: Magnetometer
1491     * 
1492     * <ul>
1493     *   <li> <b>Default Value:</b> False
1494     * </ul>
1495     * 
1496     * Default Rates:
1497     * <ul>
1498     *   <li> <b>CAN:</b> 4.0 Hz
1499     * </ul>
1500     * 
1501     * This refreshes and returns a cached StatusSignal object.
1502     * 
1503     * @return Fault_BootupMagnetometer Status Signal Object
1504     */
1505    public StatusSignal<Boolean> getFault_BootupMagnetometer()
1506    {
1507        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootupMagne.value, Boolean.class, "Fault_BootupMagnetometer", true);
1508    }
1509        
1510    /**
1511     * Bootup checks failed: Magnetometer
1512     * 
1513     * <ul>
1514     *   <li> <b>Default Value:</b> False
1515     * </ul>
1516     * 
1517     * Default Rates:
1518     * <ul>
1519     *   <li> <b>CAN:</b> 4.0 Hz
1520     * </ul>
1521     * 
1522     * This refreshes and returns a cached StatusSignal object.
1523     * 
1524     * @return StickyFault_BootupMagnetometer Status Signal Object
1525     */
1526    public StatusSignal<Boolean> getStickyFault_BootupMagnetometer()
1527    {
1528        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootupMagne.value, Boolean.class, "StickyFault_BootupMagnetometer", true);
1529    }
1530        
1531    /**
1532     * Motion Detected during bootup.
1533     * 
1534     * <ul>
1535     *   <li> <b>Default Value:</b> False
1536     * </ul>
1537     * 
1538     * Default Rates:
1539     * <ul>
1540     *   <li> <b>CAN:</b> 4.0 Hz
1541     * </ul>
1542     * 
1543     * This refreshes and returns a cached StatusSignal object.
1544     * 
1545     * @return Fault_BootIntoMotion Status Signal Object
1546     */
1547    public StatusSignal<Boolean> getFault_BootIntoMotion()
1548    {
1549        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_BootIntoMotion.value, Boolean.class, "Fault_BootIntoMotion", true);
1550    }
1551        
1552    /**
1553     * Motion Detected during bootup.
1554     * 
1555     * <ul>
1556     *   <li> <b>Default Value:</b> False
1557     * </ul>
1558     * 
1559     * Default Rates:
1560     * <ul>
1561     *   <li> <b>CAN:</b> 4.0 Hz
1562     * </ul>
1563     * 
1564     * This refreshes and returns a cached StatusSignal object.
1565     * 
1566     * @return StickyFault_BootIntoMotion Status Signal Object
1567     */
1568    public StatusSignal<Boolean> getStickyFault_BootIntoMotion()
1569    {
1570        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_BootIntoMotion.value, Boolean.class, "StickyFault_BootIntoMotion", true);
1571    }
1572        
1573    /**
1574     * Motion stack data acquisition was slower than expected
1575     * 
1576     * <ul>
1577     *   <li> <b>Default Value:</b> False
1578     * </ul>
1579     * 
1580     * Default Rates:
1581     * <ul>
1582     *   <li> <b>CAN:</b> 4.0 Hz
1583     * </ul>
1584     * 
1585     * This refreshes and returns a cached StatusSignal object.
1586     * 
1587     * @return Fault_DataAcquiredLate Status Signal Object
1588     */
1589    public StatusSignal<Boolean> getFault_DataAcquiredLate()
1590    {
1591        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_DataAcquiredLate.value, Boolean.class, "Fault_DataAcquiredLate", true);
1592    }
1593        
1594    /**
1595     * Motion stack data acquisition was slower than expected
1596     * 
1597     * <ul>
1598     *   <li> <b>Default Value:</b> False
1599     * </ul>
1600     * 
1601     * Default Rates:
1602     * <ul>
1603     *   <li> <b>CAN:</b> 4.0 Hz
1604     * </ul>
1605     * 
1606     * This refreshes and returns a cached StatusSignal object.
1607     * 
1608     * @return StickyFault_DataAcquiredLate Status Signal Object
1609     */
1610    public StatusSignal<Boolean> getStickyFault_DataAcquiredLate()
1611    {
1612        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_DataAcquiredLate.value, Boolean.class, "StickyFault_DataAcquiredLate", true);
1613    }
1614        
1615    /**
1616     * Motion stack loop time was slower than expected.
1617     * 
1618     * <ul>
1619     *   <li> <b>Default Value:</b> False
1620     * </ul>
1621     * 
1622     * Default Rates:
1623     * <ul>
1624     *   <li> <b>CAN:</b> 4.0 Hz
1625     * </ul>
1626     * 
1627     * This refreshes and returns a cached StatusSignal object.
1628     * 
1629     * @return Fault_LoopTimeSlow Status Signal Object
1630     */
1631    public StatusSignal<Boolean> getFault_LoopTimeSlow()
1632    {
1633        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_LoopTimeSlow.value, Boolean.class, "Fault_LoopTimeSlow", true);
1634    }
1635        
1636    /**
1637     * Motion stack loop time was slower than expected.
1638     * 
1639     * <ul>
1640     *   <li> <b>Default Value:</b> False
1641     * </ul>
1642     * 
1643     * Default Rates:
1644     * <ul>
1645     *   <li> <b>CAN:</b> 4.0 Hz
1646     * </ul>
1647     * 
1648     * This refreshes and returns a cached StatusSignal object.
1649     * 
1650     * @return StickyFault_LoopTimeSlow Status Signal Object
1651     */
1652    public StatusSignal<Boolean> getStickyFault_LoopTimeSlow()
1653    {
1654        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_LoopTimeSlow.value, Boolean.class, "StickyFault_LoopTimeSlow", true);
1655    }
1656        
1657    /**
1658     * Magnetometer values are saturated
1659     * 
1660     * <ul>
1661     *   <li> <b>Default Value:</b> False
1662     * </ul>
1663     * 
1664     * Default Rates:
1665     * <ul>
1666     *   <li> <b>CAN:</b> 4.0 Hz
1667     * </ul>
1668     * 
1669     * This refreshes and returns a cached StatusSignal object.
1670     * 
1671     * @return Fault_SaturatedMagnetometer Status Signal Object
1672     */
1673    public StatusSignal<Boolean> getFault_SaturatedMagnetometer()
1674    {
1675        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_SaturatedMagne.value, Boolean.class, "Fault_SaturatedMagnetometer", true);
1676    }
1677        
1678    /**
1679     * Magnetometer values are saturated
1680     * 
1681     * <ul>
1682     *   <li> <b>Default Value:</b> False
1683     * </ul>
1684     * 
1685     * Default Rates:
1686     * <ul>
1687     *   <li> <b>CAN:</b> 4.0 Hz
1688     * </ul>
1689     * 
1690     * This refreshes and returns a cached StatusSignal object.
1691     * 
1692     * @return StickyFault_SaturatedMagnetometer Status Signal Object
1693     */
1694    public StatusSignal<Boolean> getStickyFault_SaturatedMagnetometer()
1695    {
1696        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_SaturatedMagne.value, Boolean.class, "StickyFault_SaturatedMagnetometer", true);
1697    }
1698        
1699    /**
1700     * Accelerometer values are saturated
1701     * 
1702     * <ul>
1703     *   <li> <b>Default Value:</b> False
1704     * </ul>
1705     * 
1706     * Default Rates:
1707     * <ul>
1708     *   <li> <b>CAN:</b> 4.0 Hz
1709     * </ul>
1710     * 
1711     * This refreshes and returns a cached StatusSignal object.
1712     * 
1713     * @return Fault_SaturatedAccelerometer Status Signal Object
1714     */
1715    public StatusSignal<Boolean> getFault_SaturatedAccelerometer()
1716    {
1717        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_SaturatedAccel.value, Boolean.class, "Fault_SaturatedAccelerometer", true);
1718    }
1719        
1720    /**
1721     * Accelerometer values are saturated
1722     * 
1723     * <ul>
1724     *   <li> <b>Default Value:</b> False
1725     * </ul>
1726     * 
1727     * Default Rates:
1728     * <ul>
1729     *   <li> <b>CAN:</b> 4.0 Hz
1730     * </ul>
1731     * 
1732     * This refreshes and returns a cached StatusSignal object.
1733     * 
1734     * @return StickyFault_SaturatedAccelerometer Status Signal Object
1735     */
1736    public StatusSignal<Boolean> getStickyFault_SaturatedAccelerometer()
1737    {
1738        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_SaturatedAccel.value, Boolean.class, "StickyFault_SaturatedAccelerometer", true);
1739    }
1740        
1741    /**
1742     * Gyroscope values are saturated
1743     * 
1744     * <ul>
1745     *   <li> <b>Default Value:</b> False
1746     * </ul>
1747     * 
1748     * Default Rates:
1749     * <ul>
1750     *   <li> <b>CAN:</b> 4.0 Hz
1751     * </ul>
1752     * 
1753     * This refreshes and returns a cached StatusSignal object.
1754     * 
1755     * @return Fault_SaturatedGyroscope Status Signal Object
1756     */
1757    public StatusSignal<Boolean> getFault_SaturatedGyroscope()
1758    {
1759        return super.lookupStatusSignal(SpnValue.Fault_PIGEON2_SaturatedGyros.value, Boolean.class, "Fault_SaturatedGyroscope", true);
1760    }
1761        
1762    /**
1763     * Gyroscope values are saturated
1764     * 
1765     * <ul>
1766     *   <li> <b>Default Value:</b> False
1767     * </ul>
1768     * 
1769     * Default Rates:
1770     * <ul>
1771     *   <li> <b>CAN:</b> 4.0 Hz
1772     * </ul>
1773     * 
1774     * This refreshes and returns a cached StatusSignal object.
1775     * 
1776     * @return StickyFault_SaturatedGyroscope Status Signal Object
1777     */
1778    public StatusSignal<Boolean> getStickyFault_SaturatedGyroscope()
1779    {
1780        return super.lookupStatusSignal(SpnValue.StickyFault_PIGEON2_SaturatedGyros.value, Boolean.class, "StickyFault_SaturatedGyroscope", true);
1781    }
1782
1783    
1784
1785    /**
1786     * Control motor with generic control request object.
1787     * <p>
1788     * User must make sure the specified object is castable to a valid control request,
1789     * otherwise this function will fail at run-time and return the NotSupported StatusCode
1790     *
1791     * @param request                Control object to request of the device
1792     * @return Status Code of the request, 0 is OK
1793     */
1794    public StatusCode setControl(ControlRequest request)
1795    {
1796        
1797        return StatusCode.NotSupported;
1798    }
1799
1800    
1801    /**
1802     * The yaw to set the Pigeon2 to right now.
1803     * 
1804     * @param newValue Value to set to. Units are in deg.
1805     * @param timeoutSeconds Maximum time to wait up to in seconds.
1806     * @return StatusCode of the set command
1807     */
1808    public StatusCode setYaw(double newValue, double timeoutSeconds) {
1809        return getConfigurator().setYaw(newValue, timeoutSeconds);
1810    }
1811    /**
1812     * The yaw to set the Pigeon2 to right now.
1813     * <p>
1814     * This will wait up to 0.050 seconds (50ms) by default.
1815     * 
1816     * @param newValue Value to set to. Units are in deg.
1817     * @return StatusCode of the set command
1818     */
1819    public StatusCode setYaw(double newValue) {
1820        return setYaw(newValue, 0.050);
1821    }
1822    
1823    /**
1824     * Clear the sticky faults in the device.
1825     * <p>
1826     * This typically has no impact on the device functionality.  Instead,
1827     * it just clears telemetry faults that are accessible via API and
1828     * Tuner Self-Test.
1829     * 
1830     * @param timeoutSeconds Maximum time to wait up to in seconds.
1831     * @return StatusCode of the set command
1832     */
1833    public StatusCode clearStickyFaults(double timeoutSeconds) {
1834        return getConfigurator().clearStickyFaults(timeoutSeconds);
1835    }
1836    /**
1837     * Clear the sticky faults in the device.
1838     * <p>
1839     * This typically has no impact on the device functionality.  Instead,
1840     * it just clears telemetry faults that are accessible via API and
1841     * Tuner Self-Test.
1842     * <p>
1843     * This will wait up to 0.050 seconds (50ms) by default.
1844     * 
1845     * @return StatusCode of the set command
1846     */
1847    public StatusCode clearStickyFaults() {
1848        return clearStickyFaults(0.050);
1849    }
1850    
1851    /**
1852     * Clear sticky fault: Hardware fault occurred
1853     * 
1854     * @param timeoutSeconds Maximum time to wait up to in seconds.
1855     * @return StatusCode of the set command
1856     */
1857    public StatusCode clearStickyFault_Hardware(double timeoutSeconds) {
1858        return getConfigurator().clearStickyFault_Hardware(timeoutSeconds);
1859    }
1860    /**
1861     * Clear sticky fault: Hardware fault occurred
1862     * <p>
1863     * This will wait up to 0.050 seconds (50ms) by default.
1864     * 
1865     * @return StatusCode of the set command
1866     */
1867    public StatusCode clearStickyFault_Hardware() {
1868        return clearStickyFault_Hardware(0.050);
1869    }
1870    
1871    /**
1872     * Clear sticky fault: Device supply voltage dropped to near brownout
1873     * levels
1874     * 
1875     * @param timeoutSeconds Maximum time to wait up to in seconds.
1876     * @return StatusCode of the set command
1877     */
1878    public StatusCode clearStickyFault_Undervoltage(double timeoutSeconds) {
1879        return getConfigurator().clearStickyFault_Undervoltage(timeoutSeconds);
1880    }
1881    /**
1882     * Clear sticky fault: Device supply voltage dropped to near brownout
1883     * levels
1884     * <p>
1885     * This will wait up to 0.050 seconds (50ms) by default.
1886     * 
1887     * @return StatusCode of the set command
1888     */
1889    public StatusCode clearStickyFault_Undervoltage() {
1890        return clearStickyFault_Undervoltage(0.050);
1891    }
1892    
1893    /**
1894     * Clear sticky fault: Device boot while detecting the enable signal
1895     * 
1896     * @param timeoutSeconds Maximum time to wait up to in seconds.
1897     * @return StatusCode of the set command
1898     */
1899    public StatusCode clearStickyFault_BootDuringEnable(double timeoutSeconds) {
1900        return getConfigurator().clearStickyFault_BootDuringEnable(timeoutSeconds);
1901    }
1902    /**
1903     * Clear sticky fault: Device boot while detecting the enable signal
1904     * <p>
1905     * This will wait up to 0.050 seconds (50ms) by default.
1906     * 
1907     * @return StatusCode of the set command
1908     */
1909    public StatusCode clearStickyFault_BootDuringEnable() {
1910        return clearStickyFault_BootDuringEnable(0.050);
1911    }
1912    
1913    /**
1914     * Clear sticky fault: Bootup checks failed: Accelerometer
1915     * 
1916     * @param timeoutSeconds Maximum time to wait up to in seconds.
1917     * @return StatusCode of the set command
1918     */
1919    public StatusCode clearStickyFault_BootupAccelerometer(double timeoutSeconds) {
1920        return getConfigurator().clearStickyFault_BootupAccelerometer(timeoutSeconds);
1921    }
1922    /**
1923     * Clear sticky fault: Bootup checks failed: Accelerometer
1924     * <p>
1925     * This will wait up to 0.050 seconds (50ms) by default.
1926     * 
1927     * @return StatusCode of the set command
1928     */
1929    public StatusCode clearStickyFault_BootupAccelerometer() {
1930        return clearStickyFault_BootupAccelerometer(0.050);
1931    }
1932    
1933    /**
1934     * Clear sticky fault: Bootup checks failed: Gyroscope
1935     * 
1936     * @param timeoutSeconds Maximum time to wait up to in seconds.
1937     * @return StatusCode of the set command
1938     */
1939    public StatusCode clearStickyFault_BootupGyroscope(double timeoutSeconds) {
1940        return getConfigurator().clearStickyFault_BootupGyroscope(timeoutSeconds);
1941    }
1942    /**
1943     * Clear sticky fault: Bootup checks failed: Gyroscope
1944     * <p>
1945     * This will wait up to 0.050 seconds (50ms) by default.
1946     * 
1947     * @return StatusCode of the set command
1948     */
1949    public StatusCode clearStickyFault_BootupGyroscope() {
1950        return clearStickyFault_BootupGyroscope(0.050);
1951    }
1952    
1953    /**
1954     * Clear sticky fault: Bootup checks failed: Magnetometer
1955     * 
1956     * @param timeoutSeconds Maximum time to wait up to in seconds.
1957     * @return StatusCode of the set command
1958     */
1959    public StatusCode clearStickyFault_BootupMagnetometer(double timeoutSeconds) {
1960        return getConfigurator().clearStickyFault_BootupMagnetometer(timeoutSeconds);
1961    }
1962    /**
1963     * Clear sticky fault: Bootup checks failed: Magnetometer
1964     * <p>
1965     * This will wait up to 0.050 seconds (50ms) by default.
1966     * 
1967     * @return StatusCode of the set command
1968     */
1969    public StatusCode clearStickyFault_BootupMagnetometer() {
1970        return clearStickyFault_BootupMagnetometer(0.050);
1971    }
1972    
1973    /**
1974     * Clear sticky fault: Motion Detected during bootup.
1975     * 
1976     * @param timeoutSeconds Maximum time to wait up to in seconds.
1977     * @return StatusCode of the set command
1978     */
1979    public StatusCode clearStickyFault_BootIntoMotion(double timeoutSeconds) {
1980        return getConfigurator().clearStickyFault_BootIntoMotion(timeoutSeconds);
1981    }
1982    /**
1983     * Clear sticky fault: Motion Detected during bootup.
1984     * <p>
1985     * This will wait up to 0.050 seconds (50ms) by default.
1986     * 
1987     * @return StatusCode of the set command
1988     */
1989    public StatusCode clearStickyFault_BootIntoMotion() {
1990        return clearStickyFault_BootIntoMotion(0.050);
1991    }
1992    
1993    /**
1994     * Clear sticky fault: Motion stack data acquisition was slower than
1995     * expected
1996     * 
1997     * @param timeoutSeconds Maximum time to wait up to in seconds.
1998     * @return StatusCode of the set command
1999     */
2000    public StatusCode clearStickyFault_DataAcquiredLate(double timeoutSeconds) {
2001        return getConfigurator().clearStickyFault_DataAcquiredLate(timeoutSeconds);
2002    }
2003    /**
2004     * Clear sticky fault: Motion stack data acquisition was slower than
2005     * expected
2006     * <p>
2007     * This will wait up to 0.050 seconds (50ms) by default.
2008     * 
2009     * @return StatusCode of the set command
2010     */
2011    public StatusCode clearStickyFault_DataAcquiredLate() {
2012        return clearStickyFault_DataAcquiredLate(0.050);
2013    }
2014    
2015    /**
2016     * Clear sticky fault: Motion stack loop time was slower than
2017     * expected.
2018     * 
2019     * @param timeoutSeconds Maximum time to wait up to in seconds.
2020     * @return StatusCode of the set command
2021     */
2022    public StatusCode clearStickyFault_LoopTimeSlow(double timeoutSeconds) {
2023        return getConfigurator().clearStickyFault_LoopTimeSlow(timeoutSeconds);
2024    }
2025    /**
2026     * Clear sticky fault: Motion stack loop time was slower than
2027     * expected.
2028     * <p>
2029     * This will wait up to 0.050 seconds (50ms) by default.
2030     * 
2031     * @return StatusCode of the set command
2032     */
2033    public StatusCode clearStickyFault_LoopTimeSlow() {
2034        return clearStickyFault_LoopTimeSlow(0.050);
2035    }
2036    
2037    /**
2038     * Clear sticky fault: Magnetometer values are saturated
2039     * 
2040     * @param timeoutSeconds Maximum time to wait up to in seconds.
2041     * @return StatusCode of the set command
2042     */
2043    public StatusCode clearStickyFault_SaturatedMagnetometer(double timeoutSeconds) {
2044        return getConfigurator().clearStickyFault_SaturatedMagnetometer(timeoutSeconds);
2045    }
2046    /**
2047     * Clear sticky fault: Magnetometer values are saturated
2048     * <p>
2049     * This will wait up to 0.050 seconds (50ms) by default.
2050     * 
2051     * @return StatusCode of the set command
2052     */
2053    public StatusCode clearStickyFault_SaturatedMagnetometer() {
2054        return clearStickyFault_SaturatedMagnetometer(0.050);
2055    }
2056    
2057    /**
2058     * Clear sticky fault: Accelerometer values are saturated
2059     * 
2060     * @param timeoutSeconds Maximum time to wait up to in seconds.
2061     * @return StatusCode of the set command
2062     */
2063    public StatusCode clearStickyFault_SaturatedAccelerometer(double timeoutSeconds) {
2064        return getConfigurator().clearStickyFault_SaturatedAccelerometer(timeoutSeconds);
2065    }
2066    /**
2067     * Clear sticky fault: Accelerometer values are saturated
2068     * <p>
2069     * This will wait up to 0.050 seconds (50ms) by default.
2070     * 
2071     * @return StatusCode of the set command
2072     */
2073    public StatusCode clearStickyFault_SaturatedAccelerometer() {
2074        return clearStickyFault_SaturatedAccelerometer(0.050);
2075    }
2076    
2077    /**
2078     * Clear sticky fault: Gyroscope values are saturated
2079     * 
2080     * @param timeoutSeconds Maximum time to wait up to in seconds.
2081     * @return StatusCode of the set command
2082     */
2083    public StatusCode clearStickyFault_SaturatedGyroscope(double timeoutSeconds) {
2084        return getConfigurator().clearStickyFault_SaturatedGyroscope(timeoutSeconds);
2085    }
2086    /**
2087     * Clear sticky fault: Gyroscope values are saturated
2088     * <p>
2089     * This will wait up to 0.050 seconds (50ms) by default.
2090     * 
2091     * @return StatusCode of the set command
2092     */
2093    public StatusCode clearStickyFault_SaturatedGyroscope() {
2094        return clearStickyFault_SaturatedGyroscope(0.050);
2095    }
2096}
2097