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