001/* Copyright (C) Cross The Road Electronics 2024 */
002package com.ctre.phoenix.motorcontrol.can;
003
004import com.ctre.phoenix.ErrorCode;
005import com.ctre.phoenix.motorcontrol.IMotorControllerEnhanced;
006import com.ctre.phoenix.motorcontrol.FeedbackDevice;
007import com.ctre.phoenix.motorcontrol.RemoteSensorSource;
008import com.ctre.phoenix.motorcontrol.LimitSwitchNormal;
009import com.ctre.phoenix.motorcontrol.LimitSwitchSource;
010import com.ctre.phoenix.motorcontrol.SensorCollection;
011import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
012import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
013import com.ctre.phoenix.motorcontrol.TalonFXSensorCollection;
014import com.ctre.phoenix.motorcontrol.TalonFXSimCollection;
015import com.ctre.phoenix.motorcontrol.TalonSRXSimCollection;
016import com.ctre.phoenix.motorcontrol.VelocityMeasPeriod;
017import com.ctre.phoenix.motorcontrol.can.MotControllerJNI;
018import com.ctre.phoenix.sensors.SensorVelocityMeasPeriod;
019import com.ctre.phoenix.ErrorCollection;
020import com.ctre.phoenix.ParamEnum;
021import com.ctre.phoenix.motorcontrol.SensorTerm;
022
023/**
024 * CTRE Talon SRX Motor Controller when used on CAN Bus.
025 */
026public class BaseTalon extends com.ctre.phoenix.motorcontrol.can.BaseMotorController
027                implements IMotorControllerEnhanced {
028
029        private SensorCollection _sensorCollSrx;
030        private TalonFXSensorCollection _sensorCollFx;
031
032        private TalonSRXSimCollection _simCollSrx;
033        private TalonFXSimCollection _simCollFx;
034
035        /**
036         * Constructor for BaseTalon object
037         * @param deviceNumber CAN Device ID of Device
038         */
039        public BaseTalon(int deviceNumber, String model, String canbus) {
040                super(deviceNumber, model, canbus);
041                _sensorCollSrx = new SensorCollection(this);
042                _sensorCollFx = new TalonFXSensorCollection(this);
043
044                _simCollSrx = new TalonSRXSimCollection(this);
045                _simCollFx = new TalonFXSimCollection(this);
046        }
047
048        /**
049         * Constructor for BaseTalon object
050         * @param deviceNumber CAN Device ID of Device
051         */
052        public BaseTalon(int deviceNumber, String model) {
053                this(deviceNumber, model, "");
054        }
055
056        protected SensorCollection getTalonSRXSensorCollection() {return _sensorCollSrx;}
057        protected TalonFXSensorCollection getTalonFXSensorCollection() {return _sensorCollFx;}
058
059        protected TalonSRXSimCollection getTalonSRXSimCollection() {return _simCollSrx;}
060        protected TalonFXSimCollection getTalonFXSimCollection() {return _simCollFx;}
061
062        /**
063         * Sets the period of the given status frame.
064         *
065         * User ensure CAN Bus utilization is not high.
066         *
067         * This setting is not persistent and is lost when device is reset.
068         * If this is a concern, calling application can use hasResetOccurred()
069         * to determine if the status frame needs to be reconfigured.
070         *
071         * @param frame
072         *            Frame whose period is to be changed.
073         * @param periodMs
074         *            Period in ms for the given frame.
075         * @param timeoutMs
076         *            Timeout value in ms. If nonzero, function will wait for
077         *            config success and report an error if it times out.
078         *            If zero, no blocking or checking is performed.
079         * @return Error Code generated by function. 0 indicates no error.
080         */
081        public ErrorCode setStatusFramePeriod(StatusFrameEnhanced frame, int periodMs, int timeoutMs) {
082                return super.setStatusFramePeriod(frame.value, periodMs, timeoutMs);
083        }
084        /**
085         * Sets the period of the given status frame.
086         *
087         * User ensure CAN Bus utilization is not high.
088         *
089         * This setting is not persistent and is lost when device is reset.
090         * If this is a concern, calling application can use hasResetOccurred()
091         * to determine if the status frame needs to be reconfigured.
092         *
093         * @param frame
094         *            Frame whose period is to be changed.
095         * @param periodMs
096         *            Period in ms for the given frame.
097         * @return Error Code generated by function. 0 indicates no error.
098         */
099        public ErrorCode setStatusFramePeriod(StatusFrameEnhanced frame, int periodMs) {
100                int timeoutMs = 0;
101                return setStatusFramePeriod(frame, periodMs, timeoutMs);
102        }
103        /**
104         * Gets the period of the given status frame.
105         *
106         * @param frame
107         *            Frame to get the period of.
108         * @param timeoutMs
109         *            Timeout value in ms. If nonzero, function will wait for
110         *            config success and report an error if it times out.
111         *            If zero, no blocking or checking is performed.
112         * @return Period of the given status frame.
113         */
114        public int getStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs) {
115
116                return super.getStatusFramePeriod(frame, timeoutMs);
117        }
118        /**
119         * Gets the period of the given status frame.
120         *
121         * @param frame
122         *            Frame to get the period of.
123         * @return Period of the given status frame.
124         */
125        public int getStatusFramePeriod(StatusFrameEnhanced frame) {
126                int timeoutMs = 0;
127                return getStatusFramePeriod(frame, timeoutMs);
128        }
129
130        /**
131         * Gets the output current of the motor controller.
132         * In the case of TalonSRX class, this routine returns supply current for legacy reasons.  In order to get the "true" output current, call GetStatorCurrent().
133         * In the case of TalonFX class, this routine returns the true output stator current.
134         *
135         * @deprecated Use getStatorCurrent/getSupplyCurrent instead.
136         *
137         * @return The output current (in amps).
138         */
139        @Deprecated
140        public double getOutputCurrent() {
141                return super.getOutputCurrent();
142        }
143
144        /**
145         * Gets the stator/output current of the motor controller.
146         *
147         * @return The stator/output current (in amps).
148         */
149        public double getStatorCurrent() {
150                return MotControllerJNI.GetStatorCurrent(getHandle());
151        }
152        /**
153         * Gets the supply/input current of the motor controller.
154         *
155         * @return The supply/input current (in amps).
156         */
157        public double getSupplyCurrent() {
158                return MotControllerJNI.GetSupplyCurrent(getHandle());
159        }
160
161        /**
162         * Configures the period of each velocity sample.
163         * Every 1ms a position value is sampled, and the delta between that sample
164         * and the position sampled kPeriod ms ago is inserted into a filter.
165         * kPeriod is configured with this function.
166         *
167         * @param period
168         *            Desired period for the velocity measurement. @see
169         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
170         * @param timeoutMs
171         *            Timeout value in ms. If nonzero, function will wait for
172         *            config success and report an error if it times out.
173         *            If zero, no blocking or checking is performed.
174         * @return Error Code generated by function. 0 indicates no error.
175         */
176        public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs) {
177                return super.configVelocityMeasurementPeriod(period, timeoutMs);
178        }
179        /**
180         * Configures the period of each velocity sample.
181         * Every 1ms a position value is sampled, and the delta between that sample
182         * and the position sampled kPeriod ms ago is inserted into a filter.
183         * kPeriod is configured with this function.
184         *
185         * @deprecated Use the overload with SensorVelocityMeasPeriod instead.
186         *
187         * @param period
188         *            Desired period for the velocity measurement. @see
189         *            com.ctre.phoenix.motorcontrol.VelocityMeasPeriod
190         * @param timeoutMs
191         *            Timeout value in ms. If nonzero, function will wait for
192         *            config success and report an error if it times out.
193         *            If zero, no blocking or checking is performed.
194         * @return Error Code generated by function. 0 indicates no error.
195         */
196        @Deprecated
197        public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs) {
198                return super.configVelocityMeasurementPeriod(period, timeoutMs);
199        }
200        /**
201         * Configures the period of each velocity sample.
202         * Every 1ms a position value is sampled, and the delta between that sample
203         * and the position sampled kPeriod ms ago is inserted into a filter.
204         * kPeriod is configured with this function.
205         *
206         * @param period
207         *            Desired period for the velocity measurement. @see
208         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
209         * @return Error Code generated by function. 0 indicates no error.
210         */
211        public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period) {
212                int timeoutMs = 0;
213                return configVelocityMeasurementPeriod(period, timeoutMs);
214        }
215        /**
216         * Configures the period of each velocity sample.
217         * Every 1ms a position value is sampled, and the delta between that sample
218         * and the position sampled kPeriod ms ago is inserted into a filter.
219         * kPeriod is configured with this function.
220         *
221         * @deprecated Use the overload with SensorVelocityMeasPeriod instead.
222         *
223         * @param period
224         *            Desired period for the velocity measurement. @see
225         *            com.ctre.phoenix.motorcontrol.VelocityMeasPeriod
226         * @return Error Code generated by function. 0 indicates no error.
227         */
228        @Deprecated
229        public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period) {
230                int timeoutMs = 0;
231                return configVelocityMeasurementPeriod(period, timeoutMs);
232        }
233        /**
234         * Sets the number of velocity samples used in the rolling average velocity
235         * measurement.
236         *
237         * @param windowSize
238         *            Number of samples in the rolling average of velocity
239         *            measurement. Valid values are 1,2,4,8,16,32. If another
240         *            value is specified, it will truncate to nearest support value.
241         * @param timeoutMs
242         *            Timeout value in ms. If nonzero, function will wait for
243         *            config success and report an error if it times out.
244         *            If zero, no blocking or checking is performed.
245         * @return Error Code generated by function. 0 indicates no error.
246         */
247        public ErrorCode configVelocityMeasurementWindow(int windowSize, int timeoutMs) {
248                return super.configVelocityMeasurementWindow(windowSize, timeoutMs);
249        }
250        /**
251         * Sets the number of velocity samples used in the rolling average velocity
252         * measurement.
253         *
254         * @param windowSize
255         *            Number of samples in the rolling average of velocity
256         *            measurement. Valid values are 1,2,4,8,16,32. If another
257         *            value is specified, it will truncate to nearest support value.
258         * @return Error Code generated by function. 0 indicates no error.
259         */
260        public ErrorCode configVelocityMeasurementWindow(int windowSize) {
261                int timeoutMs = 0;
262                return configVelocityMeasurementWindow(windowSize, timeoutMs);
263        }
264        /**
265         * Configures a limit switch for a local/remote source.
266         *
267         * For example, a CAN motor controller may need to monitor the Limit-R pin
268         * of another Talon, CANifier, or local Gadgeteer feedback connector.
269         *
270         * If the sensor is remote, a device ID of zero is assumed.
271         * If that's not desired, use the four parameter version of this function.
272         *
273         * @param type
274         *            Limit switch source.
275         *            User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
276         * @param normalOpenOrClose
277         *            Setting for normally open, normally closed, or disabled. This setting
278         *            matches the Phoenix Tuner drop down.
279         * @param timeoutMs
280         *            Timeout value in ms. If nonzero, function will wait for
281         *            config success and report an error if it times out.
282         *            If zero, no blocking or checking is performed.
283         * @return Error Code generated by function. 0 indicates no error.
284         */
285        public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
286                        int timeoutMs) {
287
288                return super.configForwardLimitSwitchSource(type.value, normalOpenOrClose.value, -1, timeoutMs);
289        }
290        /**
291         * Configures a limit switch for a local/remote source.
292         *
293         * For example, a CAN motor controller may need to monitor the Limit-R pin
294         * of another Talon, CANifier, or local Gadgeteer feedback connector.
295         *
296         * If the sensor is remote, a device ID of zero is assumed.
297         * If that's not desired, use the four parameter version of this function.
298         *
299         * @param type
300         *            Limit switch source.
301         *            User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
302         * @param normalOpenOrClose
303         *            Setting for normally open, normally closed, or disabled. This setting
304         *            matches the Phoenix Tuner drop down.
305         * @return Error Code generated by function. 0 indicates no error.
306         */
307        public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose) {
308                int timeoutMs = 0;
309                return configForwardLimitSwitchSource(type, normalOpenOrClose, timeoutMs);
310        }
311        /**
312         * Configures a limit switch for a local/remote source.
313         *
314         * For example, a CAN motor controller may need to monitor the Limit-R pin
315         * of another Talon, CANifier, or local Gadgeteer feedback connector.
316         *
317         * If the sensor is remote, a device ID of zero is assumed. If that's not
318         * desired, use the four parameter version of this function.
319         *
320         * @param type
321         *            Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose
322         *            between the feedback connector, remote Talon SRX, CANifier, or
323         *            deactivate the feature.
324         * @param normalOpenOrClose
325         *            Setting for normally open, normally closed, or disabled. This
326         *            setting matches the Phoenix Tuner drop down.
327         * @param timeoutMs
328         *            Timeout value in ms. If nonzero, function will wait for config
329         *            success and report an error if it times out. If zero, no
330         *            blocking or checking is performed.
331         * @return Error Code generated by function. 0 indicates no error.
332         */
333        public ErrorCode configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
334                        int timeoutMs) {
335                return super.configReverseLimitSwitchSource(type.value, normalOpenOrClose.value, -1, timeoutMs);
336        }
337        /**
338         * Configures a limit switch for a local/remote source.
339         *
340         * For example, a CAN motor controller may need to monitor the Limit-R pin
341         * of another Talon, CANifier, or local Gadgeteer feedback connector.
342         *
343         * If the sensor is remote, a device ID of zero is assumed. If that's not
344         * desired, use the four parameter version of this function.
345         *
346         * @param type
347         *            Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose
348         *            between the feedback connector, remote Talon SRX, CANifier, or
349         *            deactivate the feature.
350         * @param normalOpenOrClose
351         *            Setting for normally open, normally closed, or disabled. This
352         *            setting matches the Phoenix Tuner drop down.
353         * @return Error Code generated by function. 0 indicates no error.
354         */
355        public ErrorCode configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose) {
356                int timeoutMs = 0;
357                return configReverseLimitSwitchSource(type, normalOpenOrClose, timeoutMs);
358
359        }
360
361        // ------ Current Lim ----------//
362        /**
363         * Configures the supply (input) current limit.
364
365         * @param currLimitCfg  Current limit configuration
366         * @param timeoutMs
367         *            Timeout value in ms. If nonzero, function will wait for
368         *            config success and report an error if it times out.
369         *            If zero, no blocking or checking is performed.
370         * @return Error Code generated by function. 0 indicates no error.
371         */
372        public ErrorCode configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitCfg, int timeoutMs ) {
373                /* child classes uniquely implement ConfigSupplyCurrentLimit */
374                return ErrorCode.OK;
375        }
376
377        //------ RAW Sensor API ----------//
378
379        /**
380        * Is forward limit switch closed.
381        *
382        * @return  '1' iff forward limit switch input is closed, 0 iff switch is open. This function works
383        *          regardless if limit switch feature is enabled.  Remote limit features do not impact this routine.
384        */
385        public int isFwdLimitSwitchClosed() {
386                return MotControllerJNI.IsFwdLimitSwitchClosed(getHandle());
387        }
388        /**
389         * Is reverse limit switch closed.
390         *
391         * @return  '1' iff reverse limit switch is closed, 0 iff switch is open. This function works
392         *          regardless if limit switch feature is enabled.  Remote limit features do not impact this routine.
393         */
394        public int isRevLimitSwitchClosed() {
395                return MotControllerJNI.IsRevLimitSwitchClosed(getHandle());
396        }
397
398
399    /**
400     * Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms
401     * and pidIdx is 0).
402     *
403         * @param pid               Object with all of the PID set persistant settings
404         * @param pidIdx            0 for Primary closed-loop. 1 for auxiliary closed-loop.
405     * @param timeoutMs
406     *              Timeout value in ms. If nonzero, function will wait for
407     *              config success and report an error if it times out.
408     *              If zero, no blocking or checking is performed.
409         * @param enableOptimizations   Enable the optimization technique
410     *
411     * @return Error Code generated by function. 0 indicates no error.
412     */
413        protected ErrorCode configurePID(BaseTalonPIDSetConfiguration pid, int pidIdx, int timeoutMs, boolean enableOptimizations) {
414        ErrorCollection errorCollection = new ErrorCollection();
415
416        //------ sensor selection ----------//
417
418                if(BaseTalonPIDSetConfigUtil.selectedFeedbackCoefficientDifferent(pid) || !enableOptimizations)
419                        errorCollection.NewError(configSelectedFeedbackCoefficient(pid.selectedFeedbackCoefficient, pidIdx, timeoutMs));
420                if(BaseTalonPIDSetConfigUtil.selectedFeedbackSensorDifferent(pid) || !enableOptimizations)
421                        errorCollection.NewError(configSelectedFeedbackSensor(pid.selectedFeedbackSensor, pidIdx, timeoutMs));
422
423
424        return errorCollection._worstError;
425
426
427        }
428    /**
429     * Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms
430     * and pidIdx is 0).
431     *
432         * @param pid               Object with all of the PID set persistant settings
433     *
434     * @return Error Code generated by function. 0 indicates no error.
435     */
436        protected ErrorCode configurePID(BaseTalonPIDSetConfiguration pid) {
437        int pidIdx = 0;
438        int timeoutMs = 50;
439        return configurePID(pid, pidIdx, timeoutMs, true);
440    }
441
442    /**
443     * Gets all PID set persistant settings.
444     *
445         * @param pid               Object with all of the PID set persistant settings
446         * @param pidIdx            0 for Primary closed-loop. 1 for auxiliary closed-loop.
447     * @param timeoutMs
448     *              Timeout value in ms. If nonzero, function will wait for
449     *              config success and report an error if it times out.
450     *              If zero, no blocking or checking is performed.
451     */
452    protected void getPIDConfigs(BaseTalonPIDSetConfiguration pid, int pidIdx, int timeoutMs)
453    {
454        baseGetPIDConfigs(pid, pidIdx, timeoutMs);
455        pid.selectedFeedbackSensor = FeedbackDevice.valueOf(configGetParameter(ParamEnum.eFeedbackSensorType, pidIdx, timeoutMs));
456
457    }
458    /**
459     * Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms
460     * and pidIdx is 0).
461     *
462         * @param pid               Object with all of the PID set persistant settings
463     */
464        protected void getPIDConfigs(BaseTalonPIDSetConfiguration pid) {
465        int pidIdx = 0;
466        int timeoutMs = 50;
467        getPIDConfigs(pid, pidIdx, timeoutMs);
468    }
469
470
471
472    /**
473     * Configures all persistent settings.
474     *
475         * @param allConfigs        Object with all of the persistant settings
476     * @param timeoutMs
477     *              Timeout value in ms. If nonzero, function will wait for
478     *              config success and report an error if it times out.
479     *              If zero, no blocking or checking is performed.
480     *
481     * @return Error Code generated by function. 0 indicates no error.
482     */
483        protected ErrorCode configAllSettings(BaseTalonConfiguration allConfigs, int timeoutMs) {
484        ErrorCollection errorCollection = new ErrorCollection();
485
486        errorCollection.NewError(baseConfigAllSettings(allConfigs, timeoutMs));
487
488
489        //--------PIDs---------------//
490                errorCollection.NewError(configurePID(allConfigs.primaryPID, 0, timeoutMs, allConfigs.enableOptimizations));
491                errorCollection.NewError(configurePID(allConfigs.auxiliaryPID, 1, timeoutMs, allConfigs.enableOptimizations));
492
493                if(BaseTalonConfigUtil.forwardLimitSwitchDifferent(allConfigs))
494                        errorCollection.NewError(MotControllerJNI.ConfigForwardLimitSwitchSource(m_handle, allConfigs.forwardLimitSwitchSource.value,
495                                allConfigs.forwardLimitSwitchNormal.value, allConfigs.forwardLimitSwitchDeviceID, timeoutMs));
496                if(BaseTalonConfigUtil.reverseLimitSwitchDifferent(allConfigs))
497                        errorCollection.NewError(MotControllerJNI.ConfigReverseLimitSwitchSource(m_handle, allConfigs.reverseLimitSwitchSource.value,
498                                allConfigs.reverseLimitSwitchNormal.value, allConfigs.reverseLimitSwitchDeviceID, timeoutMs));
499
500                if(BaseTalonConfigUtil.sum0TermDifferent(allConfigs)) errorCollection.NewError(configSensorTerm(SensorTerm.Sum0, allConfigs.sum0Term, timeoutMs));
501                if(BaseTalonConfigUtil.sum1TermDifferent(allConfigs)) errorCollection.NewError(configSensorTerm(SensorTerm.Sum1, allConfigs.sum1Term, timeoutMs));
502                if(BaseTalonConfigUtil.diff0TermDifferent(allConfigs)) errorCollection.NewError(configSensorTerm(SensorTerm.Diff0, allConfigs.diff0Term, timeoutMs));
503                if(BaseTalonConfigUtil.diff1TermDifferent(allConfigs)) errorCollection.NewError(configSensorTerm(SensorTerm.Diff1, allConfigs.diff1Term, timeoutMs));
504
505        return errorCollection._worstError;
506
507        }
508
509    /**
510     * Configures all persistent settings (overloaded so timeoutMs is 50 ms).
511     *
512         * @param allConfigs        Object with all of the persistant settings
513     *
514     * @return Error Code generated by function. 0 indicates no error.
515     */
516        protected ErrorCode configAllSettings(BaseTalonConfiguration allConfigs) {
517                int timeoutMs = 50;
518                return configAllSettings(allConfigs, timeoutMs);
519        }
520
521    /**
522     * Gets all persistant settings.
523     *
524         * @param allConfigs        Object with all of the persistant settings
525     * @param timeoutMs
526     *              Timeout value in ms. If nonzero, function will wait for
527     *              config success and report an error if it times out.
528     *              If zero, no blocking or checking is performed.
529     */
530    protected void getAllConfigs(BaseTalonConfiguration allConfigs, int timeoutMs) {
531
532        baseGetAllConfigs(allConfigs, timeoutMs);
533
534        getPIDConfigs(allConfigs.primaryPID, 0, timeoutMs);
535        getPIDConfigs(allConfigs.auxiliaryPID, 1, timeoutMs);
536        allConfigs.sum0Term =  FeedbackDevice.valueOf(configGetParameter(ParamEnum.eSensorTerm, 0, timeoutMs));
537        allConfigs.sum1Term =  FeedbackDevice.valueOf(configGetParameter(ParamEnum.eSensorTerm, 1, timeoutMs));
538        allConfigs.diff0Term = FeedbackDevice.valueOf(configGetParameter(ParamEnum.eSensorTerm, 2, timeoutMs));
539        allConfigs.diff1Term = FeedbackDevice.valueOf(configGetParameter(ParamEnum.eSensorTerm, 3, timeoutMs));
540
541
542        allConfigs.forwardLimitSwitchSource = LimitSwitchSource.valueOf(configGetParameter(ParamEnum.eLimitSwitchSource, 0, timeoutMs));
543        allConfigs.reverseLimitSwitchSource = LimitSwitchSource.valueOf(configGetParameter(ParamEnum.eLimitSwitchSource, 1, timeoutMs));
544        allConfigs.forwardLimitSwitchDeviceID = (int) configGetParameter(ParamEnum.eLimitSwitchRemoteDevID, 0, timeoutMs);
545        allConfigs.reverseLimitSwitchDeviceID = (int) configGetParameter(ParamEnum.eLimitSwitchRemoteDevID, 1, timeoutMs);
546        allConfigs.forwardLimitSwitchNormal = LimitSwitchNormal.valueOf(configGetParameter(ParamEnum.eLimitSwitchNormClosedAndDis, 0, timeoutMs));
547        allConfigs.reverseLimitSwitchNormal = LimitSwitchNormal.valueOf(configGetParameter(ParamEnum.eLimitSwitchNormClosedAndDis, 1, timeoutMs));
548
549    }
550    /**
551     * Gets all persistant settings (overloaded so timeoutMs is 50 ms).
552     *
553         * @param allConfigs        Object with all of the persistant settings
554     */
555    protected void getAllConfigs(BaseTalonConfiguration allConfigs) {
556        int timeoutMs = 50;
557        getAllConfigs(allConfigs, timeoutMs);
558    }
559}