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