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