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