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.CANcoderSimState;
017import com.ctre.phoenixpro.StatusSignalValue;
018import com.ctre.phoenix6.spns.*;
019import com.ctre.phoenixpro.signals.*;
020import com.ctre.phoenixpro.Utils;
021
022/**
023 * Class for CANcoder, a CAN based magnetic encoder that provides absolute and
024 * relative position along with filtered velocity.
025 *
026 * @deprecated Classes in the phoenixpro package will be removed in 2024.
027 *             Users should instead use classes from the phoenix6 package.
028 */
029@Deprecated(forRemoval = true)
030public class CoreCANcoder extends ParentDevice
031{
032    private CANcoderConfigurator _configurator;
033
034    private StatusSignalValue<Integer> _version;
035    private boolean _isVersionOk = false;
036    private double _timeToRefreshVersion = Utils.getCurrentTimeSeconds();
037
038    private StatusSignalValue<Integer> _resetFlags;
039    private double _resetTimestamp = 0;
040
041    private double _creationTime = Utils.getCurrentTimeSeconds();
042
043    @Override
044    protected void reportIfTooOld()
045    {
046        /* If we're not initialized, we can't even check the versions */
047        if (_isVersionOk) {
048            return;
049        }
050        /* Check if we have our versions initialized */
051        if (_version == null) {
052            return;
053        }
054
055        /* get fresh data if enough time has passed */
056        final double currentTime = Utils.getCurrentTimeSeconds();
057        if (currentTime >= _timeToRefreshVersion) {
058            /* Try to refresh again after 250ms */
059            _timeToRefreshVersion = currentTime + 0.25;
060            /* Refresh versions, don't print out if there's an error with refreshing */
061            _version.refresh(false);
062            
063            /* process the fetched version */
064            StatusCode code = StatusCode.OK;
065    
066            /* First check if we have good versions or not */
067            if (_version.getError().isOK()) {
068                final long fullVersion = _version.getValue();
069    
070                if (Utils.isSimulation()) {
071                    /* only check major version in simulation */
072                    final int majorVersion = (int)((fullVersion >> 0x18) & 0xFF);
073    
074                    /* Just check if it's good */
075                    if (majorVersion != 23) {
076                        code = StatusCode.FirmwareTooOld;
077                    }
078                    else {
079                        /* Equal major versions, this is sufficient */
080                    }
081                }
082                else {
083                    /* test the parts individually */
084                    final int majorVersion = (int)((fullVersion >> 0x18) & 0xFF);
085                    final int minorVersion = (int)((fullVersion >> 0x10) & 0xFF);
086                    final int bugfixVersion = (int)((fullVersion >> 0x08) & 0xFF);
087                    final int buildVersion = (int)((fullVersion >> 0x00) & 0xFF);
088    
089                    /* Just check if they're good */
090                    if (majorVersion < 23) {
091                        code = StatusCode.FirmwareTooOld;
092                    }
093                    else if (majorVersion > 23) {
094                    }
095                    else if (minorVersion < 1) {
096                        code = StatusCode.FirmwareTooOld;
097                    }
098                    else if (minorVersion > 1) {
099                    }
100                    else if (bugfixVersion < 0) {
101                        code = StatusCode.FirmwareTooOld;
102                    }
103                    else if (bugfixVersion > 0) {
104                    }
105                    else if (buildVersion < 0) {
106                        code = StatusCode.FirmwareTooOld;
107                    }
108                    else if (buildVersion > 0) {
109                    }
110                    else {
111                        /* Equal versions, this is sufficient */
112                    }
113                }
114            }
115            else {
116                /* don't care why we couldn't get message, just report we didn't get it */
117                code = StatusCode.CouldNotRetrieveProFirmware;
118            }
119    
120            /* how much time has passed */
121            final double deltaTimeSec = currentTime - _creationTime;
122    
123            if (code.isOK()) {
124                /* version is retrieved and healthy */
125                _isVersionOk = true;
126            }
127            else if (code == StatusCode.FirmwareTooOld || deltaTimeSec >= 3.0) {
128                /* report error */
129                ErrorReportingJNI.reportStatusCode(code.value, deviceIdentifier.toString());
130            }
131            else {
132                /* don't start reporting CouldNotRetrieveProFirmware yet, device was likely recently constructed */
133            }
134
135        }
136    }
137
138
139
140    /**
141     * Constructs a new CANcoder object.
142     * <p>
143     * Constructs the device using the default CAN bus for the system:
144     * <ul>
145     *   <li>"rio" on roboRIO
146     *   <li>"can0" on Linux
147     *   <li>"*" on Windows
148     * </ul>
149     *
150     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
151     *
152     * @deprecated Classes in the phoenixpro package will be removed in 2024.
153     *             Users should instead use classes from the phoenix6 package.
154     */
155    @Deprecated(forRemoval = true)
156    public CoreCANcoder(int deviceId)
157    {
158        this(deviceId, "");
159    }
160    /**
161     * Constructs a new CANcoder object.
162     *
163     * @param deviceId    ID of the device, as configured in Phoenix Tuner.
164     * @param canbus      Name of the CAN bus this device is on. Possible CAN bus strings are:
165     *                    <ul>
166     *                      <li>"rio" for the native roboRIO CAN bus
167     *                      <li>CANivore name or serial number
168     *                      <li>SocketCAN interface (non-FRC Linux only)
169     *                      <li>"*" for any CANivore seen by the program
170     *                      <li>empty string (default) to select the default for the system:
171     *                      <ul>
172     *                        <li>"rio" on roboRIO
173     *                        <li>"can0" on Linux
174     *                        <li>"*" on Windows
175     *                      </ul>
176     *                    </ul>
177     *
178     * @deprecated Classes in the phoenixpro package will be removed in 2024.
179     *             Users should instead use classes from the phoenix6 package.
180     */
181    @Deprecated(forRemoval = true)
182    public CoreCANcoder(int deviceId, String canbus)
183    {
184        super(deviceId, "cancoder", canbus);
185        _configurator = new CANcoderConfigurator(this.deviceIdentifier);
186        _version = getVersion();
187        _resetFlags = lookupStatusSignalValue(
188                SpnValue.Startup_ResetFlags.value,
189                Integer.class,
190                "ResetFlags",
191                false);
192        PlatformJNI.JNI_SimCreate(DeviceType.PRO_CANcoderType.value, deviceId);
193    }
194
195
196    /**
197     * @return true if device has reset since the previous call of this routine.
198     */
199    public boolean hasResetOccurred() {
200        boolean retval = false;
201
202        /* did we receive an update */
203        _resetFlags.refresh(false);
204        final var timestamp = _resetFlags.getAllTimestamps().getSystemTimestamp();
205        if (timestamp.isValid()) {
206            /* if the update timestamp is new, then the startup frame was sent, indicating a reset occured */
207            if (_resetTimestamp != timestamp.getTime()) {
208                _resetTimestamp = timestamp.getTime();
209                retval = true;
210            }
211        }
212        return retval;
213    }
214
215    /**
216     * Gets the configurator to use with this device's configs
217     *
218     * @return Configurator for this object
219     */
220    public CANcoderConfigurator getConfigurator()
221    {
222        return this._configurator;
223    }
224
225
226    private CANcoderSimState _simState = null;
227    /**
228     * Get the simulation state for this device.
229     * <p>
230     * This function reuses an allocated simulation state
231     * object, so it is safe to call this function multiple
232     * times in a robot loop.
233     *
234     * @return Simulation state
235     */
236    public CANcoderSimState getSimState() {
237        if (_simState == null)
238            _simState = new CANcoderSimState(this);
239        return _simState;
240    }
241
242
243    
244    /**
245     * App Major Version number.
246     *
247     *  <ul>
248     *  <li> <b>Minimum Value:</b> 0
249     *  <li> <b>Maximum Value:</b> 255
250     *  <li> <b>Default Value:</b> 0
251     *  <li> <b>Units:</b> 
252     *  </ul>
253     *
254     * Default Rates:
255     *  <ul>
256     *  <li> <b>CAN:</b> 4.0 Hz
257     *  </ul>
258     *
259     * @return  VersionMajor Status Signal Value object
260     */
261    public StatusSignalValue<Integer> getVersionMajor()
262    {
263        return super.lookupStatusSignalValue(SpnValue.Version_Major.value, Integer.class, "VersionMajor", false);
264    }
265    
266    /**
267     * App Minor Version number.
268     *
269     *  <ul>
270     *  <li> <b>Minimum Value:</b> 0
271     *  <li> <b>Maximum Value:</b> 255
272     *  <li> <b>Default Value:</b> 0
273     *  <li> <b>Units:</b> 
274     *  </ul>
275     *
276     * Default Rates:
277     *  <ul>
278     *  <li> <b>CAN:</b> 4.0 Hz
279     *  </ul>
280     *
281     * @return  VersionMinor Status Signal Value object
282     */
283    public StatusSignalValue<Integer> getVersionMinor()
284    {
285        return super.lookupStatusSignalValue(SpnValue.Version_Minor.value, Integer.class, "VersionMinor", false);
286    }
287    
288    /**
289     * App Bugfix Version number.
290     *
291     *  <ul>
292     *  <li> <b>Minimum Value:</b> 0
293     *  <li> <b>Maximum Value:</b> 255
294     *  <li> <b>Default Value:</b> 0
295     *  <li> <b>Units:</b> 
296     *  </ul>
297     *
298     * Default Rates:
299     *  <ul>
300     *  <li> <b>CAN:</b> 4.0 Hz
301     *  </ul>
302     *
303     * @return  VersionBugfix Status Signal Value object
304     */
305    public StatusSignalValue<Integer> getVersionBugfix()
306    {
307        return super.lookupStatusSignalValue(SpnValue.Version_Bugfix.value, Integer.class, "VersionBugfix", false);
308    }
309    
310    /**
311     * App Build Version number.
312     *
313     *  <ul>
314     *  <li> <b>Minimum Value:</b> 0
315     *  <li> <b>Maximum Value:</b> 255
316     *  <li> <b>Default Value:</b> 0
317     *  <li> <b>Units:</b> 
318     *  </ul>
319     *
320     * Default Rates:
321     *  <ul>
322     *  <li> <b>CAN:</b> 4.0 Hz
323     *  </ul>
324     *
325     * @return  VersionBuild Status Signal Value object
326     */
327    public StatusSignalValue<Integer> getVersionBuild()
328    {
329        return super.lookupStatusSignalValue(SpnValue.Version_Build.value, Integer.class, "VersionBuild", false);
330    }
331    
332    /**
333     * Full Version.  The format is a four byte value.
334     * <p>
335     * Full Version of firmware in device. The format is a four byte
336     * value.
337     *
338     *  <ul>
339     *  <li> <b>Minimum Value:</b> 0
340     *  <li> <b>Maximum Value:</b> 4294967295
341     *  <li> <b>Default Value:</b> 0
342     *  <li> <b>Units:</b> 
343     *  </ul>
344     *
345     * Default Rates:
346     *  <ul>
347     *  <li> <b>CAN:</b> 4.0 Hz
348     *  </ul>
349     *
350     * @return  Version Status Signal Value object
351     */
352    public StatusSignalValue<Integer> getVersion()
353    {
354        return super.lookupStatusSignalValue(SpnValue.Version_Full.value, Integer.class, "Version", false);
355    }
356    
357    /**
358     * Integer representing all faults
359     * <p>
360     * This returns the fault flags reported by the device. These are
361     * device specific and are not used directly in typical applications.
362     * Use the signal specific GetFault_*() methods instead.  
363     *
364     *  <ul>
365     *  <li> <b>Minimum Value:</b> 0
366     *  <li> <b>Maximum Value:</b> 1048575
367     *  <li> <b>Default Value:</b> 0
368     *  <li> <b>Units:</b> 
369     *  </ul>
370     *
371     * Default Rates:
372     *  <ul>
373     *  <li> <b>CAN:</b> 4.0 Hz
374     *  </ul>
375     *
376     * @return  FaultField Status Signal Value object
377     */
378    public StatusSignalValue<Integer> getFaultField()
379    {
380        return super.lookupStatusSignalValue(SpnValue.AllFaults.value, Integer.class, "FaultField", true);
381    }
382    
383    /**
384     * Integer representing all sticky faults
385     * <p>
386     * This returns the persistent "sticky" fault flags reported by the
387     * device. These are device specific and are not used directly in
388     * typical applications. Use the signal specific GetStickyFault_*()
389     * methods instead.  
390     *
391     *  <ul>
392     *  <li> <b>Minimum Value:</b> 0
393     *  <li> <b>Maximum Value:</b> 1048575
394     *  <li> <b>Default Value:</b> 0
395     *  <li> <b>Units:</b> 
396     *  </ul>
397     *
398     * Default Rates:
399     *  <ul>
400     *  <li> <b>CAN:</b> 4.0 Hz
401     *  </ul>
402     *
403     * @return  StickyFaultField Status Signal Value object
404     */
405    public StatusSignalValue<Integer> getStickyFaultField()
406    {
407        return super.lookupStatusSignalValue(SpnValue.AllStickyFaults.value, Integer.class, "StickyFaultField", true);
408    }
409    
410    /**
411     * Velocity of device.
412     *
413     *  <ul>
414     *  <li> <b>Minimum Value:</b> -512.0
415     *  <li> <b>Maximum Value:</b> 511.998046875
416     *  <li> <b>Default Value:</b> 0
417     *  <li> <b>Units:</b> rotations per second
418     *  </ul>
419     *
420     * Default Rates:
421     *  <ul>
422     *  <li> <b>CAN:</b> 100.0 Hz
423     *  </ul>
424     *
425     * @return  Velocity Status Signal Value object
426     */
427    public StatusSignalValue<Double> getVelocity()
428    {
429        return super.lookupStatusSignalValue(SpnValue.CANcoder_Velocity.value, Double.class, "Velocity", true);
430    }
431    
432    /**
433     * Position of device.
434     *
435     *  <ul>
436     *  <li> <b>Minimum Value:</b> -16384.0
437     *  <li> <b>Maximum Value:</b> 16383.999755859375
438     *  <li> <b>Default Value:</b> 0
439     *  <li> <b>Units:</b> rotations
440     *  </ul>
441     *
442     * Default Rates:
443     *  <ul>
444     *  <li> <b>CAN:</b> 100.0 Hz
445     *  </ul>
446     *
447     * @return  Position Status Signal Value object
448     */
449    public StatusSignalValue<Double> getPosition()
450    {
451        return super.lookupStatusSignalValue(SpnValue.CANcoder_Position.value, Double.class, "Position", true);
452    }
453    
454    /**
455     * Absolute Position of device.  The possible range is documented
456     * below, however the exact expected range is determined by the
457     * AbsoluteSensorRange.
458     *
459     *  <ul>
460     *  <li> <b>Minimum Value:</b> -0.5
461     *  <li> <b>Maximum Value:</b> 0.999755859375
462     *  <li> <b>Default Value:</b> 0
463     *  <li> <b>Units:</b> rotations
464     *  </ul>
465     *
466     * Default Rates:
467     *  <ul>
468     *  <li> <b>CAN:</b> 100.0 Hz
469     *  </ul>
470     *
471     * @return  AbsolutePosition Status Signal Value object
472     */
473    public StatusSignalValue<Double> getAbsolutePosition()
474    {
475        return super.lookupStatusSignalValue(SpnValue.CANcoder_AbsPosition.value, Double.class, "AbsolutePosition", true);
476    }
477    
478    /**
479     * The unfiltered velocity reported by CANcoder.
480     * <p>
481     * This is the unfiltered velocity reported by CANcoder. This signal
482     * does not use the fusing algorithm. It is also not timesynced. If
483     * you wish to use a signal with timesync, use Velocity.
484     *
485     *  <ul>
486     *  <li> <b>Minimum Value:</b> -8000.0
487     *  <li> <b>Maximum Value:</b> 7999.755859375
488     *  <li> <b>Default Value:</b> 0
489     *  <li> <b>Units:</b> rotations per second
490     *  </ul>
491     *
492     * Default Rates:
493     *  <ul>
494     *  <li> <b>CAN 2.0:</b> 10.0 Hz
495     *  <li> <b>CAN FD:</b> 100.0 Hz
496     *  </ul>
497     *
498     * @return  UnfilteredVelocity Status Signal Value object
499     */
500    public StatusSignalValue<Double> getUnfilteredVelocity()
501    {
502        return super.lookupStatusSignalValue(SpnValue.CANCoder_RawVel.value, Double.class, "UnfilteredVelocity", true);
503    }
504    
505    /**
506     * The relative position reported by the CANcoder since boot.
507     * <p>
508     * This is the total displacement reported by CANcoder since power up.
509     * This signal is relative and is not influenced by the fusing
510     * algorithm. It is also not timesynced. If you wish to use a signal
511     * with timesync, use Position.
512     *
513     *  <ul>
514     *  <li> <b>Minimum Value:</b> -16384.0
515     *  <li> <b>Maximum Value:</b> 16383.999755859375
516     *  <li> <b>Default Value:</b> 0
517     *  <li> <b>Units:</b> rotations
518     *  </ul>
519     *
520     * Default Rates:
521     *  <ul>
522     *  <li> <b>CAN 2.0:</b> 10.0 Hz
523     *  <li> <b>CAN FD:</b> 100.0 Hz
524     *  </ul>
525     *
526     * @return  PositionSinceBoot Status Signal Value object
527     */
528    public StatusSignalValue<Double> getPositionSinceBoot()
529    {
530        return super.lookupStatusSignalValue(SpnValue.CANCoder_RawPos.value, Double.class, "PositionSinceBoot", true);
531    }
532    
533    /**
534     * Measured supply voltage to the CANcoder.
535     *
536     *  <ul>
537     *  <li> <b>Minimum Value:</b> 4
538     *  <li> <b>Maximum Value:</b> 16.75
539     *  <li> <b>Default Value:</b> 4
540     *  <li> <b>Units:</b> V
541     *  </ul>
542     *
543     * Default Rates:
544     *  <ul>
545     *  <li> <b>CAN 2.0:</b> 10.0 Hz
546     *  <li> <b>CAN FD:</b> 100.0 Hz
547     *  </ul>
548     *
549     * @return  SupplyVoltage Status Signal Value object
550     */
551    public StatusSignalValue<Double> getSupplyVoltage()
552    {
553        return super.lookupStatusSignalValue(SpnValue.CANCoder_SupplyVoltage.value, Double.class, "SupplyVoltage", true);
554    }
555    
556    /**
557     * Magnet health as measured by CANcoder.
558     * <p>
559     * Magnet health as measured by CANcoder. Red indicates too close or
560     * too far, Orange is adequate but with reduced accuracy, green is
561     * ideal. Invalid means the accuracy cannot be determined.
562     *
563     *
564     * Default Rates:
565     *  <ul>
566     *  <li> <b>CAN 2.0:</b> 10.0 Hz
567     *  <li> <b>CAN FD:</b> 100.0 Hz
568     *  </ul>
569     *
570     * @return  MagnetHealth Status Signal Value object
571     */
572    public StatusSignalValue<MagnetHealthValue> getMagnetHealth()
573    {
574        return super.lookupStatusSignalValue(SpnValue.CANcoder_MagHealth.value, MagnetHealthValue.class, "MagnetHealth", true);
575    }
576    
577    /**
578     * Hardware fault occurred
579     *
580     *  <ul>
581     *  <li> <b>Default Value:</b> False
582     *  </ul>
583     *
584     * Default Rates:
585     *  <ul>
586     *  <li> <b>CAN:</b> 4.0 Hz
587     *  </ul>
588     *
589     * @return  Fault_Hardware Status Signal Value object
590     */
591    public StatusSignalValue<Boolean> getFault_Hardware()
592    {
593        return super.lookupStatusSignalValue(SpnValue.Fault_Hardware.value, Boolean.class, "Fault_Hardware", true);
594    }
595    
596    /**
597     * Hardware fault occurred
598     *
599     *  <ul>
600     *  <li> <b>Default Value:</b> False
601     *  </ul>
602     *
603     * Default Rates:
604     *  <ul>
605     *  <li> <b>CAN:</b> 4.0 Hz
606     *  </ul>
607     *
608     * @return  StickyFault_Hardware Status Signal Value object
609     */
610    public StatusSignalValue<Boolean> getStickyFault_Hardware()
611    {
612        return super.lookupStatusSignalValue(SpnValue.StickyFault_Hardware.value, Boolean.class, "StickyFault_Hardware", true);
613    }
614    
615    /**
616     * Device supply voltage dropped to near brownout levels
617     *
618     *  <ul>
619     *  <li> <b>Default Value:</b> False
620     *  </ul>
621     *
622     * Default Rates:
623     *  <ul>
624     *  <li> <b>CAN:</b> 4.0 Hz
625     *  </ul>
626     *
627     * @return  Fault_Undervoltage Status Signal Value object
628     */
629    public StatusSignalValue<Boolean> getFault_Undervoltage()
630    {
631        return super.lookupStatusSignalValue(SpnValue.Fault_Undervoltage.value, Boolean.class, "Fault_Undervoltage", true);
632    }
633    
634    /**
635     * Device supply voltage dropped to near brownout levels
636     *
637     *  <ul>
638     *  <li> <b>Default Value:</b> False
639     *  </ul>
640     *
641     * Default Rates:
642     *  <ul>
643     *  <li> <b>CAN:</b> 4.0 Hz
644     *  </ul>
645     *
646     * @return  StickyFault_Undervoltage Status Signal Value object
647     */
648    public StatusSignalValue<Boolean> getStickyFault_Undervoltage()
649    {
650        return super.lookupStatusSignalValue(SpnValue.StickyFault_Undervoltage.value, Boolean.class, "StickyFault_Undervoltage", true);
651    }
652    
653    /**
654     * Device boot while detecting the enable signal
655     *
656     *  <ul>
657     *  <li> <b>Default Value:</b> False
658     *  </ul>
659     *
660     * Default Rates:
661     *  <ul>
662     *  <li> <b>CAN:</b> 4.0 Hz
663     *  </ul>
664     *
665     * @return  Fault_BootDuringEnable Status Signal Value object
666     */
667    public StatusSignalValue<Boolean> getFault_BootDuringEnable()
668    {
669        return super.lookupStatusSignalValue(SpnValue.Fault_BootDuringEnable.value, Boolean.class, "Fault_BootDuringEnable", true);
670    }
671    
672    /**
673     * Device boot while detecting the enable signal
674     *
675     *  <ul>
676     *  <li> <b>Default Value:</b> False
677     *  </ul>
678     *
679     * Default Rates:
680     *  <ul>
681     *  <li> <b>CAN:</b> 4.0 Hz
682     *  </ul>
683     *
684     * @return  StickyFault_BootDuringEnable Status Signal Value object
685     */
686    public StatusSignalValue<Boolean> getStickyFault_BootDuringEnable()
687    {
688        return super.lookupStatusSignalValue(SpnValue.StickyFault_BootDuringEnable.value, Boolean.class, "StickyFault_BootDuringEnable", true);
689    }
690    
691    /**
692     * An unlicensed feature is in use, device may not behave as expected.
693     *
694     *  <ul>
695     *  <li> <b>Default Value:</b> False
696     *  </ul>
697     *
698     * Default Rates:
699     *  <ul>
700     *  <li> <b>CAN:</b> 4.0 Hz
701     *  </ul>
702     *
703     * @return  Fault_UnlicensedFeatureInUse Status Signal Value object
704     */
705    public StatusSignalValue<Boolean> getFault_UnlicensedFeatureInUse()
706    {
707        return super.lookupStatusSignalValue(SpnValue.Fault_UnlicensedFeatureInUse.value, Boolean.class, "Fault_UnlicensedFeatureInUse", true);
708    }
709    
710    /**
711     * An unlicensed feature is in use, device may not behave as expected.
712     *
713     *  <ul>
714     *  <li> <b>Default Value:</b> False
715     *  </ul>
716     *
717     * Default Rates:
718     *  <ul>
719     *  <li> <b>CAN:</b> 4.0 Hz
720     *  </ul>
721     *
722     * @return  StickyFault_UnlicensedFeatureInUse Status Signal Value object
723     */
724    public StatusSignalValue<Boolean> getStickyFault_UnlicensedFeatureInUse()
725    {
726        return super.lookupStatusSignalValue(SpnValue.StickyFault_UnlicensedFeatureInUse.value, Boolean.class, "StickyFault_UnlicensedFeatureInUse", true);
727    }
728    
729    /**
730     * The magnet distance is not correct or magnet is missing
731     *
732     *  <ul>
733     *  <li> <b>Default Value:</b> False
734     *  </ul>
735     *
736     * Default Rates:
737     *  <ul>
738     *  <li> <b>CAN:</b> 4.0 Hz
739     *  </ul>
740     *
741     * @return  Fault_BadMagnet Status Signal Value object
742     */
743    public StatusSignalValue<Boolean> getFault_BadMagnet()
744    {
745        return super.lookupStatusSignalValue(SpnValue.Fault_CANCODER_BadMagnet.value, Boolean.class, "Fault_BadMagnet", true);
746    }
747    
748    /**
749     * The magnet distance is not correct or magnet is missing
750     *
751     *  <ul>
752     *  <li> <b>Default Value:</b> False
753     *  </ul>
754     *
755     * Default Rates:
756     *  <ul>
757     *  <li> <b>CAN:</b> 4.0 Hz
758     *  </ul>
759     *
760     * @return  StickyFault_BadMagnet Status Signal Value object
761     */
762    public StatusSignalValue<Boolean> getStickyFault_BadMagnet()
763    {
764        return super.lookupStatusSignalValue(SpnValue.StickyFault_CANCODER_BadMagnet.value, Boolean.class, "StickyFault_BadMagnet", true);
765    }
766
767
768
769    /**
770     * Control motor with generic control request object.
771     * <p>
772     * User must make sure the specified object is castable to a valid control request,
773     * otherwise this function will fail at run-time and return the NotSupported StatusCode
774     *
775     * @param request                Control object to request of the device
776     * @return Status Code of the request, 0 is OK
777     */
778    public StatusCode setControl(ControlRequest request)
779    {
780        
781        return StatusCode.NotSupported;
782    }
783
784    
785    /**
786     * The position to set the sensor position to right now.
787     *
788     * @param newValue Value to set to.
789     * @param timeoutSeconds Maximum time to wait up to in seconds.
790     * @return StatusCode of the set command
791     */
792    public StatusCode setPosition(double newValue, double timeoutSeconds) {
793        return getConfigurator().setPosition(newValue, timeoutSeconds);
794    }
795    /**
796     * The position to set the sensor position to right now.
797     * <p>
798     * This will wait up to 0.050 seconds (50ms) by default.
799     *
800     * @param newValue Value to set to.
801     * @return StatusCode of the set command
802     */
803    public StatusCode setPosition(double newValue) {
804        return setPosition(newValue, 0.050);
805    }
806    
807    /**
808     * Clear the sticky faults in the device.
809     * <p>
810     * This typically has no impact on the device functionality.  Instead,
811     * it just clears telemetry faults that are accessible via API and
812     * Tuner Self-Test.
813     * @param timeoutSeconds Maximum time to wait up to in seconds.
814     * @return StatusCode of the set command
815     */
816    public StatusCode clearStickyFaults(double timeoutSeconds) {
817        return getConfigurator().clearStickyFaults(timeoutSeconds);
818    }
819    /**
820     * Clear the sticky faults in the device.
821     * <p>
822     * This typically has no impact on the device functionality.  Instead,
823     * it just clears telemetry faults that are accessible via API and
824     * Tuner Self-Test.
825     * <p>
826     * This will wait up to 0.050 seconds (50ms) by default.
827     * @return StatusCode of the set command
828     */
829    public StatusCode clearStickyFaults() {
830        return clearStickyFaults(0.050);
831    }
832}
833