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.phoenixpro.hardware.core;
008
009import com.ctre.phoenixpro.hardware.ParentDevice;
010import com.ctre.phoenixpro.controls.*;
011import com.ctre.phoenixpro.configs.*;
012import com.ctre.phoenix6.StatusCode;
013import com.ctre.phoenix6.jni.ErrorReportingJNI;
014import com.ctre.phoenix6.jni.PlatformJNI;
015import com.ctre.phoenixpro.sim.DeviceType;
016import com.ctre.phoenixpro.sim.Pigeon2SimState;
017import com.ctre.phoenixpro.StatusSignalValue;
018import com.ctre.phoenix6.spns.*;
019import com.ctre.phoenixpro.Utils;
020
021/**
022 * Class description for the Pigeon 2 IMU sensor that measures orientation.
023 *
024 * @deprecated Classes in the phoenixpro package will be removed in 2024.
025 *             Users should instead use classes from the phoenix6 package.
026 */
027@Deprecated(forRemoval = true)
028public class CorePigeon2 extends ParentDevice
029{
030    private Pigeon2Configurator _configurator;
031
032    private StatusSignalValue<Integer> _version;
033    private boolean _isVersionOk = false;
034    private double _timeToRefreshVersion = Utils.getCurrentTimeSeconds();
035
036    private StatusSignalValue<Integer> _resetFlags;
037    private double _resetTimestamp = 0;
038
039    private double _creationTime = Utils.getCurrentTimeSeconds();
040
041    @Override
042    protected void reportIfTooOld()
043    {
044        /* If we're not initialized, we can't even check the versions */
045        if (_isVersionOk) {
046            return;
047        }
048        /* Check if we have our versions initialized */
049        if (_version == null) {
050            return;
051        }
052
053        /* get fresh data if enough time has passed */
054        final double currentTime = Utils.getCurrentTimeSeconds();
055        if (currentTime >= _timeToRefreshVersion) {
056            /* Try to refresh again after 250ms */
057            _timeToRefreshVersion = currentTime + 0.25;
058            /* Refresh versions, don't print out if there's an error with refreshing */
059            _version.refresh(false);
060            
061            /* process the fetched version */
062            StatusCode code = StatusCode.OK;
063    
064            /* First check if we have good versions or not */
065            if (_version.getError().isOK()) {
066                final long fullVersion = _version.getValue();
067    
068                if (Utils.isSimulation()) {
069                    /* only check major version in simulation */
070                    final int majorVersion = (int)((fullVersion >> 0x18) & 0xFF);
071    
072                    /* Just check if it's good */
073                    if (majorVersion != 23) {
074                        code = StatusCode.FirmwareTooOld;
075                    }
076                    else {
077                        /* Equal major versions, this is sufficient */
078                    }
079                }
080                else {
081                    /* test the parts individually */
082                    final int majorVersion = (int)((fullVersion >> 0x18) & 0xFF);
083                    final int minorVersion = (int)((fullVersion >> 0x10) & 0xFF);
084                    final int bugfixVersion = (int)((fullVersion >> 0x08) & 0xFF);
085                    final int buildVersion = (int)((fullVersion >> 0x00) & 0xFF);
086    
087                    /* Just check if they're good */
088                    if (majorVersion < 23) {
089                        code = StatusCode.FirmwareTooOld;
090                    }
091                    else if (majorVersion > 23) {
092                    }
093                    else if (minorVersion < 1) {
094                        code = StatusCode.FirmwareTooOld;
095                    }
096                    else if (minorVersion > 1) {
097                    }
098                    else if (bugfixVersion < 4) {
099                        code = StatusCode.FirmwareTooOld;
100                    }
101                    else if (bugfixVersion > 4) {
102                    }
103                    else if (buildVersion < 0) {
104                        code = StatusCode.FirmwareTooOld;
105                    }
106                    else if (buildVersion > 0) {
107                    }
108                    else {
109                        /* Equal versions, this is sufficient */
110                    }
111                }
112            }
113            else {
114                /* don't care why we couldn't get message, just report we didn't get it */
115                code = StatusCode.CouldNotRetrieveProFirmware;
116            }
117    
118            /* how much time has passed */
119            final double deltaTimeSec = currentTime - _creationTime;
120    
121            if (code.isOK()) {
122                /* version is retrieved and healthy */
123                _isVersionOk = true;
124            }
125            else if (code == StatusCode.FirmwareTooOld || deltaTimeSec >= 3.0) {
126                /* report error */
127                ErrorReportingJNI.reportStatusCode(code.value, deviceIdentifier.toString());
128            }
129            else {
130                /* don't start reporting CouldNotRetrieveProFirmware yet, device was likely recently constructed */
131            }
132
133        }
134    }
135
136
137
138    /**
139     * Constructs a new Pigeon 2 sensor object.
140     * <p>
141     * Constructs the device using the default CAN bus for the system:
142     * <ul>
143     *   <li>"rio" on roboRIO
144     *   <li>"can0" on Linux
145     *   <li>"*" on Windows
146     * </ul>
147     *
148     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
149     *
150     * @deprecated Classes in the phoenixpro package will be removed in 2024.
151     *             Users should instead use classes from the phoenix6 package.
152     */
153    @Deprecated(forRemoval = true)
154    public CorePigeon2(int deviceId)
155    {
156        this(deviceId, "");
157    }
158    /**
159     * Constructs a new Pigeon 2 sensor object.
160     *
161     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
162     * @param canbus      Name of the CAN bus this device is on. Possible CAN bus strings are:
163     *                    <ul>
164     *                      <li>"rio" for the native roboRIO CAN bus
165     *                      <li>CANivore name or serial number
166     *                      <li>SocketCAN interface (non-FRC Linux only)
167     *                      <li>"*" for any CANivore seen by the program
168     *                      <li>empty string (default) to select the default for the system:
169     *                      <ul>
170     *                        <li>"rio" on roboRIO
171     *                        <li>"can0" on Linux
172     *                        <li>"*" on Windows
173     *                      </ul>
174     *                    </ul>
175     *
176     * @deprecated Classes in the phoenixpro package will be removed in 2024.
177     *             Users should instead use classes from the phoenix6 package.
178     */
179    @Deprecated(forRemoval = true)
180    public CorePigeon2(int deviceId, String canbus)
181    {
182        super(deviceId, "pigeon 2", canbus);
183        _configurator = new Pigeon2Configurator(this.deviceIdentifier);
184        _version = getVersion();
185        _resetFlags = lookupStatusSignalValue(
186                SpnValue.Startup_ResetFlags.value,
187                Integer.class,
188                "ResetFlags",
189                false);
190        PlatformJNI.JNI_SimCreate(DeviceType.PRO_Pigeon2Type.value, deviceId);
191    }
192
193
194    /**
195     * @return true if device has reset since the previous call of this routine.
196     */
197    public boolean hasResetOccurred() {
198        boolean retval = false;
199
200        /* did we receive an update */
201        _resetFlags.refresh(false);
202        final var timestamp = _resetFlags.getAllTimestamps().getSystemTimestamp();
203        if (timestamp.isValid()) {
204            /* if the update timestamp is new, then the startup frame was sent, indicating a reset occured */
205            if (_resetTimestamp != timestamp.getTime()) {
206                _resetTimestamp = timestamp.getTime();
207                retval = true;
208            }
209        }
210        return retval;
211    }
212
213    /**
214     * Gets the configurator to use with this device's configs
215     *
216     * @return Configurator for this object
217     */
218    public Pigeon2Configurator getConfigurator()
219    {
220        return this._configurator;
221    }
222
223
224    private Pigeon2SimState _simState = null;
225    /**
226     * Get the simulation state for this device.
227     * <p>
228     * This function reuses an allocated simulation state
229     * object, so it is safe to call this function multiple
230     * times in a robot loop.
231     *
232     * @return Simulation state
233     */
234    public Pigeon2SimState getSimState() {
235        if (_simState == null)
236            _simState = new Pigeon2SimState(this);
237        return _simState;
238    }
239
240
241    
242    /**
243     * App Major Version number.
244     *
245     *  <ul>
246     *  <li> <b>Minimum Value:</b> 0
247     *  <li> <b>Maximum Value:</b> 255
248     *  <li> <b>Default Value:</b> 0
249     *  <li> <b>Units:</b> 
250     *  </ul>
251     *
252     * Default Rates:
253     *  <ul>
254     *  <li> <b>CAN:</b> 4.0 Hz
255     *  </ul>
256     *
257     * @return  VersionMajor Status Signal Value object
258     */
259    public StatusSignalValue<Integer> getVersionMajor()
260    {
261        return super.lookupStatusSignalValue(SpnValue.Version_Major.value, Integer.class, "VersionMajor", false);
262    }
263    
264    /**
265     * App Minor Version number.
266     *
267     *  <ul>
268     *  <li> <b>Minimum Value:</b> 0
269     *  <li> <b>Maximum Value:</b> 255
270     *  <li> <b>Default Value:</b> 0
271     *  <li> <b>Units:</b> 
272     *  </ul>
273     *
274     * Default Rates:
275     *  <ul>
276     *  <li> <b>CAN:</b> 4.0 Hz
277     *  </ul>
278     *
279     * @return  VersionMinor Status Signal Value object
280     */
281    public StatusSignalValue<Integer> getVersionMinor()
282    {
283        return super.lookupStatusSignalValue(SpnValue.Version_Minor.value, Integer.class, "VersionMinor", false);
284    }
285    
286    /**
287     * App Bugfix Version number.
288     *
289     *  <ul>
290     *  <li> <b>Minimum Value:</b> 0
291     *  <li> <b>Maximum Value:</b> 255
292     *  <li> <b>Default Value:</b> 0
293     *  <li> <b>Units:</b> 
294     *  </ul>
295     *
296     * Default Rates:
297     *  <ul>
298     *  <li> <b>CAN:</b> 4.0 Hz
299     *  </ul>
300     *
301     * @return  VersionBugfix Status Signal Value object
302     */
303    public StatusSignalValue<Integer> getVersionBugfix()
304    {
305        return super.lookupStatusSignalValue(SpnValue.Version_Bugfix.value, Integer.class, "VersionBugfix", false);
306    }
307    
308    /**
309     * App Build Version number.
310     *
311     *  <ul>
312     *  <li> <b>Minimum Value:</b> 0
313     *  <li> <b>Maximum Value:</b> 255
314     *  <li> <b>Default Value:</b> 0
315     *  <li> <b>Units:</b> 
316     *  </ul>
317     *
318     * Default Rates:
319     *  <ul>
320     *  <li> <b>CAN:</b> 4.0 Hz
321     *  </ul>
322     *
323     * @return  VersionBuild Status Signal Value object
324     */
325    public StatusSignalValue<Integer> getVersionBuild()
326    {
327        return super.lookupStatusSignalValue(SpnValue.Version_Build.value, Integer.class, "VersionBuild", false);
328    }
329    
330    /**
331     * Full Version.  The format is a four byte value.
332     * <p>
333     * Full Version of firmware in device. The format is a four byte
334     * value.
335     *
336     *  <ul>
337     *  <li> <b>Minimum Value:</b> 0
338     *  <li> <b>Maximum Value:</b> 4294967295
339     *  <li> <b>Default Value:</b> 0
340     *  <li> <b>Units:</b> 
341     *  </ul>
342     *
343     * Default Rates:
344     *  <ul>
345     *  <li> <b>CAN:</b> 4.0 Hz
346     *  </ul>
347     *
348     * @return  Version Status Signal Value object
349     */
350    public StatusSignalValue<Integer> getVersion()
351    {
352        return super.lookupStatusSignalValue(SpnValue.Version_Full.value, Integer.class, "Version", false);
353    }
354    
355    /**
356     * Integer representing all faults
357     * <p>
358     * This returns the fault flags reported by the device. These are
359     * device specific and are not used directly in typical applications.
360     * Use the signal specific GetFault_*() methods instead.  
361     *
362     *  <ul>
363     *  <li> <b>Minimum Value:</b> 0
364     *  <li> <b>Maximum Value:</b> 1048575
365     *  <li> <b>Default Value:</b> 0
366     *  <li> <b>Units:</b> 
367     *  </ul>
368     *
369     * Default Rates:
370     *  <ul>
371     *  <li> <b>CAN:</b> 4.0 Hz
372     *  </ul>
373     *
374     * @return  FaultField Status Signal Value object
375     */
376    public StatusSignalValue<Integer> getFaultField()
377    {
378        return super.lookupStatusSignalValue(SpnValue.AllFaults.value, Integer.class, "FaultField", true);
379    }
380    
381    /**
382     * Integer representing all sticky faults
383     * <p>
384     * This returns the persistent "sticky" fault flags reported by the
385     * device. These are device specific and are not used directly in
386     * typical applications. Use the signal specific GetStickyFault_*()
387     * methods instead.  
388     *
389     *  <ul>
390     *  <li> <b>Minimum Value:</b> 0
391     *  <li> <b>Maximum Value:</b> 1048575
392     *  <li> <b>Default Value:</b> 0
393     *  <li> <b>Units:</b> 
394     *  </ul>
395     *
396     * Default Rates:
397     *  <ul>
398     *  <li> <b>CAN:</b> 4.0 Hz
399     *  </ul>
400     *
401     * @return  StickyFaultField Status Signal Value object
402     */
403    public StatusSignalValue<Integer> getStickyFaultField()
404    {
405        return super.lookupStatusSignalValue(SpnValue.AllStickyFaults.value, Integer.class, "StickyFaultField", true);
406    }
407    
408    /**
409     * Current reported yaw of the Pigeon2.
410     *
411     *  <ul>
412     *  <li> <b>Minimum Value:</b> -368640.0
413     *  <li> <b>Maximum Value:</b> 368639.99725341797
414     *  <li> <b>Default Value:</b> 0
415     *  <li> <b>Units:</b> deg
416     *  </ul>
417     *
418     * Default Rates:
419     *  <ul>
420     *  <li> <b>CAN:</b> 100.0 Hz
421     *  </ul>
422     *
423     * @return  Yaw Status Signal Value object
424     */
425    public StatusSignalValue<Double> getYaw()
426    {
427        return super.lookupStatusSignalValue(SpnValue.Pigeon2Yaw.value, Double.class, "Yaw", true);
428    }
429    
430    /**
431     * Current reported pitch of the Pigeon2.
432     *
433     *  <ul>
434     *  <li> <b>Minimum Value:</b> -90.0
435     *  <li> <b>Maximum Value:</b> 89.9560546875
436     *  <li> <b>Default Value:</b> 0
437     *  <li> <b>Units:</b> deg
438     *  </ul>
439     *
440     * Default Rates:
441     *  <ul>
442     *  <li> <b>CAN:</b> 100.0 Hz
443     *  </ul>
444     *
445     * @return  Pitch Status Signal Value object
446     */
447    public StatusSignalValue<Double> getPitch()
448    {
449        return super.lookupStatusSignalValue(SpnValue.Pigeon2Pitch.value, Double.class, "Pitch", true);
450    }
451    
452    /**
453     * Current reported roll of the Pigeon2.
454     *
455     *  <ul>
456     *  <li> <b>Minimum Value:</b> -180.0
457     *  <li> <b>Maximum Value:</b> 179.9560546875
458     *  <li> <b>Default Value:</b> 0
459     *  <li> <b>Units:</b> deg
460     *  </ul>
461     *
462     * Default Rates:
463     *  <ul>
464     *  <li> <b>CAN:</b> 100.0 Hz
465     *  </ul>
466     *
467     * @return  Roll Status Signal Value object
468     */
469    public StatusSignalValue<Double> getRoll()
470    {
471        return super.lookupStatusSignalValue(SpnValue.Pigeon2Roll.value, Double.class, "Roll", true);
472    }
473    
474    /**
475     * The W component of the reported Quaternion.
476     *
477     *  <ul>
478     *  <li> <b>Minimum Value:</b> -1.0001220852154804
479     *  <li> <b>Maximum Value:</b> 1.0
480     *  <li> <b>Default Value:</b> 0
481     *  <li> <b>Units:</b> 
482     *  </ul>
483     *
484     * Default Rates:
485     *  <ul>
486     *  <li> <b>CAN 2.0:</b> 50.0 Hz
487     *  <li> <b>CAN FD:</b> 100.0 Hz
488     *  </ul>
489     *
490     * @return  QuatW Status Signal Value object
491     */
492    public StatusSignalValue<Double> getQuatW()
493    {
494        return super.lookupStatusSignalValue(SpnValue.Pigeon2QuatW.value, Double.class, "QuatW", true);
495    }
496    
497    /**
498     * The X component of the reported Quaternion.
499     *
500     *  <ul>
501     *  <li> <b>Minimum Value:</b> -1.0001220852154804
502     *  <li> <b>Maximum Value:</b> 1.0
503     *  <li> <b>Default Value:</b> 0
504     *  <li> <b>Units:</b> 
505     *  </ul>
506     *
507     * Default Rates:
508     *  <ul>
509     *  <li> <b>CAN 2.0:</b> 50.0 Hz
510     *  <li> <b>CAN FD:</b> 100.0 Hz
511     *  </ul>
512     *
513     * @return  QuatX Status Signal Value object
514     */
515    public StatusSignalValue<Double> getQuatX()
516    {
517        return super.lookupStatusSignalValue(SpnValue.Pigeon2QuatX.value, Double.class, "QuatX", true);
518    }
519    
520    /**
521     * The Y component of the reported Quaternion.
522     *
523     *  <ul>
524     *  <li> <b>Minimum Value:</b> -1.0001220852154804
525     *  <li> <b>Maximum Value:</b> 1.0
526     *  <li> <b>Default Value:</b> 0
527     *  <li> <b>Units:</b> 
528     *  </ul>
529     *
530     * Default Rates:
531     *  <ul>
532     *  <li> <b>CAN 2.0:</b> 50.0 Hz
533     *  <li> <b>CAN FD:</b> 100.0 Hz
534     *  </ul>
535     *
536     * @return  QuatY Status Signal Value object
537     */
538    public StatusSignalValue<Double> getQuatY()
539    {
540        return super.lookupStatusSignalValue(SpnValue.Pigeon2QuatY.value, Double.class, "QuatY", true);
541    }
542    
543    /**
544     * The Z component of the reported Quaternion.
545     *
546     *  <ul>
547     *  <li> <b>Minimum Value:</b> -1.0001220852154804
548     *  <li> <b>Maximum Value:</b> 1.0
549     *  <li> <b>Default Value:</b> 0
550     *  <li> <b>Units:</b> 
551     *  </ul>
552     *
553     * Default Rates:
554     *  <ul>
555     *  <li> <b>CAN 2.0:</b> 50.0 Hz
556     *  <li> <b>CAN FD:</b> 100.0 Hz
557     *  </ul>
558     *
559     * @return  QuatZ Status Signal Value object
560     */
561    public StatusSignalValue<Double> getQuatZ()
562    {
563        return super.lookupStatusSignalValue(SpnValue.Pigeon2QuatZ.value, Double.class, "QuatZ", true);
564    }
565    
566    /**
567     * The X component of the gravity vector.
568     * <p>
569     * This is the X component of the reported gravity-vector. The gravity
570     * vector is not the acceleration experienced by the Pigeon2, rather
571     * it is where the Pigeon2 believes "Down" is. This can be used for
572     * mechanisms that are linearly related to gravity, such as an arm
573     * pivoting about a point, as the contribution of gravity to the arm
574     * is directly proportional to the contribution of gravity about one
575     * of these primary axis.
576     *
577     *  <ul>
578     *  <li> <b>Minimum Value:</b> -1.000030518509476
579     *  <li> <b>Maximum Value:</b> 1.0
580     *  <li> <b>Default Value:</b> 0
581     *  <li> <b>Units:</b> 
582     *  </ul>
583     *
584     * Default Rates:
585     *  <ul>
586     *  <li> <b>CAN 2.0:</b> 10.0 Hz
587     *  <li> <b>CAN FD:</b> 100.0 Hz
588     *  </ul>
589     *
590     * @return  GravityVectorX Status Signal Value object
591     */
592    public StatusSignalValue<Double> getGravityVectorX()
593    {
594        return super.lookupStatusSignalValue(SpnValue.Pigeon2GravityVectorX.value, Double.class, "GravityVectorX", true);
595    }
596    
597    /**
598     * The Y component of the gravity vector.
599     * <p>
600     * This is the X component of the reported gravity-vector. The gravity
601     * vector is not the acceleration experienced by the Pigeon2, rather
602     * it is where the Pigeon2 believes "Down" is. This can be used for
603     * mechanisms that are linearly related to gravity, such as an arm
604     * pivoting about a point, as the contribution of gravity to the arm
605     * is directly proportional to the contribution of gravity about one
606     * of these primary axis.
607     *
608     *  <ul>
609     *  <li> <b>Minimum Value:</b> -1.000030518509476
610     *  <li> <b>Maximum Value:</b> 1.0
611     *  <li> <b>Default Value:</b> 0
612     *  <li> <b>Units:</b> 
613     *  </ul>
614     *
615     * Default Rates:
616     *  <ul>
617     *  <li> <b>CAN 2.0:</b> 10.0 Hz
618     *  <li> <b>CAN FD:</b> 100.0 Hz
619     *  </ul>
620     *
621     * @return  GravityVectorY Status Signal Value object
622     */
623    public StatusSignalValue<Double> getGravityVectorY()
624    {
625        return super.lookupStatusSignalValue(SpnValue.Pigeon2GravityVectorY.value, Double.class, "GravityVectorY", true);
626    }
627    
628    /**
629     * The Z component of the gravity vector.
630     * <p>
631     * This is the Z component of the reported gravity-vector. The gravity
632     * vector is not the acceleration experienced by the Pigeon2, rather
633     * it is where the Pigeon2 believes "Down" is. This can be used for
634     * mechanisms that are linearly related to gravity, such as an arm
635     * pivoting about a point, as the contribution of gravity to the arm
636     * is directly proportional to the contribution of gravity about one
637     * of these primary axis.
638     *
639     *  <ul>
640     *  <li> <b>Minimum Value:</b> -1.000030518509476
641     *  <li> <b>Maximum Value:</b> 1.0
642     *  <li> <b>Default Value:</b> 0
643     *  <li> <b>Units:</b> 
644     *  </ul>
645     *
646     * Default Rates:
647     *  <ul>
648     *  <li> <b>CAN 2.0:</b> 10.0 Hz
649     *  <li> <b>CAN FD:</b> 100.0 Hz
650     *  </ul>
651     *
652     * @return  GravityVectorZ Status Signal Value object
653     */
654    public StatusSignalValue<Double> getGravityVectorZ()
655    {
656        return super.lookupStatusSignalValue(SpnValue.Pigeon2GravityVectorZ.value, Double.class, "GravityVectorZ", true);
657    }
658    
659    /**
660     * Temperature of the Pigeon 2.
661     *
662     *  <ul>
663     *  <li> <b>Minimum Value:</b> -128.0
664     *  <li> <b>Maximum Value:</b> 127.99609375
665     *  <li> <b>Default Value:</b> 0
666     *  <li> <b>Units:</b> ℃
667     *  </ul>
668     *
669     * Default Rates:
670     *  <ul>
671     *  <li> <b>CAN 2.0:</b> 10.0 Hz
672     *  <li> <b>CAN FD:</b> 100.0 Hz
673     *  </ul>
674     *
675     * @return  Temperature Status Signal Value object
676     */
677    public StatusSignalValue<Double> getTemperature()
678    {
679        return super.lookupStatusSignalValue(SpnValue.Pigeon2Temperature.value, Double.class, "Temperature", true);
680    }
681    
682    /**
683     * Whether the no-motion calibration feature is enabled.
684     *
685     *  <ul>
686     *  <li> <b>Default Value:</b> 0
687     *  </ul>
688     *
689     * Default Rates:
690     *  <ul>
691     *  <li> <b>CAN 2.0:</b> 10.0 Hz
692     *  <li> <b>CAN FD:</b> 100.0 Hz
693     *  </ul>
694     *
695     * @return  NoMotionEnabled Status Signal Value object
696     */
697    public StatusSignalValue<Boolean> getNoMotionEnabled()
698    {
699        return super.lookupStatusSignalValue(SpnValue.Pigeon2NoMotionCalEnabled.value, Boolean.class, "NoMotionEnabled", true);
700    }
701    
702    /**
703     * The number of times a no-motion event occurred, wraps at 15.
704     *
705     *  <ul>
706     *  <li> <b>Minimum Value:</b> 0
707     *  <li> <b>Maximum Value:</b> 15
708     *  <li> <b>Default Value:</b> 0
709     *  <li> <b>Units:</b> 
710     *  </ul>
711     *
712     * Default Rates:
713     *  <ul>
714     *  <li> <b>CAN 2.0:</b> 10.0 Hz
715     *  <li> <b>CAN FD:</b> 100.0 Hz
716     *  </ul>
717     *
718     * @return  NoMotionCount Status Signal Value object
719     */
720    public StatusSignalValue<Double> getNoMotionCount()
721    {
722        return super.lookupStatusSignalValue(SpnValue.Pigeon2NoMotionCount.value, Double.class, "NoMotionCount", true);
723    }
724    
725    /**
726     * Whether the temperature-compensation feature is disabled.
727     *
728     *  <ul>
729     *  <li> <b>Default Value:</b> 0
730     *  </ul>
731     *
732     * Default Rates:
733     *  <ul>
734     *  <li> <b>CAN 2.0:</b> 10.0 Hz
735     *  <li> <b>CAN FD:</b> 100.0 Hz
736     *  </ul>
737     *
738     * @return  TemperatureCompensationDisabled Status Signal Value object
739     */
740    public StatusSignalValue<Boolean> getTemperatureCompensationDisabled()
741    {
742        return super.lookupStatusSignalValue(SpnValue.Pigeon2TempCompDisabled.value, Boolean.class, "TemperatureCompensationDisabled", true);
743    }
744    
745    /**
746     * How long the Pigeon 2's been up in seconds, caps at 255 seconds.
747     *
748     *  <ul>
749     *  <li> <b>Minimum Value:</b> 0
750     *  <li> <b>Maximum Value:</b> 255
751     *  <li> <b>Default Value:</b> 0
752     *  <li> <b>Units:</b> s
753     *  </ul>
754     *
755     * Default Rates:
756     *  <ul>
757     *  <li> <b>CAN 2.0:</b> 10.0 Hz
758     *  <li> <b>CAN FD:</b> 100.0 Hz
759     *  </ul>
760     *
761     * @return  UpTime Status Signal Value object
762     */
763    public StatusSignalValue<Double> getUpTime()
764    {
765        return super.lookupStatusSignalValue(SpnValue.Pigeon2UpTime.value, Double.class, "UpTime", true);
766    }
767    
768    /**
769     * The accumulated gyro about the X axis without any sensor fusing.
770     *
771     *  <ul>
772     *  <li> <b>Minimum Value:</b> -23040.0
773     *  <li> <b>Maximum Value:</b> 23039.9560546875
774     *  <li> <b>Default Value:</b> 0
775     *  <li> <b>Units:</b> deg
776     *  </ul>
777     *
778     * Default Rates:
779     *  <ul>
780     *  <li> <b>CAN 2.0:</b> 10.0 Hz
781     *  <li> <b>CAN FD:</b> 100.0 Hz
782     *  </ul>
783     *
784     * @return  AccumGyroX Status Signal Value object
785     */
786    public StatusSignalValue<Double> getAccumGyroX()
787    {
788        return super.lookupStatusSignalValue(SpnValue.Pigeon2AccumGyroX.value, Double.class, "AccumGyroX", true);
789    }
790    
791    /**
792     * The accumulated gyro about the Y axis without any sensor fusing.
793     *
794     *  <ul>
795     *  <li> <b>Minimum Value:</b> -23040.0
796     *  <li> <b>Maximum Value:</b> 23039.9560546875
797     *  <li> <b>Default Value:</b> 0
798     *  <li> <b>Units:</b> deg
799     *  </ul>
800     *
801     * Default Rates:
802     *  <ul>
803     *  <li> <b>CAN 2.0:</b> 10.0 Hz
804     *  <li> <b>CAN FD:</b> 100.0 Hz
805     *  </ul>
806     *
807     * @return  AccumGyroY Status Signal Value object
808     */
809    public StatusSignalValue<Double> getAccumGyroY()
810    {
811        return super.lookupStatusSignalValue(SpnValue.Pigeon2AccumGyroY.value, Double.class, "AccumGyroY", true);
812    }
813    
814    /**
815     * The accumulated gyro about the Z axis without any sensor fusing.
816     *
817     *  <ul>
818     *  <li> <b>Minimum Value:</b> -23040.0
819     *  <li> <b>Maximum Value:</b> 23039.9560546875
820     *  <li> <b>Default Value:</b> 0
821     *  <li> <b>Units:</b> deg
822     *  </ul>
823     *
824     * Default Rates:
825     *  <ul>
826     *  <li> <b>CAN 2.0:</b> 10.0 Hz
827     *  <li> <b>CAN FD:</b> 100.0 Hz
828     *  </ul>
829     *
830     * @return  AccumGyroZ Status Signal Value object
831     */
832    public StatusSignalValue<Double> getAccumGyroZ()
833    {
834        return super.lookupStatusSignalValue(SpnValue.Pigeon2AccumGyroZ.value, Double.class, "AccumGyroZ", true);
835    }
836    
837    /**
838     * The angular velocity (ω) of the Pigeon 2 about the X axis.
839     *
840     *  <ul>
841     *  <li> <b>Minimum Value:</b> -1998.048780487805
842     *  <li> <b>Maximum Value:</b> 1997.987804878049
843     *  <li> <b>Default Value:</b> 0
844     *  <li> <b>Units:</b> dps
845     *  </ul>
846     *
847     * Default Rates:
848     *  <ul>
849     *  <li> <b>CAN 2.0:</b> 10.0 Hz
850     *  <li> <b>CAN FD:</b> 100.0 Hz
851     *  </ul>
852     *
853     * @return  AngularVelocityX Status Signal Value object
854     */
855    public StatusSignalValue<Double> getAngularVelocityX()
856    {
857        return super.lookupStatusSignalValue(SpnValue.Pigeon2AngularVelocityX.value, Double.class, "AngularVelocityX", true);
858    }
859    
860    /**
861     * The angular velocity (ω) of the Pigeon 2 about the Y axis.
862     *
863     *  <ul>
864     *  <li> <b>Minimum Value:</b> -1998.048780487805
865     *  <li> <b>Maximum Value:</b> 1997.987804878049
866     *  <li> <b>Default Value:</b> 0
867     *  <li> <b>Units:</b> dps
868     *  </ul>
869     *
870     * Default Rates:
871     *  <ul>
872     *  <li> <b>CAN 2.0:</b> 10.0 Hz
873     *  <li> <b>CAN FD:</b> 100.0 Hz
874     *  </ul>
875     *
876     * @return  AngularVelocityY Status Signal Value object
877     */
878    public StatusSignalValue<Double> getAngularVelocityY()
879    {
880        return super.lookupStatusSignalValue(SpnValue.Pigeon2AngularVelocityY.value, Double.class, "AngularVelocityY", true);
881    }
882    
883    /**
884     * The angular velocity (ω) of the Pigeon 2 about the Z axis.
885     *
886     *  <ul>
887     *  <li> <b>Minimum Value:</b> -1998.048780487805
888     *  <li> <b>Maximum Value:</b> 1997.987804878049
889     *  <li> <b>Default Value:</b> 0
890     *  <li> <b>Units:</b> dps
891     *  </ul>
892     *
893     * Default Rates:
894     *  <ul>
895     *  <li> <b>CAN 2.0:</b> 10.0 Hz
896     *  <li> <b>CAN FD:</b> 100.0 Hz
897     *  </ul>
898     *
899     * @return  AngularVelocityZ Status Signal Value object
900     */
901    public StatusSignalValue<Double> getAngularVelocityZ()
902    {
903        return super.lookupStatusSignalValue(SpnValue.Pigeon2AngularVelocityZ.value, Double.class, "AngularVelocityZ", true);
904    }
905    
906    /**
907     * The acceleration measured by Pigeon2 in the X direction.
908     * <p>
909     * This value includes the acceleration due to gravity. If this is
910     * undesirable, get the gravity vector and subtract out the
911     * contribution in this direction.
912     *
913     *  <ul>
914     *  <li> <b>Minimum Value:</b> -2.0
915     *  <li> <b>Maximum Value:</b> 1.99993896484375
916     *  <li> <b>Default Value:</b> 0
917     *  <li> <b>Units:</b> g
918     *  </ul>
919     *
920     * Default Rates:
921     *  <ul>
922     *  <li> <b>CAN 2.0:</b> 10.0 Hz
923     *  <li> <b>CAN FD:</b> 100.0 Hz
924     *  </ul>
925     *
926     * @return  AccelerationX Status Signal Value object
927     */
928    public StatusSignalValue<Double> getAccelerationX()
929    {
930        return super.lookupStatusSignalValue(SpnValue.Pigeon2AccelerationX.value, Double.class, "AccelerationX", true);
931    }
932    
933    /**
934     * The acceleration measured by Pigeon2 in the Y direction.
935     * <p>
936     * This value includes the acceleration due to gravity. If this is
937     * undesirable, get the gravity vector and subtract out the
938     * contribution in this direction.
939     *
940     *  <ul>
941     *  <li> <b>Minimum Value:</b> -2.0
942     *  <li> <b>Maximum Value:</b> 1.99993896484375
943     *  <li> <b>Default Value:</b> 0
944     *  <li> <b>Units:</b> g
945     *  </ul>
946     *
947     * Default Rates:
948     *  <ul>
949     *  <li> <b>CAN 2.0:</b> 10.0 Hz
950     *  <li> <b>CAN FD:</b> 100.0 Hz
951     *  </ul>
952     *
953     * @return  AccelerationY Status Signal Value object
954     */
955    public StatusSignalValue<Double> getAccelerationY()
956    {
957        return super.lookupStatusSignalValue(SpnValue.Pigeon2AccelerationY.value, Double.class, "AccelerationY", true);
958    }
959    
960    /**
961     * The acceleration measured by Pigeon2 in the Z direction.
962     * <p>
963     * This value includes the acceleration due to gravity. If this is
964     * undesirable, get the gravity vector and subtract out the
965     * contribution in this direction.
966     *
967     *  <ul>
968     *  <li> <b>Minimum Value:</b> -2.0
969     *  <li> <b>Maximum Value:</b> 1.99993896484375
970     *  <li> <b>Default Value:</b> 0
971     *  <li> <b>Units:</b> g
972     *  </ul>
973     *
974     * Default Rates:
975     *  <ul>
976     *  <li> <b>CAN 2.0:</b> 10.0 Hz
977     *  <li> <b>CAN FD:</b> 100.0 Hz
978     *  </ul>
979     *
980     * @return  AccelerationZ Status Signal Value object
981     */
982    public StatusSignalValue<Double> getAccelerationZ()
983    {
984        return super.lookupStatusSignalValue(SpnValue.Pigeon2AccelerationZ.value, Double.class, "AccelerationZ", true);
985    }
986    
987    /**
988     * Measured supply voltage to the Pigeon2.
989     *
990     *  <ul>
991     *  <li> <b>Minimum Value:</b> 0.0
992     *  <li> <b>Maximum Value:</b> 31.99951171875
993     *  <li> <b>Default Value:</b> 0
994     *  <li> <b>Units:</b> V
995     *  </ul>
996     *
997     * Default Rates:
998     *  <ul>
999     *  <li> <b>CAN:</b> 10.0 Hz
1000     *  </ul>
1001     *
1002     * @return  SupplyVoltage Status Signal Value object
1003     */
1004    public StatusSignalValue<Double> getSupplyVoltage()
1005    {
1006        return super.lookupStatusSignalValue(SpnValue.Pigeon2_SupplyVoltage.value, Double.class, "SupplyVoltage", true);
1007    }
1008    
1009    /**
1010     * The biased magnitude of the magnetic field measured by the Pigeon 2
1011     * in the X direction. This is only valid after performing a
1012     * magnetometer calibration.
1013     *
1014     *  <ul>
1015     *  <li> <b>Minimum Value:</b> -19660.8
1016     *  <li> <b>Maximum Value:</b> 19660.2
1017     *  <li> <b>Default Value:</b> 0
1018     *  <li> <b>Units:</b> uT
1019     *  </ul>
1020     *
1021     * Default Rates:
1022     *  <ul>
1023     *  <li> <b>CAN:</b> 5.0 Hz
1024     *  </ul>
1025     *
1026     * @return  MagneticFieldX Status Signal Value object
1027     */
1028    public StatusSignalValue<Double> getMagneticFieldX()
1029    {
1030        return super.lookupStatusSignalValue(SpnValue.Pigeon2MagneticFieldX.value, Double.class, "MagneticFieldX", true);
1031    }
1032    
1033    /**
1034     * The biased magnitude of the magnetic field measured by the Pigeon 2
1035     * in the Y direction. This is only valid after performing a
1036     * magnetometer calibration.
1037     *
1038     *  <ul>
1039     *  <li> <b>Minimum Value:</b> -19660.8
1040     *  <li> <b>Maximum Value:</b> 19660.2
1041     *  <li> <b>Default Value:</b> 0
1042     *  <li> <b>Units:</b> uT
1043     *  </ul>
1044     *
1045     * Default Rates:
1046     *  <ul>
1047     *  <li> <b>CAN:</b> 5.0 Hz
1048     *  </ul>
1049     *
1050     * @return  MagneticFieldY Status Signal Value object
1051     */
1052    public StatusSignalValue<Double> getMagneticFieldY()
1053    {
1054        return super.lookupStatusSignalValue(SpnValue.Pigeon2MagneticFieldY.value, Double.class, "MagneticFieldY", true);
1055    }
1056    
1057    /**
1058     * The biased magnitude of the magnetic field measured by the Pigeon 2
1059     * in the Z direction. This is only valid after performing a
1060     * magnetometer calibration.
1061     *
1062     *  <ul>
1063     *  <li> <b>Minimum Value:</b> -19660.8
1064     *  <li> <b>Maximum Value:</b> 19660.2
1065     *  <li> <b>Default Value:</b> 0
1066     *  <li> <b>Units:</b> uT
1067     *  </ul>
1068     *
1069     * Default Rates:
1070     *  <ul>
1071     *  <li> <b>CAN:</b> 5.0 Hz
1072     *  </ul>
1073     *
1074     * @return  MagneticFieldZ Status Signal Value object
1075     */
1076    public StatusSignalValue<Double> getMagneticFieldZ()
1077    {
1078        return super.lookupStatusSignalValue(SpnValue.Pigeon2MagneticFieldZ.value, Double.class, "MagneticFieldZ", true);
1079    }
1080    
1081    /**
1082     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
1083     * the X direction. This is only valid after performing a magnetometer
1084     * calibration.
1085     *
1086     *  <ul>
1087     *  <li> <b>Minimum Value:</b> -19660.8
1088     *  <li> <b>Maximum Value:</b> 19660.2
1089     *  <li> <b>Default Value:</b> 0
1090     *  <li> <b>Units:</b> uT
1091     *  </ul>
1092     *
1093     * Default Rates:
1094     *  <ul>
1095     *  <li> <b>CAN:</b> 5.0 Hz
1096     *  </ul>
1097     *
1098     * @return  RawMagneticFieldX Status Signal Value object
1099     */
1100    public StatusSignalValue<Double> getRawMagneticFieldX()
1101    {
1102        return super.lookupStatusSignalValue(SpnValue.Pigeon2RawMagneticFieldX.value, Double.class, "RawMagneticFieldX", true);
1103    }
1104    
1105    /**
1106     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
1107     * the Y direction. This is only valid after performing a magnetometer
1108     * calibration.
1109     *
1110     *  <ul>
1111     *  <li> <b>Minimum Value:</b> -19660.8
1112     *  <li> <b>Maximum Value:</b> 19660.2
1113     *  <li> <b>Default Value:</b> 0
1114     *  <li> <b>Units:</b> uT
1115     *  </ul>
1116     *
1117     * Default Rates:
1118     *  <ul>
1119     *  <li> <b>CAN:</b> 5.0 Hz
1120     *  </ul>
1121     *
1122     * @return  RawMagneticFieldY Status Signal Value object
1123     */
1124    public StatusSignalValue<Double> getRawMagneticFieldY()
1125    {
1126        return super.lookupStatusSignalValue(SpnValue.Pigeon2RawMagneticFieldY.value, Double.class, "RawMagneticFieldY", true);
1127    }
1128    
1129    /**
1130     * The raw magnitude of the magnetic field measured by the Pigeon 2 in
1131     * the Z direction. This is only valid after performing a magnetometer
1132     * calibration.
1133     *
1134     *  <ul>
1135     *  <li> <b>Minimum Value:</b> -19660.8
1136     *  <li> <b>Maximum Value:</b> 19660.2
1137     *  <li> <b>Default Value:</b> 0
1138     *  <li> <b>Units:</b> uT
1139     *  </ul>
1140     *
1141     * Default Rates:
1142     *  <ul>
1143     *  <li> <b>CAN:</b> 5.0 Hz
1144     *  </ul>
1145     *
1146     * @return  RawMagneticFieldZ Status Signal Value object
1147     */
1148    public StatusSignalValue<Double> getRawMagneticFieldZ()
1149    {
1150        return super.lookupStatusSignalValue(SpnValue.Pigeon2RawMagneticFieldZ.value, Double.class, "RawMagneticFieldZ", true);
1151    }
1152    
1153    /**
1154     * Hardware fault occurred
1155     *
1156     *  <ul>
1157     *  <li> <b>Default Value:</b> False
1158     *  </ul>
1159     *
1160     * Default Rates:
1161     *  <ul>
1162     *  <li> <b>CAN:</b> 4.0 Hz
1163     *  </ul>
1164     *
1165     * @return  Fault_Hardware Status Signal Value object
1166     */
1167    public StatusSignalValue<Boolean> getFault_Hardware()
1168    {
1169        return super.lookupStatusSignalValue(SpnValue.Fault_Hardware.value, Boolean.class, "Fault_Hardware", true);
1170    }
1171    
1172    /**
1173     * Hardware fault occurred
1174     *
1175     *  <ul>
1176     *  <li> <b>Default Value:</b> False
1177     *  </ul>
1178     *
1179     * Default Rates:
1180     *  <ul>
1181     *  <li> <b>CAN:</b> 4.0 Hz
1182     *  </ul>
1183     *
1184     * @return  StickyFault_Hardware Status Signal Value object
1185     */
1186    public StatusSignalValue<Boolean> getStickyFault_Hardware()
1187    {
1188        return super.lookupStatusSignalValue(SpnValue.StickyFault_Hardware.value, Boolean.class, "StickyFault_Hardware", true);
1189    }
1190    
1191    /**
1192     * Device supply voltage dropped to near brownout levels
1193     *
1194     *  <ul>
1195     *  <li> <b>Default Value:</b> False
1196     *  </ul>
1197     *
1198     * Default Rates:
1199     *  <ul>
1200     *  <li> <b>CAN:</b> 4.0 Hz
1201     *  </ul>
1202     *
1203     * @return  Fault_Undervoltage Status Signal Value object
1204     */
1205    public StatusSignalValue<Boolean> getFault_Undervoltage()
1206    {
1207        return super.lookupStatusSignalValue(SpnValue.Fault_Undervoltage.value, Boolean.class, "Fault_Undervoltage", true);
1208    }
1209    
1210    /**
1211     * Device supply voltage dropped to near brownout levels
1212     *
1213     *  <ul>
1214     *  <li> <b>Default Value:</b> False
1215     *  </ul>
1216     *
1217     * Default Rates:
1218     *  <ul>
1219     *  <li> <b>CAN:</b> 4.0 Hz
1220     *  </ul>
1221     *
1222     * @return  StickyFault_Undervoltage Status Signal Value object
1223     */
1224    public StatusSignalValue<Boolean> getStickyFault_Undervoltage()
1225    {
1226        return super.lookupStatusSignalValue(SpnValue.StickyFault_Undervoltage.value, Boolean.class, "StickyFault_Undervoltage", true);
1227    }
1228    
1229    /**
1230     * Device boot while detecting the enable signal
1231     *
1232     *  <ul>
1233     *  <li> <b>Default Value:</b> False
1234     *  </ul>
1235     *
1236     * Default Rates:
1237     *  <ul>
1238     *  <li> <b>CAN:</b> 4.0 Hz
1239     *  </ul>
1240     *
1241     * @return  Fault_BootDuringEnable Status Signal Value object
1242     */
1243    public StatusSignalValue<Boolean> getFault_BootDuringEnable()
1244    {
1245        return super.lookupStatusSignalValue(SpnValue.Fault_BootDuringEnable.value, Boolean.class, "Fault_BootDuringEnable", true);
1246    }
1247    
1248    /**
1249     * Device boot while detecting the enable signal
1250     *
1251     *  <ul>
1252     *  <li> <b>Default Value:</b> False
1253     *  </ul>
1254     *
1255     * Default Rates:
1256     *  <ul>
1257     *  <li> <b>CAN:</b> 4.0 Hz
1258     *  </ul>
1259     *
1260     * @return  StickyFault_BootDuringEnable Status Signal Value object
1261     */
1262    public StatusSignalValue<Boolean> getStickyFault_BootDuringEnable()
1263    {
1264        return super.lookupStatusSignalValue(SpnValue.StickyFault_BootDuringEnable.value, Boolean.class, "StickyFault_BootDuringEnable", true);
1265    }
1266    
1267    /**
1268     * An unlicensed feature is in use, device may not behave as expected.
1269     *
1270     *  <ul>
1271     *  <li> <b>Default Value:</b> False
1272     *  </ul>
1273     *
1274     * Default Rates:
1275     *  <ul>
1276     *  <li> <b>CAN:</b> 4.0 Hz
1277     *  </ul>
1278     *
1279     * @return  Fault_UnlicensedFeatureInUse Status Signal Value object
1280     */
1281    public StatusSignalValue<Boolean> getFault_UnlicensedFeatureInUse()
1282    {
1283        return super.lookupStatusSignalValue(SpnValue.Fault_UnlicensedFeatureInUse.value, Boolean.class, "Fault_UnlicensedFeatureInUse", true);
1284    }
1285    
1286    /**
1287     * An unlicensed feature is in use, device may not behave as expected.
1288     *
1289     *  <ul>
1290     *  <li> <b>Default Value:</b> False
1291     *  </ul>
1292     *
1293     * Default Rates:
1294     *  <ul>
1295     *  <li> <b>CAN:</b> 4.0 Hz
1296     *  </ul>
1297     *
1298     * @return  StickyFault_UnlicensedFeatureInUse Status Signal Value object
1299     */
1300    public StatusSignalValue<Boolean> getStickyFault_UnlicensedFeatureInUse()
1301    {
1302        return super.lookupStatusSignalValue(SpnValue.StickyFault_UnlicensedFeatureInUse.value, Boolean.class, "StickyFault_UnlicensedFeatureInUse", true);
1303    }
1304    
1305    /**
1306     * Bootup checks failed: Accelerometer
1307     *
1308     *  <ul>
1309     *  <li> <b>Default Value:</b> False
1310     *  </ul>
1311     *
1312     * Default Rates:
1313     *  <ul>
1314     *  <li> <b>CAN:</b> 4.0 Hz
1315     *  </ul>
1316     *
1317     * @return  Fault_BootupAccelerometer Status Signal Value object
1318     */
1319    public StatusSignalValue<Boolean> getFault_BootupAccelerometer()
1320    {
1321        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_BootupAccel.value, Boolean.class, "Fault_BootupAccelerometer", true);
1322    }
1323    
1324    /**
1325     * Bootup checks failed: Accelerometer
1326     *
1327     *  <ul>
1328     *  <li> <b>Default Value:</b> False
1329     *  </ul>
1330     *
1331     * Default Rates:
1332     *  <ul>
1333     *  <li> <b>CAN:</b> 4.0 Hz
1334     *  </ul>
1335     *
1336     * @return  StickyFault_BootupAccelerometer Status Signal Value object
1337     */
1338    public StatusSignalValue<Boolean> getStickyFault_BootupAccelerometer()
1339    {
1340        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_BootupAccel.value, Boolean.class, "StickyFault_BootupAccelerometer", true);
1341    }
1342    
1343    /**
1344     * Bootup checks failed: Gyroscope
1345     *
1346     *  <ul>
1347     *  <li> <b>Default Value:</b> False
1348     *  </ul>
1349     *
1350     * Default Rates:
1351     *  <ul>
1352     *  <li> <b>CAN:</b> 4.0 Hz
1353     *  </ul>
1354     *
1355     * @return  Fault_BootupGyroscope Status Signal Value object
1356     */
1357    public StatusSignalValue<Boolean> getFault_BootupGyroscope()
1358    {
1359        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_BootupGyros.value, Boolean.class, "Fault_BootupGyroscope", true);
1360    }
1361    
1362    /**
1363     * Bootup checks failed: Gyroscope
1364     *
1365     *  <ul>
1366     *  <li> <b>Default Value:</b> False
1367     *  </ul>
1368     *
1369     * Default Rates:
1370     *  <ul>
1371     *  <li> <b>CAN:</b> 4.0 Hz
1372     *  </ul>
1373     *
1374     * @return  StickyFault_BootupGyroscope Status Signal Value object
1375     */
1376    public StatusSignalValue<Boolean> getStickyFault_BootupGyroscope()
1377    {
1378        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_BootupGyros.value, Boolean.class, "StickyFault_BootupGyroscope", true);
1379    }
1380    
1381    /**
1382     * Bootup checks failed: Magnetometer
1383     *
1384     *  <ul>
1385     *  <li> <b>Default Value:</b> False
1386     *  </ul>
1387     *
1388     * Default Rates:
1389     *  <ul>
1390     *  <li> <b>CAN:</b> 4.0 Hz
1391     *  </ul>
1392     *
1393     * @return  Fault_BootupMagnetometer Status Signal Value object
1394     */
1395    public StatusSignalValue<Boolean> getFault_BootupMagnetometer()
1396    {
1397        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_BootupMagne.value, Boolean.class, "Fault_BootupMagnetometer", true);
1398    }
1399    
1400    /**
1401     * Bootup checks failed: Magnetometer
1402     *
1403     *  <ul>
1404     *  <li> <b>Default Value:</b> False
1405     *  </ul>
1406     *
1407     * Default Rates:
1408     *  <ul>
1409     *  <li> <b>CAN:</b> 4.0 Hz
1410     *  </ul>
1411     *
1412     * @return  StickyFault_BootupMagnetometer Status Signal Value object
1413     */
1414    public StatusSignalValue<Boolean> getStickyFault_BootupMagnetometer()
1415    {
1416        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_BootupMagne.value, Boolean.class, "StickyFault_BootupMagnetometer", true);
1417    }
1418    
1419    /**
1420     * Motion Detected during bootup.
1421     *
1422     *  <ul>
1423     *  <li> <b>Default Value:</b> False
1424     *  </ul>
1425     *
1426     * Default Rates:
1427     *  <ul>
1428     *  <li> <b>CAN:</b> 4.0 Hz
1429     *  </ul>
1430     *
1431     * @return  Fault_BootIntoMotion Status Signal Value object
1432     */
1433    public StatusSignalValue<Boolean> getFault_BootIntoMotion()
1434    {
1435        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_BootIntoMotion.value, Boolean.class, "Fault_BootIntoMotion", true);
1436    }
1437    
1438    /**
1439     * Motion Detected during bootup.
1440     *
1441     *  <ul>
1442     *  <li> <b>Default Value:</b> False
1443     *  </ul>
1444     *
1445     * Default Rates:
1446     *  <ul>
1447     *  <li> <b>CAN:</b> 4.0 Hz
1448     *  </ul>
1449     *
1450     * @return  StickyFault_BootIntoMotion Status Signal Value object
1451     */
1452    public StatusSignalValue<Boolean> getStickyFault_BootIntoMotion()
1453    {
1454        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_BootIntoMotion.value, Boolean.class, "StickyFault_BootIntoMotion", true);
1455    }
1456    
1457    /**
1458     * Motion stack data acquisition was slower than expected
1459     *
1460     *  <ul>
1461     *  <li> <b>Default Value:</b> False
1462     *  </ul>
1463     *
1464     * Default Rates:
1465     *  <ul>
1466     *  <li> <b>CAN:</b> 4.0 Hz
1467     *  </ul>
1468     *
1469     * @return  Fault_DataAcquiredLate Status Signal Value object
1470     */
1471    public StatusSignalValue<Boolean> getFault_DataAcquiredLate()
1472    {
1473        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_DataAcquiredLate.value, Boolean.class, "Fault_DataAcquiredLate", true);
1474    }
1475    
1476    /**
1477     * Motion stack data acquisition was slower than expected
1478     *
1479     *  <ul>
1480     *  <li> <b>Default Value:</b> False
1481     *  </ul>
1482     *
1483     * Default Rates:
1484     *  <ul>
1485     *  <li> <b>CAN:</b> 4.0 Hz
1486     *  </ul>
1487     *
1488     * @return  StickyFault_DataAcquiredLate Status Signal Value object
1489     */
1490    public StatusSignalValue<Boolean> getStickyFault_DataAcquiredLate()
1491    {
1492        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_DataAcquiredLate.value, Boolean.class, "StickyFault_DataAcquiredLate", true);
1493    }
1494    
1495    /**
1496     * Motion stack loop time was slower than expected.
1497     *
1498     *  <ul>
1499     *  <li> <b>Default Value:</b> False
1500     *  </ul>
1501     *
1502     * Default Rates:
1503     *  <ul>
1504     *  <li> <b>CAN:</b> 4.0 Hz
1505     *  </ul>
1506     *
1507     * @return  Fault_LoopTimeSlow Status Signal Value object
1508     */
1509    public StatusSignalValue<Boolean> getFault_LoopTimeSlow()
1510    {
1511        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_LoopTimeSlow.value, Boolean.class, "Fault_LoopTimeSlow", true);
1512    }
1513    
1514    /**
1515     * Motion stack loop time was slower than expected.
1516     *
1517     *  <ul>
1518     *  <li> <b>Default Value:</b> False
1519     *  </ul>
1520     *
1521     * Default Rates:
1522     *  <ul>
1523     *  <li> <b>CAN:</b> 4.0 Hz
1524     *  </ul>
1525     *
1526     * @return  StickyFault_LoopTimeSlow Status Signal Value object
1527     */
1528    public StatusSignalValue<Boolean> getStickyFault_LoopTimeSlow()
1529    {
1530        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_LoopTimeSlow.value, Boolean.class, "StickyFault_LoopTimeSlow", true);
1531    }
1532    
1533    /**
1534     * Magnetometer values are saturated
1535     *
1536     *  <ul>
1537     *  <li> <b>Default Value:</b> False
1538     *  </ul>
1539     *
1540     * Default Rates:
1541     *  <ul>
1542     *  <li> <b>CAN:</b> 4.0 Hz
1543     *  </ul>
1544     *
1545     * @return  Fault_SaturatedMagneter Status Signal Value object
1546     */
1547    public StatusSignalValue<Boolean> getFault_SaturatedMagneter()
1548    {
1549        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_SaturatedMagne.value, Boolean.class, "Fault_SaturatedMagneter", true);
1550    }
1551    
1552    /**
1553     * Magnetometer values are saturated
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     * @return  StickyFault_SaturatedMagneter Status Signal Value object
1565     */
1566    public StatusSignalValue<Boolean> getStickyFault_SaturatedMagneter()
1567    {
1568        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_SaturatedMagne.value, Boolean.class, "StickyFault_SaturatedMagneter", true);
1569    }
1570    
1571    /**
1572     * Accelerometer values are saturated
1573     *
1574     *  <ul>
1575     *  <li> <b>Default Value:</b> False
1576     *  </ul>
1577     *
1578     * Default Rates:
1579     *  <ul>
1580     *  <li> <b>CAN:</b> 4.0 Hz
1581     *  </ul>
1582     *
1583     * @return  Fault_SaturatedAccelometer Status Signal Value object
1584     */
1585    public StatusSignalValue<Boolean> getFault_SaturatedAccelometer()
1586    {
1587        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_SaturatedAccel.value, Boolean.class, "Fault_SaturatedAccelometer", true);
1588    }
1589    
1590    /**
1591     * Accelerometer values are saturated
1592     *
1593     *  <ul>
1594     *  <li> <b>Default Value:</b> False
1595     *  </ul>
1596     *
1597     * Default Rates:
1598     *  <ul>
1599     *  <li> <b>CAN:</b> 4.0 Hz
1600     *  </ul>
1601     *
1602     * @return  StickyFault_SaturatedAccelometer Status Signal Value object
1603     */
1604    public StatusSignalValue<Boolean> getStickyFault_SaturatedAccelometer()
1605    {
1606        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_SaturatedAccel.value, Boolean.class, "StickyFault_SaturatedAccelometer", true);
1607    }
1608    
1609    /**
1610     * Gyroscope values are saturated
1611     *
1612     *  <ul>
1613     *  <li> <b>Default Value:</b> False
1614     *  </ul>
1615     *
1616     * Default Rates:
1617     *  <ul>
1618     *  <li> <b>CAN:</b> 4.0 Hz
1619     *  </ul>
1620     *
1621     * @return  Fault_SaturatedGyrosscope Status Signal Value object
1622     */
1623    public StatusSignalValue<Boolean> getFault_SaturatedGyrosscope()
1624    {
1625        return super.lookupStatusSignalValue(SpnValue.Fault_PIGEON2_SaturatedGyros.value, Boolean.class, "Fault_SaturatedGyrosscope", true);
1626    }
1627    
1628    /**
1629     * Gyroscope values are saturated
1630     *
1631     *  <ul>
1632     *  <li> <b>Default Value:</b> False
1633     *  </ul>
1634     *
1635     * Default Rates:
1636     *  <ul>
1637     *  <li> <b>CAN:</b> 4.0 Hz
1638     *  </ul>
1639     *
1640     * @return  StickyFault_SaturatedGyrosscope Status Signal Value object
1641     */
1642    public StatusSignalValue<Boolean> getStickyFault_SaturatedGyrosscope()
1643    {
1644        return super.lookupStatusSignalValue(SpnValue.StickyFault_PIGEON2_SaturatedGyros.value, Boolean.class, "StickyFault_SaturatedGyrosscope", true);
1645    }
1646
1647
1648
1649    /**
1650     * Control motor with generic control request object.
1651     * <p>
1652     * User must make sure the specified object is castable to a valid control request,
1653     * otherwise this function will fail at run-time and return the NotSupported StatusCode
1654     *
1655     * @param request                Control object to request of the device
1656     * @return Status Code of the request, 0 is OK
1657     */
1658    public StatusCode setControl(ControlRequest request)
1659    {
1660        
1661        return StatusCode.NotSupported;
1662    }
1663
1664    
1665    /**
1666     * The yaw to set the Pigeon2 to right now.
1667     *
1668     * @param newValue Value to set to.
1669     * @param timeoutSeconds Maximum time to wait up to in seconds.
1670     * @return StatusCode of the set command
1671     */
1672    public StatusCode setYaw(double newValue, double timeoutSeconds) {
1673        return getConfigurator().setYaw(newValue, timeoutSeconds);
1674    }
1675    /**
1676     * The yaw to set the Pigeon2 to right now.
1677     * <p>
1678     * This will wait up to 0.050 seconds (50ms) by default.
1679     *
1680     * @param newValue Value to set to.
1681     * @return StatusCode of the set command
1682     */
1683    public StatusCode setYaw(double newValue) {
1684        return setYaw(newValue, 0.050);
1685    }
1686    
1687    /**
1688     * Clear the sticky faults in the device.
1689     * <p>
1690     * This typically has no impact on the device functionality.  Instead,
1691     * it just clears telemetry faults that are accessible via API and
1692     * Tuner Self-Test.
1693     * @param timeoutSeconds Maximum time to wait up to in seconds.
1694     * @return StatusCode of the set command
1695     */
1696    public StatusCode clearStickyFaults(double timeoutSeconds) {
1697        return getConfigurator().clearStickyFaults(timeoutSeconds);
1698    }
1699    /**
1700     * Clear the sticky faults in the device.
1701     * <p>
1702     * This typically has no impact on the device functionality.  Instead,
1703     * it just clears telemetry faults that are accessible via API and
1704     * Tuner Self-Test.
1705     * <p>
1706     * This will wait up to 0.050 seconds (50ms) by default.
1707     * @return StatusCode of the set command
1708     */
1709    public StatusCode clearStickyFaults() {
1710        return clearStickyFaults(0.050);
1711    }
1712}
1713