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