001/* Copyright (C) Cross The Road Electronics 2024 */
002package com.ctre.phoenix.motorcontrol.can;
003
004import com.ctre.phoenix.motorcontrol.ControlFrame;
005import com.ctre.phoenix.motorcontrol.ControlMode;
006import com.ctre.phoenix.motorcontrol.DemandType;
007import com.ctre.phoenix.motorcontrol.Faults;
008import com.ctre.phoenix.motorcontrol.FeedbackDevice;
009import com.ctre.phoenix.motorcontrol.FollowerType;
010import com.ctre.phoenix.motorcontrol.IMotorController;
011import com.ctre.phoenix.motorcontrol.InvertType;
012import com.ctre.phoenix.motorcontrol.LimitSwitchNormal;
013import com.ctre.phoenix.motorcontrol.LimitSwitchSource;
014import com.ctre.phoenix.motorcontrol.NeutralMode;
015import com.ctre.phoenix.motorcontrol.RemoteFeedbackDevice;
016import com.ctre.phoenix.motorcontrol.RemoteLimitSwitchSource;
017import com.ctre.phoenix.motorcontrol.RemoteSensorSource;
018import com.ctre.phoenix.motorcontrol.SensorTerm;
019import com.ctre.phoenix.motorcontrol.StatusFrame;
020import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
021import com.ctre.phoenix.motorcontrol.StickyFaults;
022import com.ctre.phoenix.motorcontrol.VelocityMeasPeriod;
023import com.ctre.phoenix.motorcontrol.VictorSPXSimCollection;
024import com.ctre.phoenix.sensors.CANCoder;
025import com.ctre.phoenix.ParamEnum;
026import com.ctre.phoenix.motion.BufferedTrajectoryPointStream;
027import com.ctre.phoenix.motion.MotionProfileStatus;
028import com.ctre.phoenix.motion.SetValueMotionProfile;
029import com.ctre.phoenix.motion.TrajectoryPoint;
030import com.ctre.phoenix.ErrorCode;
031import com.ctre.phoenix.ErrorCollection;
032import com.ctre.phoenix.ParamEnum;
033import com.ctre.phoenix.sensors.SensorVelocityMeasPeriod;
034
035/**
036 * Base motor controller features for all CTRE CAN motor controllers.
037 */
038public abstract class BaseMotorController implements com.ctre.phoenix.motorcontrol.IMotorController {
039
040        private ControlMode m_controlMode = ControlMode.PercentOutput;
041        private ControlMode m_sendMode = ControlMode.PercentOutput;
042
043        private InvertType _invert = InvertType.None;
044
045        private boolean _isVcompEn = false; //off by default
046
047        /**
048         * Device handle
049         */
050        protected long m_handle;
051
052        private int [] _motionProfStats = new int[11];
053
054        private VictorSPXSimCollection _simCollSpx;
055
056        // --------------------- Constructors -----------------------------//
057        /**
058         * Constructor for motor controllers.
059         *
060         * @param arbId Device ID [0,62]
061         * @param model String specifying device model
062         */
063        public BaseMotorController(int arbId, String model, String canbus) {
064                m_handle = MotControllerJNI.Create2(arbId, model, canbus);
065                _simCollSpx = new VictorSPXSimCollection(this);
066        }
067
068        /**
069         * Constructor for motor controllers.
070         *
071         * @param arbId Device ID [0,62]
072         * @param model String specifying device model
073         */
074        public BaseMotorController(int arbId, String model) {
075                this(arbId, model, "");
076        }
077
078        protected VictorSPXSimCollection getVictorSPXSimCollection() {return _simCollSpx;}
079
080        /**
081         * Destructor for motor controllers
082         * @return Error Code generated by function. 0 indicates no error.
083         */
084    public ErrorCode DestroyObject() {
085        return ErrorCode.valueOf(MotControllerJNI.JNI_destroy_MotController(m_handle));
086    }
087
088    //public static void DestroyAllMotControllers() {
089    //    MotControllerJNI.JNI_destroy_AllMotControllers();
090    //}
091
092        /**
093         * @return CCI handle for child classes.
094         */
095        public long getHandle() {
096                return m_handle;
097        }
098
099        /**
100         * Returns the Device ID
101         *
102         * @return Device number.
103         */
104        public int getDeviceID() {
105                return MotControllerJNI.GetDeviceNumber(m_handle);
106        }
107
108        // ------ Set output routines. ----------//
109        /**
110         * Sets the appropriate output on the talon, depending on the mode.
111         * @param mode The output mode to apply.
112         * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
113         * In Current mode, output value is in amperes.
114         * In Velocity mode, output value is in position change / 100ms.
115         * In Position mode, output value is in encoder ticks or an analog value,
116         *   depending on the sensor.
117         * In Follower mode, the output value is the integer device ID of the talon to
118         * duplicate.
119         *
120         * @param outputValue The setpoint value, as described above.
121         *
122         *
123         *      Standard Driving Example:
124         *      _talonLeft.set(ControlMode.PercentOutput, leftJoy);
125         *      _talonRght.set(ControlMode.PercentOutput, rghtJoy);
126         */
127        public void set(ControlMode mode, double outputValue) {
128                set(mode, outputValue, DemandType.Neutral, 0);
129        }
130        /**
131         * @param mode Sets the appropriate output on the talon, depending on the mode.
132         * @param demand0 The output value to apply.
133         *      such as advanced feed forward and/or auxiliary close-looping in firmware.
134         * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
135         * In Current mode, output value is in amperes.
136         * In Velocity mode, output value is in position change / 100ms.
137         * In Position mode, output value is in encoder ticks or an analog value,
138         *   depending on the sensor. See
139         * In Follower mode, the output value is the integer device ID of the talon to
140         * duplicate.
141         *
142         * @param demand1Type The demand type for demand1.
143         * Neutral: Ignore demand1 and apply no change to the demand0 output.
144         * AuxPID: Use demand1 to set the target for the auxiliary PID 1.  Auxiliary
145         *   PID is always executed as standard Position PID control.
146         * ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the
147         *       demand0 output.  In PercentOutput the demand0 output is the motor output,
148         *   and in closed-loop modes the demand0 output is the output of PID0.
149         * @param demand1 Supplmental output value.
150         * AuxPID: Target position in Sensor Units
151         * ArbitraryFeedForward: Percent Output between -1.0 and 1.0
152         *
153         *
154         *  Arcade Drive Example:
155         *              _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn);
156         *              _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);
157         *
158         *      Drive Straight Example:
159         *      Note: Selected Sensor Configuration is necessary for both PID0 and PID1.
160         *              _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
161         *              _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);
162         *
163         *      Drive Straight to a Distance Example:
164         *      Note: Other configurations (sensor selection, PID gains, etc.) need to be set.
165         *              _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
166         *              _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
167         */
168        public void set(ControlMode mode, double demand0, DemandType demand1Type, double demand1){
169                m_controlMode = mode;
170                m_sendMode = mode;
171                int work;
172
173                switch (m_controlMode) {
174                case PercentOutput:
175                        // case TimedPercentOutput:
176                        MotControllerJNI.Set_4(m_handle, m_sendMode.value, demand0, demand1, demand1Type.value);
177                        break;
178                case Follower:
179                        /* did caller specify device ID */
180                        if ((0 <= demand0) && (demand0 <= 62)) { // [0,62]
181                                work = getBaseID();
182                                work >>= 16;
183                                work <<= 8;
184                                work |= ((int) demand0) & 0xFF;
185                        } else {
186                                work = (int) demand0;
187                        }
188                        /* single precision guarantees 16bits of integral precision,
189                   * so float/double cast on work is safe */
190                        MotControllerJNI.Set_4(m_handle, m_sendMode.value, (double)work, demand1, demand1Type.value);
191                        break;
192                case Velocity:
193                case Position:
194                case MotionMagic:
195                case MotionProfile:
196                case MotionProfileArc:
197                        MotControllerJNI.Set_4(m_handle, m_sendMode.value, demand0, demand1, demand1Type.value);
198                        break;
199                case Current:
200                        MotControllerJNI.SetDemand(m_handle, m_sendMode.value, (int) (1000. * demand0), 0); /* milliamps */
201                        break;
202                case MusicTone:
203                        MotControllerJNI.Set_4(m_handle, m_sendMode.value, demand0, demand1, demand1Type.value);
204                        break;
205                case Disabled:
206                        /* fall thru... */
207                default:
208                        MotControllerJNI.SetDemand(m_handle, m_sendMode.value, 0, 0);
209                        break;
210                }
211
212        }
213
214        /**
215         * Neutral the motor output by setting control mode to disabled.
216         */
217        public void neutralOutput() {
218                set(ControlMode.Disabled, 0);
219        }
220
221        /**
222         * Sets the mode of operation during neutral throttle output.
223         *
224         * @param neutralMode
225         *            The desired mode of operation when the Controller output
226         *            throttle is neutral (ie brake/coast)
227         **/
228        public void setNeutralMode(NeutralMode neutralMode) {
229                MotControllerJNI.SetNeutralMode(m_handle, neutralMode.value);
230        }
231
232        // ------ Invert behavior ----------//
233        /**
234         * Sets the phase of the sensor. Use when controller forward/reverse output
235         * doesn't correlate to appropriate forward/reverse reading of sensor.
236         * Pick a value so that positive PercentOutput yields a positive change in sensor.
237         * After setting this, user can freely call SetInverted() with any value.
238         *
239         * @param PhaseSensor
240         *            Indicates whether to invert the phase of the sensor.
241         */
242        public void setSensorPhase(boolean PhaseSensor) {
243                MotControllerJNI.SetSensorPhase(m_handle, PhaseSensor);
244        }
245
246        /**
247         * Inverts the hbridge output of the motor controller.
248         *
249         * This does not impact sensor phase and should not be used to correct sensor polarity.
250         *
251         * This will invert the hbridge output but NOT the LEDs.
252         * This ensures....
253         *  - Green LEDs always represents positive request from robot-controller/closed-looping mode.
254         *  - Green LEDs correlates to forward limit switch.
255         *  - Green LEDs correlates to forward soft limit.
256         *
257         * @param invert
258         *            Invert state to set.
259         */
260        public void setInverted(boolean invert) {
261                if(invert){
262                        setInverted(InvertType.InvertMotorOutput);
263                }
264                else{
265                        setInverted(InvertType.None);
266                }
267        }
268
269        /**
270         * Inverts the hbridge output of the motor controller in relation to the master if present
271         *
272         * This does not impact sensor phase and should not be used to correct sensor polarity.
273         *
274         * This will allow you to either:
275         *  - Not invert the motor
276         *  - Invert the motor
277         *  - Always follow the master regardless of master's inversion
278         *  - Always oppose the master regardless of master's inversion
279         *
280         * @param invertType
281         *            Invert state to set.
282         */
283        public void setInverted(InvertType invertType){
284                _invert = invertType;
285                MotControllerJNI.SetInverted_2(m_handle, invertType.value);
286        }
287
288        /**
289         * @return invert setting of motor output.
290         */
291        public boolean getInverted() {
292                switch(_invert){
293                        case None:{
294                                return false;
295                        }
296                        case InvertMotorOutput:{
297                                return true;
298                        }
299                        default:{
300                                break;
301                        }
302                }
303                return MotControllerJNI.GetInverted(m_handle);
304        }
305
306    //----- Factory Default Configuration -----//
307        /**
308         * Revert all configurations to factory default values.
309         * Use this before your individual config* calls to avoid having to config every single param.
310         *
311         * Alternatively you can use the configAllSettings routine.
312         *
313         * @param timeoutMs
314         *            Timeout value in ms. Function will generate error if config is
315         *            not successful within timeout.
316         * @return Error Code generated by function. 0 indicates no error.
317         */
318        public ErrorCode configFactoryDefault(int timeoutMs){
319                int retval = MotControllerJNI.ConfigFactoryDefault(m_handle, timeoutMs);
320                return ErrorCode.valueOf(retval);
321        }
322        /**
323         * Revert all configurations to factory default values.
324         * Use this before your individual config* calls to avoid having to config every single param.
325         *
326         * Alternatively you can use the configAllSettings routine.
327         *
328         * @return Error Code generated by function. 0 indicates no error.
329         */
330        public ErrorCode configFactoryDefault() {
331        int timeoutMs = 50;
332                int retval = MotControllerJNI.ConfigFactoryDefault(m_handle, timeoutMs);
333                return ErrorCode.valueOf(retval);
334        }
335
336        // ----- general output shaping ------------------//
337        /**
338         * Configures the open-loop ramp rate of throttle output.
339         *
340         * @param secondsFromNeutralToFull
341         *            Minimum desired time to go from neutral to full throttle. A
342         *            value of '0' will disable the ramp.
343         * @param timeoutMs
344         *            Timeout value in ms. If nonzero, function will wait for
345         *            config success and report an error if it times out.
346         *            If zero, no blocking or checking is performed.
347         * @return Error Code generated by function. 0 indicates no error.
348         */
349        public ErrorCode configOpenloopRamp(double secondsFromNeutralToFull, int timeoutMs) {
350                int retval = MotControllerJNI.ConfigOpenLoopRamp(m_handle, secondsFromNeutralToFull, timeoutMs);
351                return ErrorCode.valueOf(retval);
352        }
353        /**
354         * Configures the open-loop ramp rate of throttle output.
355         *
356         * @param secondsFromNeutralToFull
357         *            Minimum desired time to go from neutral to full throttle. A
358         *            value of '0' will disable the ramp.
359         * @return Error Code generated by function. 0 indicates no error.
360         */
361        public ErrorCode configOpenloopRamp(double secondsFromNeutralToFull) {
362                int timeoutMs = 0;
363                return configOpenloopRamp(secondsFromNeutralToFull, timeoutMs);
364        }
365
366        /**
367         * Configures the closed-loop ramp rate of throttle output.
368         *
369         * @param secondsFromNeutralToFull
370         *            Minimum desired time to go from neutral to full throttle. A
371         *            value of '0' will disable the ramp.
372         * @param timeoutMs
373         *            Timeout value in ms. If nonzero, function will wait for
374         *            config success and report an error if it times out.
375         *            If zero, no blocking or checking is performed.
376         * @return Error Code generated by function. 0 indicates no error.
377         */
378        public ErrorCode configClosedloopRamp(double secondsFromNeutralToFull, int timeoutMs) {
379                int retval = MotControllerJNI.ConfigClosedLoopRamp(m_handle, secondsFromNeutralToFull, timeoutMs);
380                return ErrorCode.valueOf(retval);
381        }
382        /**
383         * Configures the closed-loop ramp rate of throttle output.
384         *
385         * @param secondsFromNeutralToFull
386         *            Minimum desired time to go from neutral to full throttle. A
387         *            value of '0' will disable the ramp.
388         * @return Error Code generated by function. 0 indicates no error.
389         */
390        public ErrorCode configClosedloopRamp(double secondsFromNeutralToFull) {
391                int timeoutMs = 0;
392                return configClosedloopRamp(secondsFromNeutralToFull, timeoutMs);
393        }
394
395        /**
396         * Configures the forward peak output percentage.
397         *
398         * @param percentOut
399         *            Desired peak output percentage. [0,1]
400         * @param timeoutMs
401         *            Timeout value in ms. If nonzero, function will wait for
402         *            config success and report an error if it times out.
403         *            If zero, no blocking or checking is performed.
404         * @return Error Code generated by function. 0 indicates no error.
405         */
406        public ErrorCode configPeakOutputForward(double percentOut, int timeoutMs) {
407                int retval = MotControllerJNI.ConfigPeakOutputForward(m_handle, percentOut, timeoutMs);
408                return ErrorCode.valueOf(retval);
409        }
410        /**
411         * Configures the forward peak output percentage.
412         *
413         * @param percentOut
414         *            Desired peak output percentage. [0,1]
415         * @return Error Code generated by function. 0 indicates no error.
416         */
417        public ErrorCode configPeakOutputForward(double percentOut) {
418                int timeoutMs = 0;
419                return configPeakOutputForward(percentOut, timeoutMs);
420        }
421
422        /**
423         * Configures the reverse peak output percentage.
424         *
425         * @param percentOut
426         *            Desired peak output percentage.
427         * @param timeoutMs
428         *            Timeout value in ms. If nonzero, function will wait for
429         *            config success and report an error if it times out.
430         *            If zero, no blocking or checking is performed.
431         * @return Error Code generated by function. 0 indicates no error.
432         */
433        public ErrorCode configPeakOutputReverse(double percentOut, int timeoutMs) {
434                int retval = MotControllerJNI.ConfigPeakOutputReverse(m_handle, percentOut, timeoutMs);
435                return ErrorCode.valueOf(retval);
436        }
437        /**
438         * Configures the reverse peak output percentage.
439         *
440         * @param percentOut
441         *            Desired peak output percentage.
442         * @return Error Code generated by function. 0 indicates no error.
443         */
444        public ErrorCode configPeakOutputReverse(double percentOut) {
445                int timeoutMs = 0;
446                return configPeakOutputReverse(percentOut, timeoutMs);
447        }
448        /**
449         * Configures the forward nominal output percentage.
450         *
451         * @param percentOut
452         *            Nominal (minimum) percent output. [0,+1]
453         * @param timeoutMs
454         *            Timeout value in ms. If nonzero, function will wait for
455         *            config success and report an error if it times out.
456         *            If zero, no blocking or checking is performed.
457         * @return Error Code generated by function. 0 indicates no error.
458         */
459        public ErrorCode configNominalOutputForward(double percentOut, int timeoutMs) {
460                int retval = MotControllerJNI.ConfigNominalOutputForward(m_handle, percentOut, timeoutMs);
461                return ErrorCode.valueOf(retval);
462        }
463        /**
464         * Configures the forward nominal output percentage.
465         *
466         * @param percentOut
467         *            Nominal (minimum) percent output. [0,+1]
468         * @return Error Code generated by function. 0 indicates no error.
469         */
470        public ErrorCode configNominalOutputForward(double percentOut) {
471                int timeoutMs = 0;
472                return configNominalOutputForward(percentOut, timeoutMs);
473        }
474
475        /**
476         * Configures the reverse nominal output percentage.
477         *
478         * @param percentOut
479         *            Nominal (minimum) percent output. [-1,0]
480         * @param timeoutMs
481         *            Timeout value in ms. If nonzero, function will wait for
482         *            config success and report an error if it times out.
483         *            If zero, no blocking or checking is performed.
484         * @return Error Code generated by function. 0 indicates no error.
485         */
486        public ErrorCode configNominalOutputReverse(double percentOut, int timeoutMs) {
487                int retval = MotControllerJNI.ConfigNominalOutputReverse(m_handle, percentOut, timeoutMs);
488                return ErrorCode.valueOf(retval);
489        }
490        /**
491         * Configures the reverse nominal output percentage.
492         *
493         * @param percentOut
494         *            Nominal (minimum) percent output. [-1,0]
495         * @return Error Code generated by function. 0 indicates no error.
496         */
497        public ErrorCode configNominalOutputReverse(double percentOut) {
498                int timeoutMs = 0;
499                return configNominalOutputReverse(percentOut, timeoutMs);
500        }
501
502        /**
503         * Configures the output deadband percentage.
504         *
505         * @param percentDeadband
506         *            Desired deadband percentage. Minimum is 0.1%, Maximum is 25%.
507         *            Pass 0.04 for 4% (factory default).
508         * @param timeoutMs
509         *            Timeout value in ms. If nonzero, function will wait for
510         *            config success and report an error if it times out.
511         *            If zero, no blocking or checking is performed.
512         * @return Error Code generated by function. 0 indicates no error.
513         */
514        public ErrorCode configNeutralDeadband(double percentDeadband, int timeoutMs) {
515                int retval = MotControllerJNI.ConfigNeutralDeadband(m_handle, percentDeadband, timeoutMs);
516                return ErrorCode.valueOf(retval);
517        }
518        /**
519         * Configures the output deadband percentage.
520         *
521         * @param percentDeadband
522         *            Desired deadband percentage. Minimum is 0.1%, Maximum is 25%.
523         *            Pass 0.04 for 4% (factory default).
524         * @return Error Code generated by function. 0 indicates no error.
525         */
526        public ErrorCode configNeutralDeadband(double percentDeadband) {
527                int timeoutMs = 0;
528                return configNeutralDeadband(percentDeadband, timeoutMs);
529        }
530
531        // ------ Voltage Compensation ----------//
532        /**
533         * Configures the Voltage Compensation saturation voltage.
534         *
535         * @param voltage
536         *            This is the max voltage to apply to the hbridge when voltage
537         *            compensation is enabled.  For example, if 10 (volts) is specified
538         *            and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc)
539         *            then the TalonSRX will attempt to apply a duty-cycle to produce 5V.
540         * @param timeoutMs
541         *            Timeout value in ms. If nonzero, function will wait for
542         *            config success and report an error if it times out.
543         *            If zero, no blocking or checking is performed.
544         * @return Error Code generated by function. 0 indicates no error.
545         */
546        public ErrorCode configVoltageCompSaturation(double voltage, int timeoutMs) {
547                int retval = MotControllerJNI.ConfigVoltageCompSaturation(m_handle, voltage, timeoutMs);
548                return ErrorCode.valueOf(retval);
549        }
550        /**
551         * Configures the Voltage Compensation saturation voltage.
552         *
553         * @param voltage
554         *            This is the max voltage to apply to the hbridge when voltage
555         *            compensation is enabled.  For example, if 10 (volts) is specified
556         *            and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc)
557         *            then the TalonSRX will attempt to apply a duty-cycle to produce 5V.
558         * @return Error Code generated by function. 0 indicates no error.
559         */
560        public ErrorCode configVoltageCompSaturation(double voltage) {
561                int timeoutMs = 0;
562                return configVoltageCompSaturation(voltage, timeoutMs);
563        }
564
565        /**
566         * Configures the voltage measurement filter.
567         *
568         * @param filterWindowSamples
569         *            Number of samples in the rolling average of voltage
570         *            measurement.
571         * @param timeoutMs
572         *            Timeout value in ms. If nonzero, function will wait for
573         *            config success and report an error if it times out.
574         *            If zero, no blocking or checking is performed.
575         * @return Error Code generated by function. 0 indicates no error.
576         */
577        public ErrorCode configVoltageMeasurementFilter(int filterWindowSamples, int timeoutMs) {
578                int retval = MotControllerJNI.ConfigVoltageMeasurementFilter(m_handle, filterWindowSamples, timeoutMs);
579                return ErrorCode.valueOf(retval);
580        }
581        /**
582         * Configures the voltage measurement filter.
583         *
584         * @param filterWindowSamples
585         *            Number of samples in the rolling average of voltage
586         *            measurement.
587         * @return Error Code generated by function. 0 indicates no error.
588         */
589        public ErrorCode configVoltageMeasurementFilter(int filterWindowSamples) {
590                int timeoutMs = 0;
591                return configVoltageMeasurementFilter(filterWindowSamples, timeoutMs);
592        }
593
594        /**
595         * Enables voltage compensation. If enabled, voltage compensation works in
596         * all control modes.
597         *
598         * Be sure to configure the saturation voltage before enabling this.
599         *
600         * @param enable
601         *            Enable state of voltage compensation.
602         **/
603        public void enableVoltageCompensation(boolean enable) {
604                _isVcompEn = enable;
605                MotControllerJNI.EnableVoltageCompensation(m_handle, enable);
606        }
607
608        /**
609         * Returns the enable state of Voltage Compensation that the caller has set.
610         *
611         * @return TRUE if voltage compensation is enabled.
612         */
613        public boolean isVoltageCompensationEnabled(){
614                return _isVcompEn;
615        }
616
617        // ------ General Status ----------//
618        /**
619         * Gets the bus voltage seen by the device.
620         *
621         * @return The bus voltage value (in volts).
622         */
623        public double getBusVoltage() {
624                return MotControllerJNI.GetBusVoltage(m_handle);
625        }
626
627        /**
628         * Gets the output percentage of the motor controller.
629         *
630         * @return Output of the motor controller (in percent).
631         */
632        public double getMotorOutputPercent() {
633                return MotControllerJNI.GetMotorOutputPercent(m_handle);
634        }
635
636        /**
637         * @return applied voltage to motor  in volts.
638         */
639        public double getMotorOutputVoltage() {
640                return getBusVoltage() * getMotorOutputPercent();
641        }
642
643        /**
644         * Gets the output current of the motor controller.
645         * In the case of TalonSRX class, this routine returns supply current for legacy reasons.  In order to get the "true" output current, call GetStatorCurrent().
646         *
647         * @deprecated Use getStatorCurrent/getSupplyCurrent instead.
648         *
649         * @return The output current (in amps).
650         */
651        @Deprecated
652        protected double getOutputCurrent() {
653                return MotControllerJNI.GetOutputCurrent(m_handle);
654        }
655
656        /**
657         * Gets the temperature of the motor controller.
658         *
659         * @return Temperature of the motor controller (in 'C)
660         */
661        public double getTemperature() {
662                return MotControllerJNI.GetTemperature(m_handle);
663        }
664
665        // ------ sensor selection ----------//
666        /**
667         * Select the remote feedback device for the motor controller.
668         * Most CTRE CAN motor controllers will support remote sensors over CAN.
669         *
670         * @param feedbackDevice
671         *            Remote Feedback Device to select.
672         * @param pidIdx
673         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
674         * @param timeoutMs
675         *            Timeout value in ms. If nonzero, function will wait for
676         *            config success and report an error if it times out.
677         *            If zero, no blocking or checking is performed.
678         * @return Error Code generated by function. 0 indicates no error.
679         */
680        public ErrorCode configSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx, int timeoutMs) {
681                int retval = MotControllerJNI.ConfigSelectedFeedbackSensor(m_handle, feedbackDevice.value, pidIdx, timeoutMs);
682                return ErrorCode.valueOf(retval);
683        }
684        /**
685         * Select the remote feedback device for the motor controller.
686         * Most CTRE CAN motor controllers will support remote sensors over CAN.
687         *
688         * @param feedbackDevice
689         *            Remote Feedback Device to select.
690         * @return Error Code generated by function. 0 indicates no error.
691         */
692        public ErrorCode configSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice) {
693                int pidIdx = 0;
694                int timeoutMs = 0;
695                return configSelectedFeedbackSensor(feedbackDevice, pidIdx, timeoutMs);
696        }
697
698        /**
699         * Select the feedback device for the motor controller.
700         *
701         * @param feedbackDevice
702         *            Feedback Device to select.
703         * @param pidIdx
704         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
705         * @param timeoutMs
706         *            Timeout value in ms. If nonzero, function will wait for
707         *            config success and report an error if it times out.
708         *            If zero, no blocking or checking is performed.
709         * @return Error Code generated by function. 0 indicates no error.
710         */
711        public ErrorCode configSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx, int timeoutMs) {
712                int retval = MotControllerJNI.ConfigSelectedFeedbackSensor(m_handle, feedbackDevice.value, pidIdx, timeoutMs);
713                return ErrorCode.valueOf(retval);
714        }
715        /**
716         * Select the feedback device for the motor controller.
717         *
718         * @param feedbackDevice
719         *            Feedback Device to select.
720         * @return Error Code generated by function. 0 indicates no error.
721         */
722        public ErrorCode configSelectedFeedbackSensor(FeedbackDevice feedbackDevice) {
723                int pidIdx = 0;
724                int timeoutMs = 0;
725                return configSelectedFeedbackSensor(feedbackDevice, pidIdx, timeoutMs);
726        }
727
728        /**
729         * The Feedback Coefficient is a scalar applied to the value of the
730         * feedback sensor.  Useful when you need to scale your sensor values
731         * within the closed-loop calculations.  Default value is 1.
732         *
733         * Selected Feedback Sensor register in firmware is the decoded sensor value
734         * multiplied by the Feedback Coefficient.
735         *
736         * @param coefficient
737         *            Feedback Coefficient value.  Maximum value of 1.
738         *                                              Resolution is 1/(2^16).  Cannot be 0.
739         * @param pidIdx
740         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
741         * @param timeoutMs
742         *            Timeout value in ms. If nonzero, function will wait for
743         *            config success and report an error if it times out.
744         *            If zero, no blocking or checking is performed.
745         * @return Error Code generated by function. 0 indicates no error.
746         */
747        public ErrorCode configSelectedFeedbackCoefficient(double coefficient, int pidIdx, int timeoutMs) {
748          int retval = MotControllerJNI.ConfigSelectedFeedbackCoefficient(m_handle, coefficient, pidIdx, timeoutMs);
749                return ErrorCode.valueOf(retval);
750        }
751        /**
752         * The Feedback Coefficient is a scalar applied to the value of the
753         * feedback sensor.  Useful when you need to scale your sensor values
754         * within the closed-loop calculations.  Default value is 1.
755         *
756         * Selected Feedback Sensor register in firmware is the decoded sensor value
757         * multiplied by the Feedback Coefficient.
758         *
759         * @param coefficient
760         *            Feedback Coefficient value.  Maximum value of 1.
761         *                                              Resolution is 1/(2^16).  Cannot be 0.
762         * @return Error Code generated by function. 0 indicates no error.
763         */
764        public ErrorCode configSelectedFeedbackCoefficient(double coefficient) {
765                int pidIdx = 0;
766        int timeoutMs = 0;
767                return configSelectedFeedbackCoefficient(coefficient, pidIdx, timeoutMs);
768        }
769        /**
770         * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
771         * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
772         * as a PID source for closed-loop features.
773         *
774         * @param deviceID
775         *            The device ID of the remote sensor device.
776         * @param remoteSensorSource
777         *            The remote sensor device and signal type to bind.
778         * @param remoteOrdinal
779         *            0 for configuring Remote Sensor 0,
780         *            1 for configuring Remote Sensor 1
781         * @param timeoutMs
782         *            Timeout value in ms. If nonzero, function will wait for
783         *            config success and report an error if it times out.
784         *            If zero, no blocking or checking is performed.
785         * @return Error Code generated by function. 0 indicates no error.
786         */
787        public ErrorCode configRemoteFeedbackFilter(int deviceID, RemoteSensorSource remoteSensorSource, int remoteOrdinal,
788                        int timeoutMs) {
789                int retval = MotControllerJNI.ConfigRemoteFeedbackFilter(m_handle, deviceID, remoteSensorSource.value, remoteOrdinal,
790                                timeoutMs);
791                return ErrorCode.valueOf(retval);
792        }
793        /**
794         * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
795         * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
796         * as a PID source for closed-loop features.
797         *
798         * @param deviceID
799         *            The device ID of the remote sensor device.
800         * @param remoteSensorSource
801         *            The remote sensor device and signal type to bind.
802         * @param remoteOrdinal
803         *            0 for configuring Remote Sensor 0,
804         *            1 for configuring Remote Sensor 1
805         * @return Error Code generated by function. 0 indicates no error.
806         */
807        public ErrorCode configRemoteFeedbackFilter(int deviceID, RemoteSensorSource remoteSensorSource, int remoteOrdinal) {
808        int timeoutMs = 0;
809                return configRemoteFeedbackFilter(deviceID, remoteSensorSource, remoteOrdinal, timeoutMs);
810        }
811        /**
812         * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
813         * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
814         * as a PID source for closed-loop features.
815         *
816         * @param canCoderRef
817         *            CANCoder device reference to use.
818         * @param remoteOrdinal
819         *            0 for configuring Remote Sensor 0,
820         *            1 for configuring Remote Sensor 1
821         * @param timeoutMs
822         *            Timeout value in ms. If nonzero, function will wait for
823         *            config success and report an error if it times out.
824         *            If zero, no blocking or checking is performed.
825         * @return Error Code generated by function. 0 indicates no error.
826         */
827        public ErrorCode configRemoteFeedbackFilter(CANCoder canCoderRef, int remoteOrdinal, int timeoutMs) {
828                return configRemoteFeedbackFilter(canCoderRef.getDeviceID(), RemoteSensorSource.CANCoder, remoteOrdinal, timeoutMs);
829        }
830        /**
831         * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
832         * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
833         * as a PID source for closed-loop features.
834         *
835         * @param canCoderRef
836         *            CANCoder device reference to use.
837         * @param remoteOrdinal
838         *            0 for configuring Remote Sensor 0,
839         *            1 for configuring Remote Sensor 1
840         * @return Error Code generated by function. 0 indicates no error.
841         */
842        public ErrorCode configRemoteFeedbackFilter(CANCoder canCoderRef, int remoteOrdinal) {
843                int timeoutMs = 0;
844                return configRemoteFeedbackFilter(canCoderRef, remoteOrdinal, timeoutMs);
845        }
846        /**
847         * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
848         * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
849         * as a PID source for closed-loop features.
850         *
851         * @param talonRef
852         *            Talon device reference to use.
853         * @param remoteOrdinal
854         *            0 for configuring Remote Sensor 0,
855         *            1 for configuring Remote Sensor 1
856         * @param timeoutMs
857         *            Timeout value in ms. If nonzero, function will wait for
858         *            config success and report an error if it times out.
859         *            If zero, no blocking or checking is performed.
860         * @return Error Code generated by function. 0 indicates no error.
861         */
862        public ErrorCode configRemoteFeedbackFilter(BaseTalon talonRef, int remoteOrdinal, int timeoutMs) {
863                return configRemoteFeedbackFilter(talonRef.getDeviceID(), RemoteSensorSource.TalonSRX_SelectedSensor, remoteOrdinal, timeoutMs);
864        }
865        /**
866         * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
867         * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
868         * as a PID source for closed-loop features.
869         *
870         * @param talonRef
871         *            Talon device reference to use.
872         * @param remoteOrdinal
873         *            0 for configuring Remote Sensor 0,
874         *            1 for configuring Remote Sensor 1
875         * @return Error Code generated by function. 0 indicates no error.
876         */
877        public ErrorCode configRemoteFeedbackFilter(BaseTalon talonRef, int remoteOrdinal) {
878                int timeoutMs = 0;
879                return configRemoteFeedbackFilter(talonRef, remoteOrdinal, timeoutMs);
880        }
881        /**
882         * Select what sensor term should be bound to switch feedback device.
883         * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
884         * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
885         * The four terms are specified with this routine.  Then Sensor Sum/Difference
886         * can be selected for closed-looping.
887         *
888         * @param sensorTerm Which sensor term to bind to a feedback source.
889         * @param feedbackDevice The sensor signal to attach to sensorTerm.
890         * @param timeoutMs
891         *            Timeout value in ms. If nonzero, function will wait for
892         *            config success and report an error if it times out.
893         *            If zero, no blocking or checking is performed.
894         * @return Error Code generated by function. 0 indicates no error.
895         */
896        public ErrorCode configSensorTerm(SensorTerm sensorTerm, FeedbackDevice feedbackDevice, int timeoutMs) {
897                int retval = MotControllerJNI.ConfigSensorTerm(m_handle, sensorTerm.value, feedbackDevice.value, timeoutMs);
898                return ErrorCode.valueOf(retval);
899        }
900        /**
901         * Select what sensor term should be bound to switch feedback device.
902         * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
903         * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
904         * The four terms are specified with this routine.  Then Sensor Sum/Difference
905         * can be selected for closed-looping.
906         *
907         * @param sensorTerm Which sensor term to bind to a feedback source.
908         * @param feedbackDevice The sensor signal to attach to sensorTerm.
909         * @return Error Code generated by function. 0 indicates no error.
910         */
911        public ErrorCode configSensorTerm(SensorTerm sensorTerm, FeedbackDevice feedbackDevice) {
912                int timeoutMs = 0;
913                return configSensorTerm(sensorTerm, feedbackDevice, timeoutMs);
914        }
915        /**
916         * Select what sensor term should be bound to switch feedback device.
917         * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
918         * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
919         * The four terms are specified with this routine.  Then Sensor Sum/Difference
920         * can be selected for closed-looping.
921         *
922         * @param sensorTerm Which sensor term to bind to a feedback source.
923         * @param feedbackDevice The sensor signal to attach to sensorTerm.
924         * @param timeoutMs
925         *            Timeout value in ms. If nonzero, function will wait for
926         *            config success and report an error if it times out.
927         *            If zero, no blocking or checking is performed.
928         * @return Error Code generated by function. 0 indicates no error.
929         */
930        public ErrorCode configSensorTerm(SensorTerm sensorTerm, RemoteFeedbackDevice feedbackDevice, int timeoutMs) {
931                return configSensorTerm(sensorTerm, feedbackDevice.getFeedbackDevice(), timeoutMs);
932        }
933        /**
934         * Select what sensor term should be bound to switch feedback device.
935         * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
936         * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
937         * The four terms are specified with this routine.  Then Sensor Sum/Difference
938         * can be selected for closed-looping.
939         *
940         * @param sensorTerm Which sensor term to bind to a feedback source.
941         * @param feedbackDevice The sensor signal to attach to sensorTerm.
942         * @return Error Code generated by function. 0 indicates no error.
943         */
944        public ErrorCode configSensorTerm(SensorTerm sensorTerm, RemoteFeedbackDevice feedbackDevice) {
945                int timeoutMs = 0;
946                return configSensorTerm(sensorTerm, feedbackDevice.getFeedbackDevice(), timeoutMs);
947        }
948
949        // ------- sensor status --------- //
950        /**
951         * Get the selected sensor position (in raw sensor units).
952         *
953         * @param pidIdx
954         *            0 for Primary closed-loop. 1 for auxiliary closed-loop. See
955         *            Phoenix-Documentation for how to interpret.
956         *
957         * @return Position of selected sensor (in raw sensor units).
958         */
959        public double getSelectedSensorPosition(int pidIdx) {
960                return (double)MotControllerJNI.GetSelectedSensorPosition(m_handle, pidIdx);
961        }
962        /**
963         * Get the selected sensor position (in raw sensor units).
964         *
965         * @return Position of selected sensor (in raw sensor units).
966         */
967        public double getSelectedSensorPosition() {
968                int pidIdx = 0;
969                return getSelectedSensorPosition(pidIdx);
970        }
971
972        /**
973         * Get the selected sensor velocity.
974         *
975         * @param pidIdx
976         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
977         * @return selected sensor (in raw sensor units) per 100ms.
978         * See Phoenix-Documentation for how to interpret.
979         */
980        public double getSelectedSensorVelocity(int pidIdx) {
981                return (double)MotControllerJNI.GetSelectedSensorVelocity(m_handle, pidIdx);
982        }
983        /**
984         * Get the selected sensor velocity.
985         *
986         * @return selected sensor (in raw sensor units) per 100ms.
987         * See Phoenix-Documentation for how to interpret.
988         */
989        public double getSelectedSensorVelocity() {
990                int pidIdx = 0;
991                return getSelectedSensorVelocity(pidIdx);
992        }
993
994        /**
995         * Sets the sensor position to the given value.
996         *
997         * @param sensorPos
998         *            Position to set for the selected sensor (in raw sensor units).
999         * @param pidIdx
1000         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
1001         * @param timeoutMs
1002         *            Timeout value in ms. If nonzero, function will wait for
1003         *            config success and report an error if it times out.
1004         *            If zero, no blocking or checking is performed.
1005         * @return Error Code generated by function. 0 indicates no error.
1006         */
1007        public ErrorCode setSelectedSensorPosition(double sensorPos, int pidIdx, int timeoutMs) {
1008                int retval = MotControllerJNI.SetSelectedSensorPosition(m_handle, (int)sensorPos, pidIdx, timeoutMs);
1009                return ErrorCode.valueOf(retval);
1010        }
1011        /**
1012         * Sets the sensor position to the given value.
1013         *
1014         * @param sensorPos
1015         *            Position to set for the selected sensor (in raw sensor units).
1016         * @return Error Code generated by function. 0 indicates no error.
1017         */
1018        public ErrorCode setSelectedSensorPosition(double sensorPos) {
1019                int pidIdx = 0;
1020                int timeoutMs = 0;
1021                return setSelectedSensorPosition(sensorPos, pidIdx, timeoutMs);
1022        }
1023
1024        // ------ status frame period changes ----------//
1025        /**
1026         * Sets the period of the given control frame.
1027         *
1028         * @param frame
1029         *            Frame whose period is to be changed.
1030         * @param periodMs
1031         *            Period in ms for the given frame.
1032         * @return Error Code generated by function. 0 indicates no error.
1033         */
1034        public ErrorCode setControlFramePeriod(ControlFrame frame, int periodMs) {
1035                int retval = MotControllerJNI.SetControlFramePeriod(m_handle, frame.value, periodMs);
1036                return ErrorCode.valueOf(retval);
1037        }
1038
1039        /**
1040         * Sets the period of the given status frame.
1041         *
1042         * User ensure CAN Bus utilization is not high.
1043         *
1044         * This setting is not persistent and is lost when device is reset.
1045         * If this is a concern, calling application can use hasResetOccurred()
1046         * to determine if the status frame needs to be reconfigured.
1047         *
1048         * @param frame
1049         *            Frame whose period is to be changed.
1050         * @param periodMs
1051         *            Period in ms for the given frame.
1052         * @return Error Code generated by function. 0 indicates no error.
1053         */
1054        public ErrorCode setControlFramePeriod(int frame, int periodMs) {
1055                int retval = MotControllerJNI.SetControlFramePeriod(m_handle, frame, periodMs);
1056                return ErrorCode.valueOf(retval);
1057        }
1058
1059        /**
1060         * Sets the period of the given status frame.
1061         *
1062         * User ensure CAN Bus utilization is not high.
1063         *
1064         * This setting is not persistent and is lost when device is reset. If this
1065         * is a concern, calling application can use hasResetOccurred() to determine if the
1066         * status frame needs to be reconfigured.
1067         *
1068         * @param frameValue
1069         *            Frame whose period is to be changed.
1070         * @param periodMs
1071         *            Period in ms for the given frame.
1072         * @param timeoutMs
1073         *            Timeout value in ms. If nonzero, function will wait for config
1074         *            success and report an error if it times out. If zero, no
1075         *            blocking or checking is performed.
1076         * @return Error Code generated by function. 0 indicates no error.
1077         */
1078        public ErrorCode setStatusFramePeriod(int frameValue, int periodMs, int timeoutMs) {
1079                int retval = MotControllerJNI.SetStatusFramePeriod(m_handle, frameValue, periodMs, timeoutMs);
1080                return ErrorCode.valueOf(retval);
1081        }
1082        /**
1083         * Sets the period of the given status frame.
1084         *
1085         * User ensure CAN Bus utilization is not high.
1086         *
1087         * This setting is not persistent and is lost when device is reset. If this
1088         * is a concern, calling application can use hasResetOccurred() to determine if the
1089         * status frame needs to be reconfigured.
1090         *
1091         * @param frameValue
1092         *            Frame whose period is to be changed.
1093         * @param periodMs
1094         *            Period in ms for the given frame.
1095         * @return Error Code generated by function. 0 indicates no error.
1096         */
1097        public ErrorCode setStatusFramePeriod(int frameValue, int periodMs) {
1098                int timeoutMs = 0;
1099                return  setStatusFramePeriod(frameValue, periodMs,timeoutMs);
1100        }
1101
1102        /**
1103         * Sets the period of the given status frame.
1104         *
1105         * @param frame
1106         *            Frame whose period is to be changed.
1107         * @param periodMs
1108         *            Period in ms for the given frame.
1109         * @param timeoutMs
1110         *            Timeout value in ms. If nonzero, function will wait for
1111         *            config success and report an error if it times out.
1112         *            If zero, no blocking or checking is performed.
1113         * @return Error Code generated by function. 0 indicates no error.
1114         */
1115        public ErrorCode setStatusFramePeriod(StatusFrame frame, int periodMs, int timeoutMs) {
1116                return setStatusFramePeriod(frame.value, periodMs, timeoutMs);
1117        }
1118        /**
1119         * Sets the period of the given status frame.
1120         *
1121         * @param frame
1122         *            Frame whose period is to be changed.
1123         * @param periodMs
1124         *            Period in ms for the given frame.
1125         * @return Error Code generated by function. 0 indicates no error.
1126         */
1127        public ErrorCode setStatusFramePeriod(StatusFrame frame, int periodMs) {
1128                int timeoutMs = 0;
1129                return setStatusFramePeriod(frame,periodMs, timeoutMs);
1130        }
1131
1132        /**
1133         * Gets the period of the given status frame.
1134         *
1135         * @param frame
1136         *            Frame to get the period of.
1137         * @param timeoutMs
1138         *            Timeout value in ms. If nonzero, function will wait for
1139         *            config success and report an error if it times out.
1140         *            If zero, no blocking or checking is performed.
1141         * @return Period of the given status frame.
1142         */
1143        public int getStatusFramePeriod(int frame, int timeoutMs) {
1144                return MotControllerJNI.GetStatusFramePeriod(m_handle, frame, timeoutMs);
1145        }
1146        /**
1147         * Gets the period of the given status frame.
1148         *
1149         * @param frame
1150         *            Frame to get the period of.
1151         * @return Period of the given status frame.
1152         */
1153        public int getStatusFramePeriod(int frame) {
1154                int timeoutMs = 0;
1155                return getStatusFramePeriod(frame, timeoutMs);
1156        }
1157
1158        /**
1159         * Gets the period of the given status frame.
1160         *
1161         * @param frame
1162         *            Frame to get the period of.
1163         * @param timeoutMs
1164         *            Timeout value in ms. If nonzero, function will wait for
1165         *            config success and report an error if it times out.
1166         *            If zero, no blocking or checking is performed.
1167         * @return Period of the given status frame.
1168         */
1169        public int getStatusFramePeriod(StatusFrame frame, int timeoutMs) {
1170                return MotControllerJNI.GetStatusFramePeriod(m_handle, frame.value, timeoutMs);
1171        }
1172        /**
1173         * Gets the period of the given status frame.
1174         *
1175         * @param frame
1176         *            Frame to get the period of.
1177         * @return Period of the given status frame.
1178         */
1179        public int getStatusFramePeriod(StatusFrame frame) {
1180                int timeoutMs = 0;
1181                return getStatusFramePeriod(frame, timeoutMs);
1182        }
1183
1184        /**
1185         * Gets the period of the given status frame.
1186         *
1187         * @param frame
1188         *            Frame to get the period of.
1189         * @param timeoutMs
1190         *            Timeout value in ms. If nonzero, function will wait for
1191         *            config success and report an error if it times out.
1192         *            If zero, no blocking or checking is performed.
1193         * @return Period of the given status frame.
1194         */
1195        public int getStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs) {
1196                return MotControllerJNI.GetStatusFramePeriod(m_handle, frame.value, timeoutMs);
1197        }
1198        /**
1199         * Gets the period of the given status frame.
1200         *
1201         * @param frame
1202         *            Frame to get the period of.
1203         * @return Period of the given status frame.
1204         */
1205        public int getStatusFramePeriod(StatusFrameEnhanced frame) {
1206                int timeoutMs = 0;
1207                return  getStatusFramePeriod(frame, timeoutMs);
1208        }
1209
1210        // ----- velocity signal conditionaing ------//
1211
1212        /**
1213         * Sets the period over which velocity measurements are taken.
1214         *
1215         * @param period
1216         *            Desired period for the velocity measurement. @see
1217         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
1218         * @param timeoutMs
1219         *            Timeout value in ms. If nonzero, function will wait for
1220         *            config success and report an error if it times out.
1221         *            If zero, no blocking or checking is performed.
1222         * @return Error Code generated by function. 0 indicates no error.
1223         */
1224        public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs) {
1225                int retval = MotControllerJNI.ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs);
1226                return ErrorCode.valueOf(retval);
1227        }
1228        /**
1229         * Sets the period over which velocity measurements are taken.
1230         *
1231         * @deprecated Use the overload with SensorVelocityMeasPeriod instead.
1232         *
1233         * @param period
1234         *            Desired period for the velocity measurement. @see
1235         *            com.ctre.phoenix.motorcontrol.VelocityMeasPeriod
1236         * @param timeoutMs
1237         *            Timeout value in ms. If nonzero, function will wait for
1238         *            config success and report an error if it times out.
1239         *            If zero, no blocking or checking is performed.
1240         * @return Error Code generated by function. 0 indicates no error.
1241         */
1242        @Deprecated
1243        public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs) {
1244                int retval = MotControllerJNI.ConfigVelocityMeasurementPeriod(m_handle, period.value, timeoutMs);
1245                return ErrorCode.valueOf(retval);
1246        }
1247        /**
1248         * Sets the period over which velocity measurements are taken.
1249         *
1250         * @param period
1251         *            Desired period for the velocity measurement. @see
1252         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
1253         * @return Error Code generated by function. 0 indicates no error.
1254         */
1255        public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period) {
1256                int timeoutMs = 0;
1257                return configVelocityMeasurementPeriod(period, timeoutMs);
1258        }
1259        /**
1260         * Sets the period over which velocity measurements are taken.
1261         *
1262         * @deprecated Use the overload with SensorVelocityMeasPeriod instead.
1263         *
1264         * @param period
1265         *            Desired period for the velocity measurement. @see
1266         *            com.ctre.phoenix.motorcontrol.VelocityMeasPeriod
1267         * @return Error Code generated by function. 0 indicates no error.
1268         */
1269        @Deprecated
1270        public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period) {
1271                int timeoutMs = 0;
1272                return configVelocityMeasurementPeriod(period, timeoutMs);
1273        }
1274
1275        /**
1276         * Sets the number of velocity samples used in the rolling average velocity
1277         * measurement.
1278         *
1279         * @param windowSize
1280         *            Number of samples in the rolling average of velocity
1281         *            measurement. Valid values are 1,2,4,8,16,32. If another value
1282         *            is specified, it will truncate to nearest support value.
1283         * @param timeoutMs
1284         *            Timeout value in ms. If nonzero, function will wait for config
1285         *            success and report an error if it times out. If zero, no
1286         *            blocking or checking is performed.
1287         * @return Error Code generated by function. 0 indicates no error.
1288         */
1289        public ErrorCode configVelocityMeasurementWindow(int windowSize, int timeoutMs) {
1290                int retval = MotControllerJNI.ConfigVelocityMeasurementWindow(m_handle, windowSize, timeoutMs);
1291                return ErrorCode.valueOf(retval);
1292        }
1293        /**
1294         * Sets the number of velocity samples used in the rolling average velocity
1295         * measurement.
1296         *
1297         * @param windowSize
1298         *            Number of samples in the rolling average of velocity
1299         *            measurement. Valid values are 1,2,4,8,16,32. If another value
1300         *            is specified, it will truncate to nearest support value.
1301         * @return Error Code generated by function. 0 indicates no error.
1302         */
1303        public ErrorCode configVelocityMeasurementWindow(int windowSize) {
1304                int timeoutMs = 0;
1305                return configVelocityMeasurementWindow(windowSize, timeoutMs);
1306        }
1307
1308        // ------ remote limit switch ----------//
1309        /**
1310         * Configures the forward limit switch for a remote source. For example, a
1311         * CAN motor controller may need to monitor the Limit-F pin of another Talon
1312         * or CANifier.
1313         *
1314         * @param type
1315         *            Remote limit switch source. User can choose between a remote
1316         *            Talon SRX, CANifier, or deactivate the feature.
1317         * @param normalOpenOrClose
1318         *            Setting for normally open, normally closed, or disabled. This
1319         *            setting matches the Phoenix Tuner drop down.
1320         * @param deviceID
1321         *            Device ID of remote source (Talon SRX or CANifier device ID).
1322         * @param timeoutMs
1323         *            Timeout value in ms. If nonzero, function will wait for config
1324         *            success and report an error if it times out. If zero, no
1325         *            blocking or checking is performed.
1326         * @return Error Code generated by function. 0 indicates no error.
1327         */
1328        public ErrorCode configForwardLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1329                        int deviceID, int timeoutMs) {
1330                return configForwardLimitSwitchSource(type.value, normalOpenOrClose.value, deviceID, timeoutMs);
1331        }
1332        /**
1333         * Configures the forward limit switch for a remote source. For example, a
1334         * CAN motor controller may need to monitor the Limit-F pin of another Talon
1335         * or CANifier.
1336         *
1337         * @param type
1338         *            Remote limit switch source. User can choose between a remote
1339         *            Talon SRX, CANifier, or deactivate the feature.
1340         * @param normalOpenOrClose
1341         *            Setting for normally open, normally closed, or disabled. This
1342         *            setting matches the Phoenix Tuner drop down.
1343         * @param deviceID
1344         *            Device ID of remote source (Talon SRX or CANifier device ID).
1345         * @return Error Code generated by function. 0 indicates no error.
1346         */
1347        public ErrorCode configForwardLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1348                        int deviceID) {
1349                int timeoutMs = 0;
1350                return configForwardLimitSwitchSource(type, normalOpenOrClose, deviceID, timeoutMs);
1351        }
1352
1353        /**
1354         * Configures the reverse limit switch for a remote source. For example, a
1355         * CAN motor controller may need to monitor the Limit-R pin of another Talon
1356         * or CANifier.
1357         *
1358         * @param type
1359         *            Remote limit switch source. User can choose between a remote
1360         *            Talon SRX, CANifier, or deactivate the feature.
1361         * @param normalOpenOrClose
1362         *            Setting for normally open, normally closed, or disabled. This
1363         *            setting matches the Phoenix Tuner drop down.
1364         * @param deviceID
1365         *            Device ID of remote source (Talon SRX or CANifier device ID).
1366         * @param timeoutMs
1367         *            Timeout value in ms. If nonzero, function will wait for config
1368         *            success and report an error if it times out. If zero, no
1369         *            blocking or checking is performed.
1370         * @return Error Code generated by function. 0 indicates no error.
1371         */
1372        public ErrorCode configReverseLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1373                        int deviceID, int timeoutMs) {
1374                int retval = MotControllerJNI.ConfigReverseLimitSwitchSource(m_handle, type.value, normalOpenOrClose.value,
1375                                deviceID, timeoutMs);
1376                return ErrorCode.valueOf(retval);
1377        }
1378        /**
1379         * Configures the reverse limit switch for a remote source. For example, a
1380         * CAN motor controller may need to monitor the Limit-R pin of another Talon
1381         * or CANifier.
1382         *
1383         * @param type
1384         *            Remote limit switch source. User can choose between a remote
1385         *            Talon SRX, CANifier, or deactivate the feature.
1386         * @param normalOpenOrClose
1387         *            Setting for normally open, normally closed, or disabled. This
1388         *            setting matches the Phoenix Tuner drop down.
1389         * @param deviceID
1390         *            Device ID of remote source (Talon SRX or CANifier device ID).
1391         * @return Error Code generated by function. 0 indicates no error.
1392         */
1393        public ErrorCode configReverseLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1394                        int deviceID) {
1395                int timeoutMs = 0;
1396                return configReverseLimitSwitchSource(type, normalOpenOrClose, deviceID, timeoutMs);
1397        }
1398
1399        /**
1400         * Configures a limit switch for a local/remote source.
1401         *
1402         * For example, a CAN motor controller may need to monitor the Limit-R pin
1403         * of another Talon, CANifier, or local Gadgeteer feedback connector.
1404         *
1405         * If the sensor is remote, a device ID of zero is assumed. If that's not
1406         * desired, use the four parameter version of this function.
1407         *
1408         * @param type
1409         *            Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose
1410         *            between the feedback connector, remote Talon SRX, CANifier, or
1411         *            deactivate the feature.
1412         * @param normalOpenOrClose
1413         *            Setting for normally open, normally closed, or disabled. This
1414         *            setting matches the Phoenix Tuner drop down.
1415         * @param timeoutMs
1416         *            Timeout value in ms. If nonzero, function will wait for config
1417         *            success and report an error if it times out. If zero, no
1418         *            blocking or checking is performed.
1419         * @return Error Code generated by function. 0 indicates no error.
1420         */
1421        public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1422                        int timeoutMs) {
1423                return configForwardLimitSwitchSource(type.value, normalOpenOrClose.value, -1, timeoutMs);
1424        }
1425        /**
1426         * Configures a limit switch for a local/remote source.
1427         *
1428         * For example, a CAN motor controller may need to monitor the Limit-R pin
1429         * of another Talon, CANifier, or local Gadgeteer feedback connector.
1430         *
1431         * If the sensor is remote, a device ID of zero is assumed. If that's not
1432         * desired, use the four parameter version of this function.
1433         *
1434         * @param type
1435         *            Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose
1436         *            between the feedback connector, remote Talon SRX, CANifier, or
1437         *            deactivate the feature.
1438         * @param normalOpenOrClose
1439         *            Setting for normally open, normally closed, or disabled. This
1440         *            setting matches the Phoenix Tuner drop down.
1441         * @return Error Code generated by function. 0 indicates no error.
1442         */
1443        public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose) {
1444                int timeoutMs = 0;
1445                return configForwardLimitSwitchSource(type, normalOpenOrClose, timeoutMs);
1446        }
1447
1448        /**
1449         * Configures a limit switch for a local/remote source.
1450         *
1451         * For example, a CAN motor controller may need to monitor the Limit-R pin
1452         * of another Talon, CANifier, or local Gadgeteer feedback connector.
1453         *
1454         * If the sensor is remote, a device ID of zero is assumed. If that's not
1455         * desired, use the four parameter version of this function.
1456         *
1457         * @param typeValue
1458         *            Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose
1459         *            between the feedback connector, remote Talon SRX, CANifier, or
1460         *            deactivate the feature.
1461         * @param normalOpenOrCloseValue
1462         *            Setting for normally open, normally closed, or disabled. This
1463         *            setting matches the Phoenix Tuner drop down.
1464         * @param deviceID
1465         *            Device ID of remote source (Talon SRX or CANifier device ID).
1466         * @param timeoutMs
1467         *            Timeout value in ms. If nonzero, function will wait for config
1468         *            success and report an error if it times out. If zero, no
1469         *            blocking or checking is performed.
1470         * @return Error Code generated by function. 0 indicates no error.
1471         */
1472        protected ErrorCode configForwardLimitSwitchSource(int typeValue, int normalOpenOrCloseValue, int deviceID,
1473                        int timeoutMs) {
1474                int retval = MotControllerJNI.ConfigForwardLimitSwitchSource(m_handle, typeValue, normalOpenOrCloseValue,
1475                                deviceID, timeoutMs);
1476                return ErrorCode.valueOf(retval);
1477        }
1478
1479        /**
1480         * Configures a limit switch for a local/remote source.
1481         *
1482         * For example, a CAN motor controller may need to monitor the Limit-R pin
1483         * of another Talon, CANifier, or local Gadgeteer feedback connector.
1484         *
1485         * If the sensor is remote, a device ID of zero is assumed. If that's not
1486         * desired, use the four parameter version of this function.
1487         *
1488         * @param typeValue
1489         *            Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose
1490         *            between the feedback connector, remote Talon SRX, CANifier, or
1491         *            deactivate the feature.
1492         * @param normalOpenOrCloseValue
1493         *            Setting for normally open, normally closed, or disabled. This
1494         *            setting matches the Phoenix Tuner drop down.
1495         * @param deviceID
1496         *            The device ID of the remote sensor device.
1497         * @param timeoutMs
1498         *            Timeout value in ms. If nonzero, function will wait for config
1499         *            success and report an error if it times out. If zero, no
1500         *            blocking or checking is performed.
1501         * @return Error Code generated by function. 0 indicates no error.
1502         */
1503        protected ErrorCode configReverseLimitSwitchSource(int typeValue, int normalOpenOrCloseValue, int deviceID,
1504                        int timeoutMs) {
1505                int retval = MotControllerJNI.ConfigReverseLimitSwitchSource(m_handle, typeValue, normalOpenOrCloseValue,
1506                                deviceID, timeoutMs);
1507                return ErrorCode.valueOf(retval);
1508        }
1509
1510        /**
1511         * Sets the enable state for limit switches.
1512         *
1513         * @param enable
1514         *            Enable state for limit switches.
1515         **/
1516        public void overrideLimitSwitchesEnable(boolean enable) {
1517                MotControllerJNI.OverrideLimitSwitchesEnable(m_handle, enable);
1518        }
1519
1520        // ------ soft limit ----------//
1521        /**
1522         * Configures the forward soft limit threhold.
1523         *
1524         * @param forwardSensorLimit
1525         *            Forward Sensor Position Limit (in raw sensor units).
1526         * @param timeoutMs
1527         *            Timeout value in ms. If nonzero, function will wait for
1528         *            config success and report an error if it times out.
1529         *            If zero, no blocking or checking is performed.
1530         * @return Error Code generated by function. 0 indicates no error.
1531         */
1532        public ErrorCode configForwardSoftLimitThreshold(double forwardSensorLimit, int timeoutMs) {
1533                int retval = MotControllerJNI.ConfigForwardSoftLimitThreshold(m_handle, (int)forwardSensorLimit, timeoutMs);
1534                return ErrorCode.valueOf(retval);
1535        }
1536        /**
1537         * Configures the forward soft limit threhold.
1538         *
1539         * @param forwardSensorLimit
1540         *            Forward Sensor Position Limit (in raw sensor units).
1541         * @return Error Code generated by function. 0 indicates no error.
1542         */
1543        public ErrorCode configForwardSoftLimitThreshold(double forwardSensorLimit) {
1544                int timeoutMs = 0;
1545                return configForwardSoftLimitThreshold(forwardSensorLimit, timeoutMs);
1546        }
1547
1548        /**
1549         * Configures the reverse soft limit threshold.
1550         *
1551         * @param reverseSensorLimit
1552         *            Reverse Sensor Position Limit (in raw sensor units).
1553         * @param timeoutMs
1554         *            Timeout value in ms. If nonzero, function will wait for
1555         *            config success and report an error if it times out.
1556         *            If zero, no blocking or checking is performed.
1557         * @return Error Code generated by function. 0 indicates no error.
1558         */
1559        public ErrorCode configReverseSoftLimitThreshold(double reverseSensorLimit, int timeoutMs) {
1560                int retval = MotControllerJNI.ConfigReverseSoftLimitThreshold(m_handle, (int)reverseSensorLimit, timeoutMs);
1561                return ErrorCode.valueOf(retval);
1562        }
1563        /**
1564         * Configures the reverse soft limit threshold.
1565         *
1566         * @param reverseSensorLimit
1567         *            Reverse Sensor Position Limit (in raw sensor units).
1568         * @return Error Code generated by function. 0 indicates no error.
1569         */
1570        public ErrorCode configReverseSoftLimitThreshold(double reverseSensorLimit) {
1571                int timeoutMs = 0;
1572                return configReverseSoftLimitThreshold(reverseSensorLimit, timeoutMs);
1573        }
1574
1575        /**
1576         * Configures the forward soft limit enable.
1577         *
1578         * @param enable
1579         *            Forward Sensor Position Limit Enable.
1580         * @param timeoutMs
1581         *            Timeout value in ms. If nonzero, function will wait for
1582         *            config success and report an error if it times out.
1583         *            If zero, no blocking or checking is performed.
1584         * @return Error Code generated by function. 0 indicates no error.
1585         */
1586        public ErrorCode configForwardSoftLimitEnable(boolean enable, int timeoutMs) {
1587                int retval = MotControllerJNI.ConfigForwardSoftLimitEnable(m_handle, enable, timeoutMs);
1588                return ErrorCode.valueOf(retval);
1589        }
1590        /**
1591         * Configures the forward soft limit enable.
1592         *
1593         * @param enable
1594         *            Forward Sensor Position Limit Enable.
1595         * @return Error Code generated by function. 0 indicates no error.
1596         */
1597        public ErrorCode configForwardSoftLimitEnable(boolean enable) {
1598                int timeoutMs = 0;
1599                return configForwardSoftLimitEnable(enable, timeoutMs);
1600        }
1601
1602        /**
1603         * Configures the reverse soft limit enable.
1604         *
1605         * @param enable
1606         *            Reverse Sensor Position Limit Enable.
1607         * @param timeoutMs
1608         *            Timeout value in ms. If nonzero, function will wait for config
1609         *            success and report an error if it times out. If zero, no
1610         *            blocking or checking is performed.
1611         * @return Error Code generated by function. 0 indicates no error.
1612         */
1613        public ErrorCode configReverseSoftLimitEnable(boolean enable, int timeoutMs) {
1614                int retval = MotControllerJNI.ConfigReverseSoftLimitEnable(m_handle, enable, timeoutMs);
1615                return ErrorCode.valueOf(retval);
1616        }
1617        /**
1618         * Configures the reverse soft limit enable.
1619         *
1620         * @param enable
1621         *            Reverse Sensor Position Limit Enable.
1622         * @return Error Code generated by function. 0 indicates no error.
1623         */
1624        public ErrorCode configReverseSoftLimitEnable(boolean enable) {
1625                int timeoutMs = 0;
1626                return configReverseSoftLimitEnable(enable, timeoutMs);
1627        }
1628
1629        /**
1630         * Can be used to override-disable the soft limits.
1631         * This function can be used to quickly disable soft limits without
1632         * having to modify the persistent configuration.
1633         *
1634         * @param enable
1635         *            Enable state for soft limit switches.
1636         */
1637        public void overrideSoftLimitsEnable(boolean enable) {
1638                MotControllerJNI.OverrideSoftLimitsEnable(m_handle, enable);
1639        }
1640
1641        // ------ Current Lim ----------//
1642        /* not available in base */
1643
1644        // ------ General Close loop ----------//
1645        /**
1646         * Sets the 'P' constant in the given parameter slot.
1647         * This is multiplied by closed loop error in sensor units.
1648         * Note the closed loop output interprets a final value of 1023 as full output.
1649         * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation)
1650         *
1651         * @param slotIdx
1652         *            Parameter slot for the constant.
1653         * @param value
1654         *            Value of the P constant.
1655         * @param timeoutMs
1656         *            Timeout value in ms. If nonzero, function will wait for
1657         *            config success and report an error if it times out.
1658         *            If zero, no blocking or checking is performed.
1659         * @return Error Code generated by function. 0 indicates no error.
1660         */
1661        public ErrorCode config_kP(int slotIdx, double value, int timeoutMs) {
1662                int retval = MotControllerJNI.Config_kP(m_handle, slotIdx,  value, timeoutMs);
1663                return ErrorCode.valueOf(retval);
1664        }
1665        /**
1666         * Sets the 'P' constant in the given parameter slot.
1667         * This is multiplied by closed loop error in sensor units.
1668         * Note the closed loop output interprets a final value of 1023 as full output.
1669         * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation)
1670         *
1671         * @param slotIdx
1672         *            Parameter slot for the constant.
1673         * @param value
1674         *            Value of the P constant.
1675         * @return Error Code generated by function. 0 indicates no error.
1676         */
1677        public ErrorCode config_kP(int slotIdx, double value) {
1678                int timeoutMs = 0;
1679                return config_kP( slotIdx,  value,  timeoutMs);
1680        }
1681
1682        /**
1683         * Sets the 'I' constant in the given parameter slot.
1684         * This is multiplied by accumulated closed loop error in sensor units every PID Loop.
1685         * Note the closed loop output interprets a final value of 1023 as full output.
1686         * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000),
1687         * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].
1688         *
1689         * @param slotIdx
1690         *            Parameter slot for the constant.
1691         * @param value
1692         *            Value of the I constant.
1693         * @param timeoutMs
1694         *            Timeout value in ms. If nonzero, function will wait for
1695         *            config success and report an error if it times out.
1696         *            If zero, no blocking or checking is performed.
1697         * @return Error Code generated by function. 0 indicates no error.
1698         */
1699        public ErrorCode config_kI(int slotIdx, double value, int timeoutMs) {
1700                int retval = MotControllerJNI.Config_kI(m_handle, slotIdx,  value, timeoutMs);
1701                return ErrorCode.valueOf(retval);
1702        }
1703        /**
1704         * Sets the 'I' constant in the given parameter slot.
1705         * This is multiplied by accumulated closed loop error in sensor units every PID Loop.
1706         * Note the closed loop output interprets a final value of 1023 as full output.
1707         * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000),
1708         * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].
1709         *
1710         * @param slotIdx
1711         *            Parameter slot for the constant.
1712         * @param value
1713         *            Value of the I constant.
1714         * @return Error Code generated by function. 0 indicates no error.
1715         */
1716        public ErrorCode config_kI(int slotIdx, double value) {
1717        int timeoutMs = 0;
1718
1719                return config_kI( slotIdx,  value,  timeoutMs);
1720        }
1721
1722        /**
1723         * Sets the 'D' constant in the given parameter slot.
1724         *
1725         * This is multiplied by derivative error (sensor units per PID loop, typically 1ms).
1726         * Note the closed loop output interprets a final value of 1023 as full output.
1727         * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)
1728         *
1729         * @param slotIdx
1730         *            Parameter slot for the constant.
1731         * @param value
1732         *            Value of the D constant.
1733         * @param timeoutMs
1734         *            Timeout value in ms. If nonzero, function will wait for
1735         *            config success and report an error if it times out.
1736         *            If zero, no blocking or checking is performed.
1737         * @return Error Code generated by function. 0 indicates no error.
1738         */
1739        public ErrorCode config_kD(int slotIdx, double value, int timeoutMs) {
1740                int retval = MotControllerJNI.Config_kD(m_handle, slotIdx,  value, timeoutMs);
1741                return ErrorCode.valueOf(retval);
1742        }
1743        /**
1744         * Sets the 'D' constant in the given parameter slot.
1745         *
1746         * This is multiplied by derivative error (sensor units per PID loop, typically 1ms).
1747         * Note the closed loop output interprets a final value of 1023 as full output.
1748         * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)
1749         *
1750         * @param slotIdx
1751         *            Parameter slot for the constant.
1752         * @param value
1753         *            Value of the D constant.
1754         * @return Error Code generated by function. 0 indicates no error.
1755         */
1756        public ErrorCode config_kD(int slotIdx, double value) {
1757        int timeoutMs = 0;
1758                return config_kD( slotIdx,  value,  timeoutMs);
1759        }
1760
1761        /**
1762         * Sets the 'F' constant in the given parameter slot.
1763         *
1764         * See documentation for calculation details.
1765         * If using velocity, motion magic, or motion profile,
1766         * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).
1767         *
1768         * @param slotIdx
1769         *            Parameter slot for the constant.
1770         * @param value
1771         *            Value of the F constant.
1772         * @param timeoutMs
1773         *            Timeout value in ms. If nonzero, function will wait for
1774         *            config success and report an error if it times out.
1775         *            If zero, no blocking or checking is performed.
1776         * @return Error Code generated by function. 0 indicates no error.
1777         */
1778        public ErrorCode config_kF(int slotIdx, double value, int timeoutMs) {
1779                int retval = MotControllerJNI.Config_kF(m_handle, slotIdx,  value, timeoutMs);
1780                return ErrorCode.valueOf(retval);
1781        }
1782        /**
1783         * Sets the 'F' constant in the given parameter slot.
1784         *
1785         * See documentation for calculation details.
1786         * If using velocity, motion magic, or motion profile,
1787         * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).
1788         *
1789         * @param slotIdx
1790         *            Parameter slot for the constant.
1791         * @param value
1792         *            Value of the F constant.
1793         * @return Error Code generated by function. 0 indicates no error.
1794         */
1795        public ErrorCode config_kF(int slotIdx,  double value) {
1796        int timeoutMs = 0;
1797                return config_kF( slotIdx,  value,  timeoutMs);
1798        }
1799
1800        /**
1801         * Sets the Integral Zone constant in the given parameter slot. If the
1802         * (absolute) closed-loop error is outside of this zone, integral
1803         * accumulator is automatically cleared. This ensures than integral wind up
1804         * events will stop after the sensor gets far enough from its target.
1805         *
1806         * @param slotIdx
1807         *            Parameter slot for the constant.
1808         * @param izone
1809         *            Value of the Integral Zone constant (closed loop error units X
1810         *            1ms).
1811         * @param timeoutMs
1812         *            Timeout value in ms. If nonzero, function will wait for config
1813         *            success and report an error if it times out. If zero, no
1814         *            blocking or checking is performed.
1815         * @return Error Code generated by function. 0 indicates no error.
1816         */
1817        public ErrorCode config_IntegralZone(int slotIdx, double izone, int timeoutMs) {
1818                int retval = MotControllerJNI.Config_IntegralZone(m_handle, slotIdx,  (int)izone, timeoutMs);
1819                return ErrorCode.valueOf(retval);
1820        }
1821        /**
1822         * Sets the Integral Zone constant in the given parameter slot. If the
1823         * (absolute) closed-loop error is outside of this zone, integral
1824         * accumulator is automatically cleared. This ensures than integral wind up
1825         * events will stop after the sensor gets far enough from its target.
1826         *
1827         * @param slotIdx
1828         *            Parameter slot for the constant.
1829         * @param izone
1830         *            Value of the Integral Zone constant (closed loop error units X
1831         *            1ms).
1832         * @return Error Code generated by function. 0 indicates no error.
1833         */
1834        public ErrorCode config_IntegralZone(int slotIdx, double izone) {
1835        int timeoutMs = 0;
1836                return config_IntegralZone( slotIdx,  izone,  timeoutMs);
1837        }
1838
1839        /**
1840         * Sets the allowable closed-loop error in the given parameter slot.
1841         *
1842         * @param slotIdx
1843         *            Parameter slot for the constant.
1844         * @param allowableClosedLoopError
1845         *            Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity).
1846         * @param timeoutMs
1847         *            Timeout value in ms. If nonzero, function will wait for
1848         *            config success and report an error if it times out.
1849         *            If zero, no blocking or checking is performed.
1850         * @return Error Code generated by function. 0 indicates no error.
1851         */
1852        public ErrorCode configAllowableClosedloopError(int slotIdx, double allowableClosedLoopError, int timeoutMs) {
1853                int retval = MotControllerJNI.ConfigAllowableClosedloopError(m_handle, slotIdx, (int)allowableClosedLoopError,
1854                                timeoutMs);
1855                return ErrorCode.valueOf(retval);
1856        }
1857        /**
1858         * Sets the allowable closed-loop error in the given parameter slot.
1859         *
1860         * @param slotIdx
1861         *            Parameter slot for the constant.
1862         * @param allowableClosedLoopError
1863         *            Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity).
1864         * @return Error Code generated by function. 0 indicates no error.
1865         */
1866        public ErrorCode configAllowableClosedloopError(int slotIdx, double allowableClosedLoopError) {
1867        int timeoutMs = 0;
1868
1869                return configAllowableClosedloopError( slotIdx,  allowableClosedLoopError,  timeoutMs);
1870        }
1871
1872        /**
1873         * Sets the maximum integral accumulator in the given parameter slot.
1874         *
1875         * @param slotIdx
1876         *            Parameter slot for the constant.
1877         * @param iaccum
1878         *            Value of the maximum integral accumulator (closed loop error
1879         *            units X 1ms).
1880         * @param timeoutMs
1881         *            Timeout value in ms. If nonzero, function will wait for config
1882         *            success and report an error if it times out. If zero, no
1883         *            blocking or checking is performed.
1884         * @return Error Code generated by function. 0 indicates no error.
1885         */
1886        public ErrorCode configMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs) {
1887                int retval = MotControllerJNI.ConfigMaxIntegralAccumulator(m_handle, slotIdx, iaccum, timeoutMs);
1888                return ErrorCode.valueOf(retval);
1889        }
1890        /**
1891         * Sets the maximum integral accumulator in the given parameter slot.
1892         *
1893         * @param slotIdx
1894         *            Parameter slot for the constant.
1895         * @param iaccum
1896         *            Value of the maximum integral accumulator (closed loop error
1897         *            units X 1ms).
1898         * @return Error Code generated by function. 0 indicates no error.
1899         */
1900        public ErrorCode configMaxIntegralAccumulator(int slotIdx, double iaccum) {
1901        int timeoutMs = 0;
1902                return configMaxIntegralAccumulator( slotIdx,  iaccum,  timeoutMs);
1903        }
1904
1905        /**
1906         * Sets the peak closed-loop output.  This peak output is slot-specific and
1907         *   is applied to the output of the associated PID loop.
1908         * This setting is seperate from the generic Peak Output setting.
1909         *
1910         * @param slotIdx
1911         *            Parameter slot for the constant.
1912         * @param percentOut
1913         *            Peak Percent Output from 0 to 1.  This value is absolute and
1914         *                                              the magnitude will apply in both forward and reverse directions.
1915         * @param timeoutMs
1916         *            Timeout value in ms. If nonzero, function will wait for
1917         *            config success and report an error if it times out.
1918         *            If zero, no blocking or checking is performed.
1919         * @return Error Code generated by function. 0 indicates no error.
1920         */
1921        public ErrorCode configClosedLoopPeakOutput(int slotIdx, double percentOut, int timeoutMs) {
1922                int retval = MotControllerJNI.ConfigClosedLoopPeakOutput(m_handle, slotIdx, percentOut, timeoutMs);
1923                return ErrorCode.valueOf(retval);
1924        }
1925        /**
1926         * Sets the peak closed-loop output.  This peak output is slot-specific and
1927         *   is applied to the output of the associated PID loop.
1928         * This setting is seperate from the generic Peak Output setting.
1929         *
1930         * @param slotIdx
1931         *            Parameter slot for the constant.
1932         * @param percentOut
1933         *            Peak Percent Output from 0 to 1.  This value is absolute and
1934         *                                              the magnitude will apply in both forward and reverse directions.
1935         * @return Error Code generated by function. 0 indicates no error.
1936         */
1937        public ErrorCode configClosedLoopPeakOutput(int slotIdx, double percentOut) {
1938        int timeoutMs = 0;
1939
1940                return configClosedLoopPeakOutput( slotIdx,  percentOut,  timeoutMs);
1941        }
1942
1943        /**
1944         * Sets the loop time (in milliseconds) of the PID closed-loop calculations.
1945         * Default value is 1 ms.
1946         *
1947         * @param slotIdx
1948         *            Parameter slot for the constant.
1949         * @param loopTimeMs
1950         *            Loop timing of the closed-loop calculations.  Minimum value of
1951         *                                              1 ms, maximum of 64 ms.
1952         * @param timeoutMs
1953         *            Timeout value in ms. If nonzero, function will wait for
1954         *            config success and report an error if it times out.
1955         *            If zero, no blocking or checking is performed.
1956         * @return Error Code generated by function. 0 indicates no error.
1957         */
1958        public ErrorCode configClosedLoopPeriod(int slotIdx, int loopTimeMs, int timeoutMs) {
1959                int retval = MotControllerJNI.ConfigClosedLoopPeriod(m_handle, slotIdx, loopTimeMs, timeoutMs);
1960                return ErrorCode.valueOf(retval);
1961        }
1962        /**
1963         * Sets the loop time (in milliseconds) of the PID closed-loop calculations.
1964         * Default value is 1 ms.
1965         *
1966         * @param slotIdx
1967         *            Parameter slot for the constant.
1968         * @param loopTimeMs
1969         *            Loop timing of the closed-loop calculations.  Minimum value of
1970         *                                              1 ms, maximum of 64 ms.
1971         * @return Error Code generated by function. 0 indicates no error.
1972         */
1973        public ErrorCode configClosedLoopPeriod(int slotIdx, int loopTimeMs) {
1974        int timeoutMs = 0;
1975                return configClosedLoopPeriod( slotIdx,  loopTimeMs,  timeoutMs);
1976        }
1977
1978        /**
1979         * Configures the Polarity of the Auxiliary PID (PID1).
1980         *
1981         * Standard Polarity:
1982         *    Primary Output = PID0 + PID1,
1983         *    Auxiliary Output = PID0 - PID1,
1984         *
1985         * Inverted Polarity:
1986         *    Primary Output = PID0 - PID1,
1987         *    Auxiliary Output = PID0 + PID1,
1988         *
1989         * @param invert
1990         *            If true, use inverted PID1 output polarity.
1991         * @param timeoutMs
1992         *            Timeout value in ms. If nonzero, function will wait for config
1993         *            success and report an error if it times out. If zero, no
1994         *            blocking or checking is performed.
1995         * @return Error Code
1996         */
1997        public ErrorCode configAuxPIDPolarity(boolean invert, int timeoutMs){
1998                return configSetParameter(ParamEnum.ePIDLoopPolarity, invert ? 1:0, 0, 1, timeoutMs);
1999        }
2000        /**
2001         * Configures the Polarity of the Auxiliary PID (PID1).
2002         *
2003         * Standard Polarity:
2004         *    Primary Output = PID0 + PID1,
2005         *    Auxiliary Output = PID0 - PID1,
2006         *
2007         * Inverted Polarity:
2008         *    Primary Output = PID0 - PID1,
2009         *    Auxiliary Output = PID0 + PID1,
2010         *
2011         * @param invert
2012         *            If true, use inverted PID1 output polarity.
2013         * @return Error Code
2014         */
2015        public ErrorCode configAuxPIDPolarity(boolean invert){
2016                int timeoutMs = 0;
2017                return configAuxPIDPolarity(invert,  timeoutMs);
2018        }
2019
2020        /**
2021         * Sets the integral accumulator. Typically this is used to clear/zero the
2022         * integral accumulator, however some use cases may require seeding the
2023         * accumulator for a faster response.
2024         *
2025         * @param iaccum
2026         *            Value to set for the integral accumulator (closed loop error
2027         *            units X 1ms).
2028         * @param pidIdx
2029         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2030         * @param timeoutMs
2031         *            Timeout value in ms. If nonzero, function will wait for config
2032         *            success and report an error if it times out. If zero, no
2033         *            blocking or checking is performed.
2034         * @return Error Code generated by function. 0 indicates no error.
2035         */
2036        public ErrorCode setIntegralAccumulator(double iaccum, int pidIdx, int timeoutMs) {
2037                int retval = MotControllerJNI.SetIntegralAccumulator(m_handle,  iaccum, pidIdx, timeoutMs);
2038                return ErrorCode.valueOf(retval);
2039        }
2040        /**
2041         * Sets the integral accumulator. Typically this is used to clear/zero the
2042         * integral accumulator, however some use cases may require seeding the
2043         * accumulator for a faster response.
2044         *
2045         * @param iaccum
2046         *            Value to set for the integral accumulator (closed loop error
2047         *            units X 1ms).
2048         * @return Error Code generated by function. 0 indicates no error.
2049         */
2050        public ErrorCode setIntegralAccumulator(double iaccum) {
2051                int pidIdx = 0;
2052                int timeoutMs = 0;
2053                return setIntegralAccumulator( iaccum,  pidIdx,  timeoutMs);
2054        }
2055
2056        /**
2057         * Gets the closed-loop error. The units depend on which control mode is in
2058         * use.
2059         *
2060         * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target
2061         * and current sensor value (in sensor units.  Example 4096 units per rotation for CTRE Mag Encoder).
2062         *
2063         * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target
2064         * and current sensor value (in sensor units per 100ms).
2065         *
2066         * If using motion profiling or Motion Magic, closed loop error is calculated against the current target,
2067         * and not the "final" target at the end of the profile/movement.
2068         *
2069         * See Phoenix-Documentation information on units.
2070         *
2071         * @param pidIdx
2072         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2073         * @return Closed-loop error value.
2074         */
2075        public double getClosedLoopError(int pidIdx) {
2076                return (double)MotControllerJNI.GetClosedLoopError(m_handle, pidIdx);
2077        }
2078        /**
2079         * Gets the closed-loop error. The units depend on which control mode is in
2080         * use.
2081         *
2082         * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target
2083         * and current sensor value (in sensor units.  Example 4096 units per rotation for CTRE Mag Encoder).
2084         *
2085         * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target
2086         * and current sensor value (in sensor units per 100ms).
2087         *
2088         * If using motion profiling or Motion Magic, closed loop error is calculated against the current target,
2089         * and not the "final" target at the end of the profile/movement.
2090         *
2091         * See Phoenix-Documentation information on units.
2092         *
2093         * @return Closed-loop error value.
2094         */
2095        public double getClosedLoopError() {
2096                int pidIdx = 0;
2097                return getClosedLoopError( pidIdx);
2098        }
2099
2100        /**
2101         * Gets the iaccum value.
2102         *
2103         * @param pidIdx
2104         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2105         * @return Integral accumulator value (Closed-loop error X 1ms).
2106         */
2107        public double getIntegralAccumulator(int pidIdx) {
2108                return MotControllerJNI.GetIntegralAccumulator(m_handle, pidIdx);
2109        }
2110        /**
2111         * Gets the iaccum value.
2112         *
2113         * @return Integral accumulator value (Closed-loop error X 1ms).
2114         */
2115        public double getIntegralAccumulator() {
2116                int pidIdx = 0;
2117                return getIntegralAccumulator(pidIdx);
2118        }
2119
2120
2121        /**
2122         * Gets the derivative of the closed-loop error.
2123         *
2124         * @param pidIdx
2125         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2126         * @return The error derivative value.
2127         */
2128        public double getErrorDerivative(int pidIdx) {
2129                return MotControllerJNI.GetErrorDerivative(m_handle, pidIdx);
2130        }
2131        /**
2132         * Gets the derivative of the closed-loop error.
2133         *
2134         * @return The error derivative value.
2135         */
2136        public double getErrorDerivative() {
2137                int pidIdx = 0;
2138
2139                return getErrorDerivative(pidIdx);
2140        }
2141
2142        /**
2143         * Selects which profile slot to use for closed-loop control.
2144         *
2145         * @param slotIdx
2146         *            Profile slot to select.
2147         * @param pidIdx
2148         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2149         **/
2150        public void selectProfileSlot(int slotIdx, int pidIdx) {
2151                MotControllerJNI.SelectProfileSlot(m_handle, slotIdx, pidIdx);
2152        }
2153
2154        /**
2155         * Gets the current target of a given closed loop.
2156         *
2157         * @param pidIdx
2158         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2159         * @return The closed loop target.
2160         */
2161        public double getClosedLoopTarget(int pidIdx) {
2162                double value = MotControllerJNI.GetClosedLoopTarget(m_handle, pidIdx);
2163                if(m_controlMode == ControlMode.Current){
2164                        value = value / 1000; //convert back to amps
2165                }
2166                return value;
2167        }
2168        /**
2169         * Gets the current target of a given closed loop.
2170         *
2171         * @return The closed loop target.
2172         */
2173        public double getClosedLoopTarget() {
2174                int pidIdx = 0;
2175                return getClosedLoopTarget(pidIdx);
2176        }
2177
2178        /**
2179         * Gets the active trajectory target position for pid0 using
2180         * MotionMagic/MotionProfile control modes.
2181         *
2182         * @return The Active Trajectory Position in sensor units.
2183         */
2184        public double getActiveTrajectoryPosition() {
2185                return (double)MotControllerJNI.GetActiveTrajectoryPosition(m_handle);
2186        }
2187
2188        /**
2189         * Gets the active trajectory target position using
2190         * MotionMagic/MotionProfile control modes.
2191         *
2192         * @param pidIdx
2193         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2194         * @return The Active Trajectory Position in sensor units.
2195         */
2196        public double getActiveTrajectoryPosition(int pidIdx) {
2197                return (double)MotControllerJNI.GetActiveTrajectoryPosition3(m_handle, pidIdx);
2198        }
2199
2200        /**
2201         * Gets the active trajectory target velocity for pid0 using
2202         * MotionMagic/MotionProfile control modes.
2203         *
2204         * @return The Active Trajectory Velocity in sensor units per 100ms.
2205         */
2206        public double getActiveTrajectoryVelocity() {
2207                return (double)MotControllerJNI.GetActiveTrajectoryVelocity(m_handle);
2208        }
2209
2210        /**
2211         * Gets the active trajectory target velocity using
2212         * MotionMagic/MotionProfile control modes.
2213         *
2214         * @param pidIdx
2215         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2216         * @return The Active Trajectory Velocity in sensor units per 100ms.
2217         */
2218        public double getActiveTrajectoryVelocity(int pidIdx) {
2219                return (double)MotControllerJNI.GetActiveTrajectoryVelocity3(m_handle, pidIdx);
2220        }
2221
2222        /**
2223         * Gets the active trajectory arbitrary feedforward for pid0 using
2224         * MotionMagic/MotionProfile control modes.
2225         *
2226         * @return The Active Trajectory ArbFeedFwd in units of percent output
2227         *                      (where 0.01 is 1%).
2228         */
2229        public double getActiveTrajectoryArbFeedFwd() {
2230                return MotControllerJNI.GetActiveTrajectoryArbFeedFwd3(m_handle, 0);
2231        }
2232
2233        /**
2234         * Gets the active trajectory arbitrary feedforward using
2235         * MotionMagic/MotionProfile control modes.
2236         *
2237         * @param pidIdx
2238         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
2239         * @return The Active Trajectory ArbFeedFwd in units of percent output
2240         *                      (where 0.01 is 1%).
2241         */
2242        public double getActiveTrajectoryArbFeedFwd(int pidIdx) {
2243                return MotControllerJNI.GetActiveTrajectoryArbFeedFwd3(m_handle, pidIdx);
2244        }
2245
2246        // ------ Motion Profile Settings used in Motion Magic and Motion Profile ----------//
2247
2248        /**
2249         * Sets the Motion Magic Cruise Velocity. This is the peak target velocity
2250         * that the motion magic curve generator can use.
2251         *
2252         * @param sensorUnitsPer100ms
2253         *            Motion Magic Cruise Velocity (in raw sensor units per 100 ms).
2254         * @param timeoutMs
2255         *            Timeout value in ms. If nonzero, function will wait for config
2256         *            success and report an error if it times out. If zero, no
2257         *            blocking or checking is performed.
2258         * @return Error Code generated by function. 0 indicates no error.
2259         */
2260        public ErrorCode configMotionCruiseVelocity(double sensorUnitsPer100ms, int timeoutMs) {
2261                int retval = MotControllerJNI.ConfigMotionCruiseVelocity(m_handle, (int)sensorUnitsPer100ms, timeoutMs);
2262                return ErrorCode.valueOf(retval);
2263        }
2264        /**
2265         * Sets the Motion Magic Cruise Velocity. This is the peak target velocity
2266         * that the motion magic curve generator can use.
2267         *
2268         * @param sensorUnitsPer100ms
2269         *            Motion Magic Cruise Velocity (in raw sensor units per 100 ms).
2270         * @return Error Code generated by function. 0 indicates no error.
2271         */
2272        public ErrorCode configMotionCruiseVelocity(double sensorUnitsPer100ms) {
2273                int timeoutMs = 0;
2274                return configMotionCruiseVelocity( sensorUnitsPer100ms,  timeoutMs);
2275        }
2276
2277        /**
2278         * Sets the Motion Magic Acceleration. This is the target acceleration that
2279         * the motion magic curve generator can use.
2280         *
2281         * @param sensorUnitsPer100msPerSec
2282         *            Motion Magic Acceleration (in raw sensor units per 100 ms per
2283         *            second).
2284         * @param timeoutMs
2285         *            Timeout value in ms. If nonzero, function will wait for config
2286         *            success and report an error if it times out. If zero, no
2287         *            blocking or checking is performed.
2288         * @return Error Code generated by function. 0 indicates no error.
2289         */
2290        public ErrorCode configMotionAcceleration(double sensorUnitsPer100msPerSec, int timeoutMs) {
2291                int retval = MotControllerJNI.ConfigMotionAcceleration(m_handle, (int)sensorUnitsPer100msPerSec, timeoutMs);
2292                return ErrorCode.valueOf(retval);
2293        }
2294        /**
2295         * Sets the Motion Magic Acceleration. This is the target acceleration that
2296         * the motion magic curve generator can use.
2297         *
2298         * @param sensorUnitsPer100msPerSec
2299         *            Motion Magic Acceleration (in raw sensor units per 100 ms per
2300         *            second).
2301         * @return Error Code generated by function. 0 indicates no error.
2302         */
2303        public ErrorCode configMotionAcceleration(double sensorUnitsPer100msPerSec) {
2304                int timeoutMs = 0;
2305                return configMotionAcceleration( sensorUnitsPer100msPerSec,  timeoutMs);
2306        }
2307
2308        /**
2309         * Sets the Motion Magic S Curve Strength.
2310         * Call this before using Motion Magic.
2311         * Modifying this during a Motion Magic action should be avoided.
2312         *
2313         * @param curveStrength
2314         *            0 to use Trapezoidal Motion Profile. [1,8] for S-Curve (greater value yields greater smoothing).
2315         * @param timeoutMs
2316         *            Timeout value in ms. If nonzero, function will wait for config
2317         *            success and report an error if it times out. If zero, no
2318         *            blocking or checking is performed.
2319         * @return Error Code generated by function. 0 indicates no error.
2320         */
2321        public ErrorCode configMotionSCurveStrength(int curveStrength, int timeoutMs) {
2322                int retval = MotControllerJNI.ConfigMotionSCurveStrength(m_handle, curveStrength, timeoutMs);
2323                return ErrorCode.valueOf(retval);
2324        }
2325
2326        /**
2327         * Sets the Motion Magic S Curve Strength.
2328         * Call this before using Motion Magic.
2329         * Modifying this during a Motion Magic action should be avoided.
2330         *
2331         * @param curveStrength
2332         *            0 to use Trapezoidal Motion Profile. [1,8] for S-Curve (greater value yields greater smoothing).
2333         * @return Error Code generated by function. 0 indicates no error.
2334         */
2335        public ErrorCode configMotionSCurveStrength(int curveStrength) {
2336                int timeoutMs = 0;
2337                return configMotionSCurveStrength(curveStrength, timeoutMs);
2338        }
2339
2340        //------ Motion Profile Buffer ----------//
2341        /**
2342         * Clear the buffered motion profile in both controller's RAM (bottom), and in the
2343         * API (top).
2344         * @return Error Code generated by function. 0 indicates no error.
2345         */
2346        public ErrorCode clearMotionProfileTrajectories() {
2347                int retval = MotControllerJNI.ClearMotionProfileTrajectories(m_handle);
2348                return ErrorCode.valueOf(retval);
2349        }
2350
2351        /**
2352         * Retrieve just the buffer count for the api-level (top) buffer. This
2353         * routine performs no CAN or data structure lookups, so its fast and ideal
2354         * if caller needs to quickly poll the progress of trajectory points being
2355         * emptied into controller's RAM. Otherwise just use GetMotionProfileStatus.
2356         *
2357         * @return number of trajectory points in the top buffer.
2358         */
2359        public int getMotionProfileTopLevelBufferCount() {
2360                return MotControllerJNI.GetMotionProfileTopLevelBufferCount(m_handle);
2361        }
2362        /**
2363         * Push another trajectory point into the top level buffer (which is emptied
2364         * into the motor controller's bottom buffer as room allows).
2365         * @param trajPt to push into buffer.
2366         * The members should be filled in with these values...
2367         *
2368         *              targPos:  servo position in sensor units.
2369         *              targVel:  velocity to feed-forward in sensor units
2370         *                 per 100ms.
2371         *              profileSlotSelect0  Which slot to get PIDF gains. PID is used for position servo. F is used
2372         *                                                 as the Kv constant for velocity feed-forward. Typically this is hardcoded
2373         *                                                 to the a particular slot, but you are free gain schedule if need be.
2374         *                                                 Choose from [0,3]
2375         *              profileSlotSelect1 Which slot to get PIDF gains for auxiliary PId.
2376         *                                                 This only has impact during MotionProfileArc Control mode.
2377         *                                                 Choose from [0,1].
2378         *         isLastPoint  set to nonzero to signal motor controller to keep processing this
2379         *                     trajectory point, instead of jumping to the next one
2380         *                     when timeDurMs expires.  Otherwise MP executer will
2381         *                     eventually see an empty buffer after the last point
2382         *                     expires, causing it to assert the IsUnderRun flag.
2383         *                     However this may be desired if calling application
2384         *                     never wants to terminate the MP.
2385         *              zeroPos  set to nonzero to signal motor controller to "zero" the selected
2386         *                 position sensor before executing this trajectory point.
2387         *                 Typically the first point should have this set only thus
2388         *                 allowing the remainder of the MP positions to be relative to
2389         *                 zero.
2390         *              timeDur Duration to apply this trajectory pt.
2391         *                              This time unit is ADDED to the exising base time set by
2392         *                              configMotionProfileTrajectoryPeriod().
2393         * @return CTR_OKAY if trajectory point push ok. ErrorCode if buffer is
2394         *         full due to kMotionProfileTopBufferCapacity.
2395         */
2396        public ErrorCode pushMotionProfileTrajectory(TrajectoryPoint trajPt) {
2397                int retval = MotControllerJNI.PushMotionProfileTrajectory3(m_handle, trajPt.position, trajPt.velocity, trajPt.arbFeedFwd, trajPt.auxiliaryPos, trajPt.auxiliaryVel, trajPt.auxiliaryArbFeedFwd, trajPt.profileSlotSelect0, trajPt.profileSlotSelect1, trajPt.isLastPoint, trajPt.zeroPos, trajPt.timeDur, trajPt.useAuxPID);
2398                return ErrorCode.valueOf(retval);
2399        }
2400
2401        /**
2402         * Simple one-shot firing of a complete MP.
2403         * Starting in 2019, MPs can be fired by building a Buffered Trajectory Point Stream, and calling this routine.
2404         *
2405         * Once called, the motor controller software will automatically ...
2406         * [1] Clear the firmware buffer of trajectory points.
2407         * [2] Clear the underrun flags
2408         * [3] Reset an index within the Buffered Trajectory Point Stream (so that the same profile can be run again and again).
2409         * [4] Start a background thread to manage MP streaming (if not already running).
2410         * [5a] If current control mode already matches motionProfControlMode, set MPE Output to "Hold".
2411         * [5b] If current control mode does not matches motionProfControlMode, apply motionProfControlMode and set MPE Output to "Disable".
2412         * [6] Stream the trajectory points into the device's firmware buffer.
2413         * [7] Once motor controller has at least minBufferedPts worth in the firmware buffer, MP will automatically start (MPE Output set to "Enable").
2414         * [8] Wait until MP finishes, then transitions the Motion Profile Executor's output to "Hold".
2415         * [9] IsMotionProfileFinished() will now return true.
2416         *
2417         * Calling application can use IsMotionProfileFinished() to determine when internal state machine reaches [7].
2418         * Calling application can cancel MP by calling set().  Otherwise do not call set() until MP has completed.
2419         *
2420         * The legacy API from previous years requires the calling application to pass points via the ProcessMotionProfileBuffer and PushMotionProfileTrajectory.
2421         * This is no longer required if using this StartMotionProfile/IsMotionProfileFinished API.
2422         *
2423         * @param stream        A buffer that will be used to stream the trajectory points.  Caller can fill this container with the entire trajectory point, regardless of size.
2424         * @param minBufferedPts        Minimum number of firmware buffered points before starting MP.
2425         *                                                      Do not exceed device's firmware buffer capacity or MP will never fire (120 for Motion Profile, or 60 for Motion Profile Arc).
2426         *                                                      Recommendation value for this would be five to ten samples depending on timeDur of the trajectory point.
2427         * @param motionProfControlMode         Pass MotionProfile or MotionProfileArc.
2428         * @return nonzero error code if operation fails.
2429     */
2430        public ErrorCode startMotionProfile(BufferedTrajectoryPointStream stream, int minBufferedPts, ControlMode motionProfControlMode) {
2431                int retval = MotControllerJNI.StartMotionProfile(m_handle, stream.getHandle(), minBufferedPts, motionProfControlMode.value);
2432                return ErrorCode.valueOf(retval);
2433        }
2434        /**
2435         * Determine if running MP is complete.
2436         * This requires using the StartMotionProfile routine to start the MP.
2437         * That is because managing the trajectory points is now done in a background thread (if StartMotionProfile is called).
2438         *
2439         * If calling application uses the legacy API  (more-complex buffering API) from previous years, than this API will
2440         * not return true.
2441         *
2442         * @return true if MP was started using StartMotionProfile, and it has completed execution (MPE is now in "hold").
2443         */
2444        public boolean isMotionProfileFinished() {
2445                return MotControllerJNI.IsMotionProfileFinished(m_handle);
2446        }
2447
2448        /**
2449         * Retrieve just the buffer full for the api-level (top) buffer. This
2450         * routine performs no CAN or data structure lookups, so its fast and ideal
2451         * if caller needs to quickly poll. Otherwise just use
2452         * GetMotionProfileStatus.
2453         *
2454         * @return number of trajectory points in the top buffer.
2455         */
2456        public boolean isMotionProfileTopLevelBufferFull() {
2457                return MotControllerJNI.IsMotionProfileTopLevelBufferFull(m_handle);
2458        }
2459
2460        /**
2461         * This must be called periodically to funnel the trajectory points from the
2462         * API's top level buffer to the controller's bottom level buffer. Recommendation
2463         * is to call this twice as fast as the execution rate of the motion
2464         * profile. So if MP is running with 20ms trajectory points, try calling
2465         * this routine every 10ms. All motion profile functions are thread-safe
2466         * through the use of a mutex, so there is no harm in having the caller
2467         * utilize threading.
2468         */
2469        public void processMotionProfileBuffer() {
2470                MotControllerJNI.ProcessMotionProfileBuffer(m_handle);
2471        }
2472        /**
2473         * Retrieve all status information.
2474         * For best performance, Caller can snapshot all status information regarding the
2475         * motion profile executer.
2476         *
2477         * @param statusToFill  Caller supplied object to fill.
2478         *
2479         * The members are filled, as follows...
2480         *
2481         *      topBufferRem:   The available empty slots in the trajectory buffer.
2482         *                                      The robot API holds a "top buffer" of trajectory points, so your applicaion
2483         *                                      can dump several points at once.  The API will then stream them into the
2484         *                                      low-level buffer, allowing the motor controller to act on them.
2485         *
2486         *      topBufferRem: The number of points in the top trajectory buffer.
2487         *
2488         *      btmBufferCnt: The number of points in the low level controller buffer.
2489         *
2490         *      hasUnderrun:    Set if isUnderrun ever gets set.
2491         *                                      Can be manually cleared by clearMotionProfileHasUnderrun() or automatically cleared by startMotionProfile().
2492         *
2493         *      isUnderrun:             This is set if controller needs to shift a point from its buffer into
2494         *                                      the active trajectory point however
2495         *                                      the buffer is empty.
2496         *                                      This gets cleared automatically when is resolved.
2497         *
2498         *      activePointValid:       True if the active trajectory point is not empty, false otherwise. The members in activePoint are only valid if this signal is set.
2499         *
2500         *      isLast: is set/cleared based on the MP executer's current
2501         *                trajectory point's IsLast value.  This assumes
2502         *                IsLast was set when PushMotionProfileTrajectory
2503         *                was used to insert the currently processed trajectory
2504         *                point.
2505         *
2506         *      profileSlotSelect: The currently processed trajectory point's
2507         *                                selected slot.  This can differ in the currently selected slot used
2508         *                                       for Position and Velocity servo modes
2509         *
2510         *      outputEnable:           The current output mode of the motion profile
2511         *                                              executer (disabled, enabled, or hold).  When changing the set()
2512         *                                              value in MP mode, it's important to check this signal to
2513         *                                              confirm the change takes effect before interacting with the top buffer.
2514         *
2515         * @return Error Code generated by function. 0 indicates no error.
2516         */
2517        public ErrorCode getMotionProfileStatus(MotionProfileStatus statusToFill) {
2518                int retval = MotControllerJNI.GetMotionProfileStatus2(m_handle, _motionProfStats);
2519                statusToFill.topBufferRem = _motionProfStats[0];
2520                statusToFill.topBufferCnt = _motionProfStats[1];
2521                statusToFill.btmBufferCnt = _motionProfStats[2];
2522                statusToFill.hasUnderrun = _motionProfStats[3] != 0;
2523                statusToFill.isUnderrun = _motionProfStats[4] != 0;
2524                statusToFill.activePointValid = _motionProfStats[5] != 0;
2525                statusToFill.isLast = _motionProfStats[6] != 0;
2526                statusToFill.profileSlotSelect = _motionProfStats[7];
2527                statusToFill.outputEnable = SetValueMotionProfile.valueOf(_motionProfStats[8]);
2528                statusToFill.timeDurMs = _motionProfStats[9];
2529                statusToFill.profileSlotSelect1 = _motionProfStats[10];
2530                return ErrorCode.valueOf(retval);
2531        }
2532
2533        /**
2534         * Clear the "Has Underrun" flag. Typically this is called after application
2535         * has confirmed an underrun had occured.
2536         *
2537         * @param timeoutMs
2538         *            Timeout value in ms. If nonzero, function will wait for config
2539         *            success and report an error if it times out. If zero, no
2540         *            blocking or checking is performed.
2541         * @return Error Code generated by function. 0 indicates no error.
2542         */
2543        public ErrorCode clearMotionProfileHasUnderrun(int timeoutMs) {
2544                int retval = MotControllerJNI.ClearMotionProfileHasUnderrun(m_handle, timeoutMs);
2545                return ErrorCode.valueOf(retval);
2546        }
2547        /**
2548         * Clear the "Has Underrun" flag. Typically this is called after application
2549         * has confirmed an underrun had occured.
2550         *
2551         * @return Error Code generated by function. 0 indicates no error.
2552         */
2553        public ErrorCode clearMotionProfileHasUnderrun() {
2554                int timeoutMs = 0;
2555                return clearMotionProfileHasUnderrun(timeoutMs);
2556        }
2557
2558        /**
2559         * Calling application can opt to speed up the handshaking between the robot
2560         * API and the controller to increase the download rate of the controller's Motion
2561         * Profile. Ideally the period should be no more than half the period of a
2562         * trajectory point.
2563         *
2564         * @param periodMs
2565         *            The transmit period in ms.
2566         * @return Error Code generated by function. 0 indicates no error.
2567         */
2568        public ErrorCode changeMotionControlFramePeriod(int periodMs) {
2569                int retval = MotControllerJNI.ChangeMotionControlFramePeriod(m_handle, periodMs);
2570                return ErrorCode.valueOf(retval);
2571        }
2572
2573        /**
2574         * When trajectory points are processed in the motion profile executer, the MPE determines
2575         * how long to apply the active trajectory point by summing baseTrajDurationMs with the
2576         * timeDur of the trajectory point (see TrajectoryPoint).
2577         *
2578         * This allows general selection of the execution rate of the points with 1ms resolution,
2579         * while allowing some degree of change from point to point.
2580         * @param baseTrajDurationMs The base duration time of every trajectory point.
2581         *                                                      This is summed with the trajectory points unique timeDur.
2582         * @param timeoutMs
2583         *            Timeout value in ms. If nonzero, function will wait for
2584         *            config success and report an error if it times out.
2585         *            If zero, no blocking or checking is performed.
2586         * @return Error Code generated by function. 0 indicates no error.
2587         */
2588        public ErrorCode configMotionProfileTrajectoryPeriod(int baseTrajDurationMs, int timeoutMs) {
2589                int retval = MotControllerJNI.ConfigMotionProfileTrajectoryPeriod(m_handle, baseTrajDurationMs, timeoutMs);
2590                return ErrorCode.valueOf(retval);
2591        }
2592        /**
2593         * When trajectory points are processed in the motion profile executer, the MPE determines
2594         * how long to apply the active trajectory point by summing baseTrajDurationMs with the
2595         * timeDur of the trajectory point (see TrajectoryPoint).
2596         *
2597         * This allows general selection of the execution rate of the points with 1ms resolution,
2598         * while allowing some degree of change from point to point.
2599         * @param baseTrajDurationMs The base duration time of every trajectory point.
2600         *                                                      This is summed with the trajectory points unique timeDur.
2601         * @return Error Code generated by function. 0 indicates no error.
2602         */
2603        public ErrorCode configMotionProfileTrajectoryPeriod(int baseTrajDurationMs) {
2604                int timeoutMs = 0;
2605                return configMotionProfileTrajectoryPeriod( baseTrajDurationMs,  timeoutMs);
2606        }
2607
2608        /**
2609         * When trajectory points are processed in the buffer, the motor controller can
2610         * linearly interpolate additional trajectory points between the buffered
2611         * points.  The time delta between these interpolated points is 1 ms.
2612         *
2613         * By default this feature is enabled.
2614         *
2615         * @param enable Whether to enable the trajectory point interpolation feature.
2616         * @param timeoutMs
2617         *            Timeout value in ms. If nonzero, function will wait for
2618         *            config success and report an error if it times out.
2619         *            If zero, no blocking or checking is performed.
2620         * @return Error Code generated by function. 0 indicates no error.
2621         */
2622        public ErrorCode configMotionProfileTrajectoryInterpolationEnable(boolean enable, int timeoutMs) {
2623                int retval = MotControllerJNI.ConfigMotionProfileTrajectoryInterpolationEnable(m_handle, enable, timeoutMs);
2624                return ErrorCode.valueOf(retval);
2625        }
2626        /**
2627         * When trajectory points are processed in the buffer, the motor controller can
2628         * linearly interpolate additional trajectory points between the buffered
2629         * points.  The time delta between these interpolated points is 1 ms.
2630         *
2631         * By default this feature is enabled.
2632         *
2633         * @param enable Whether to enable the trajectory point interpolation feature.
2634         * @return Error Code generated by function. 0 indicates no error.
2635         */
2636        public ErrorCode configMotionProfileTrajectoryInterpolationEnable(boolean enable) {
2637                int timeoutMs = 0;
2638                return configMotionProfileTrajectoryInterpolationEnable(enable, timeoutMs);
2639        }
2640
2641    //------Feedback Device Interaction Settings---------//
2642
2643    /**
2644     * Disables continuous tracking of the position for analog and pulse-width.
2645         * If the signal goes from 4095 to 0 (pulse-width) a motor controller will continue to read 4096 by default.
2646         * If overflow tracking is disabled, it will wrap to 0 (not continuous)
2647         *
2648         * If using pulse-width on CTRE Mag Encoder (within one rotation) or absolute analog sensor (within one rotation),
2649         * setting feedbackNotContinuous to true is recommended, to prevent intermittent
2650         * connections from causing sensor "jumps" of 4096 (or 1024 for analog) units.
2651     *
2652     * @param feedbackNotContinuous     True to disable the overflow tracking.
2653     *
2654     * @param timeoutMs
2655     *            Timeout value in ms. If nonzero, function will wait for
2656     *            config success and report an error if it times out.
2657     *            If zero, no blocking or checking is performed.
2658     * @return Error Code generated by function. 0 indicates no error.
2659     */
2660    public ErrorCode configFeedbackNotContinuous(boolean feedbackNotContinuous, int timeoutMs) {
2661        int retval = MotControllerJNI.ConfigFeedbackNotContinuous(m_handle, feedbackNotContinuous, timeoutMs);
2662        return ErrorCode.valueOf(retval);
2663    }
2664
2665    /**
2666     * Disables going to neutral (brake/coast) when a remote sensor is no longer detected.
2667     *
2668     * @param remoteSensorClosedLoopDisableNeutralOnLOS     disable going to neutral
2669     *
2670     * @param timeoutMs
2671     *            Timeout value in ms. If nonzero, function will wait for
2672     *            config success and report an error if it times out.
2673     *            If zero, no blocking or checking is performed.
2674     * @return Error Code generated by function. 0 indicates no error.
2675     */
2676    public ErrorCode configRemoteSensorClosedLoopDisableNeutralOnLOS(boolean remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs) {
2677        int retval = MotControllerJNI.ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(m_handle, remoteSensorClosedLoopDisableNeutralOnLOS, timeoutMs);
2678        return ErrorCode.valueOf(retval);
2679    }
2680    /**
2681     * Enables clearing the position of the feedback sensor when the forward
2682     * limit switch is triggered.
2683     *
2684     * @param clearPositionOnLimitF     Whether clearing is enabled, defaults false
2685     * @param timeoutMs
2686     *            Timeout value in ms. If nonzero, function will wait for
2687     *            config success and report an error if it times out.
2688     *            If zero, no blocking or checking is performed.
2689     * @return Error Code generated by function. 0 indicates no error.
2690     */
2691    public ErrorCode configClearPositionOnLimitF(boolean clearPositionOnLimitF, int timeoutMs) {
2692        int retval = MotControllerJNI.ConfigClearPositionOnLimitF(m_handle, clearPositionOnLimitF, timeoutMs);
2693        return ErrorCode.valueOf(retval);
2694    }
2695
2696    /**
2697     * Enables clearing the position of the feedback sensor when the reverse
2698     * limit switch is triggered
2699     *
2700     * @param clearPositionOnLimitR     Whether clearing is enabled, defaults false
2701     * @param timeoutMs
2702     *            Timeout value in ms. If nonzero, function will wait for
2703     *            config success and report an error if it times out.
2704     *            If zero, no blocking or checking is performed.
2705     * @return Error Code generated by function. 0 indicates no error.
2706     */
2707    public ErrorCode configClearPositionOnLimitR(boolean clearPositionOnLimitR, int timeoutMs) {
2708        int retval = MotControllerJNI.ConfigClearPositionOnLimitR(m_handle, clearPositionOnLimitR, timeoutMs);
2709        return ErrorCode.valueOf(retval);
2710    }
2711
2712    /**
2713     * Enables clearing the position of the feedback sensor when the quadrature index signal
2714     * is detected
2715     *
2716     * @param clearPositionOnQuadIdx    Whether clearing is enabled, defaults false
2717     * @param timeoutMs
2718     *            Timeout value in ms. If nonzero, function will wait for
2719     *            config success and report an error if it times out.
2720     *            If zero, no blocking or checking is performed.
2721     * @return Error Code generated by function. 0 indicates no error.
2722     */
2723    public ErrorCode configClearPositionOnQuadIdx(boolean clearPositionOnQuadIdx, int timeoutMs) {
2724        int retval = MotControllerJNI.ConfigClearPositionOnQuadIdx(m_handle, clearPositionOnQuadIdx, timeoutMs);
2725        return ErrorCode.valueOf(retval);
2726    }
2727
2728    /**
2729     * Disables limit switches triggering (if enabled) when the sensor is no longer detected.
2730     *
2731     * @param limitSwitchDisableNeutralOnLOS    disable triggering
2732     *
2733     * @param timeoutMs
2734     *            Timeout value in ms. If nonzero, function will wait for
2735     *            config success and report an error if it times out.
2736     *            If zero, no blocking or checking is performed.
2737     * @return Error Code generated by function. 0 indicates no error.
2738     */
2739    public ErrorCode configLimitSwitchDisableNeutralOnLOS(boolean limitSwitchDisableNeutralOnLOS, int timeoutMs) {
2740        int retval = MotControllerJNI.ConfigLimitSwitchDisableNeutralOnLOS(m_handle, limitSwitchDisableNeutralOnLOS, timeoutMs);
2741        return ErrorCode.valueOf(retval);
2742    }
2743
2744    /**
2745     * Disables soft limits triggering (if enabled) when the sensor is no longer detected.
2746     *
2747     * @param softLimitDisableNeutralOnLOS    disable triggering
2748     *
2749     * @param timeoutMs
2750     *            Timeout value in ms. If nonzero, function will wait for
2751     *            config success and report an error if it times out.
2752     *            If zero, no blocking or checking is performed.
2753     * @return Error Code generated by function. 0 indicates no error.
2754     */
2755    public ErrorCode configSoftLimitDisableNeutralOnLOS(boolean softLimitDisableNeutralOnLOS, int timeoutMs) {
2756        int retval = MotControllerJNI.ConfigSoftLimitDisableNeutralOnLOS(m_handle, softLimitDisableNeutralOnLOS, timeoutMs);
2757        return ErrorCode.valueOf(retval);
2758    }
2759
2760    /**
2761     * Sets the edges per rotation of a pulse width sensor. (This should be set for
2762     * tachometer use).
2763     *
2764     * @param pulseWidthPeriod_EdgesPerRot    edges per rotation
2765     *
2766     * @param timeoutMs
2767     *            Timeout value in ms. If nonzero, function will wait for
2768     *            config success and report an error if it times out.
2769     *            If zero, no blocking or checking is performed.
2770     * @return Error Code generated by function. 0 indicates no error.
2771     */
2772    public ErrorCode configPulseWidthPeriod_EdgesPerRot(int pulseWidthPeriod_EdgesPerRot, int timeoutMs) {
2773        int retval = MotControllerJNI.ConfigPulseWidthPeriod_EdgesPerRot(m_handle, pulseWidthPeriod_EdgesPerRot, timeoutMs);
2774        return ErrorCode.valueOf(retval);
2775    }
2776
2777    /**
2778     * Sets the number of samples to use in smoothing a pulse width sensor with a rolling
2779     * average. Default is 1 (no smoothing).
2780     *
2781     * @param pulseWidthPeriod_FilterWindowSz   samples for rolling avg
2782     *
2783     * @param timeoutMs
2784     *            Timeout value in ms. If nonzero, function will wait for
2785     *            config success and report an error if it times out.
2786     *            If zero, no blocking or checking is performed.
2787     * @return Error Code generated by function. 0 indicates no error.
2788     */
2789    public ErrorCode configPulseWidthPeriod_FilterWindowSz(int pulseWidthPeriod_FilterWindowSz, int timeoutMs) {
2790        int retval = MotControllerJNI.ConfigPulseWidthPeriod_FilterWindowSz(m_handle, pulseWidthPeriod_FilterWindowSz, timeoutMs);
2791        return ErrorCode.valueOf(retval);
2792    }
2793        // ------ error ----------//
2794        /**
2795         * Gets the last error generated by this object. Not all functions return an
2796         * error code but can potentially report errors. This function can be used
2797         * to retrieve those error codes.
2798         *
2799         * @return Last Error Code generated by a function.
2800         */
2801        public ErrorCode getLastError() {
2802                int retval = MotControllerJNI.GetLastError(m_handle);
2803                return ErrorCode.valueOf(retval);
2804        }
2805
2806        // ------ Faults ----------//
2807        /**
2808         * Polls the various fault flags.
2809         *
2810         * @param toFill
2811         *            Caller's object to fill with latest fault flags.
2812         * @return Last Error Code generated by a function.
2813         */
2814        public ErrorCode getFaults(Faults toFill) {
2815                int bits = MotControllerJNI.GetFaults(m_handle);
2816                toFill.update(bits);
2817                return getLastError();
2818        }
2819
2820        /**
2821         * Polls the various sticky fault flags.
2822         *
2823         * @param toFill
2824         *            Caller's object to fill with latest sticky fault flags.
2825         * @return Last Error Code generated by a function.
2826         */
2827        public ErrorCode getStickyFaults(StickyFaults toFill) {
2828                int bits = MotControllerJNI.GetStickyFaults(m_handle);
2829                toFill.update(bits);
2830                return getLastError();
2831        }
2832
2833        /**
2834         * Clears all sticky faults.
2835         *
2836         * @param timeoutMs
2837         *            Timeout value in ms. If nonzero, function will wait for config
2838         *            success and report an error if it times out. If zero, no
2839         *            blocking or checking is performed.
2840         * @return Last Error Code generated by a function.
2841         */
2842        public ErrorCode clearStickyFaults(int timeoutMs) {
2843                int retval = MotControllerJNI.ClearStickyFaults(m_handle, timeoutMs);
2844                return ErrorCode.valueOf(retval);
2845        }
2846        /**
2847         * Clears all sticky faults.
2848         *
2849         * @return Last Error Code generated by a function.
2850         */
2851        public ErrorCode clearStickyFaults() {
2852                int timeoutMs = 0;
2853                return clearStickyFaults(timeoutMs);
2854        }
2855
2856        // ------ Firmware ----------//
2857        /**
2858         * Gets the firmware version of the device.
2859         *
2860         * @return Firmware version of device. For example: version 1-dot-2 is
2861         *         0x0102.
2862         */
2863        public int getFirmwareVersion() {
2864                return MotControllerJNI.GetFirmwareVersion(m_handle);
2865        }
2866
2867        /**
2868         * Returns true if the device has reset since last call.
2869         *
2870         * @return Has a Device Reset Occurred?
2871         */
2872        public boolean hasResetOccurred() {
2873                return MotControllerJNI.HasResetOccurred(m_handle);
2874        }
2875
2876        //------ Custom Persistent Params ----------//
2877        /**
2878         * Sets the value of a custom parameter. This is for arbitrary use.
2879         *
2880         * Sometimes it is necessary to save calibration/limit/target information in
2881         * the device. Particularly if the device is part of a subsystem that can be
2882         * replaced.
2883         *
2884         * @param newValue
2885         *            Value for custom parameter.
2886         * @param paramIndex
2887         *            Index of custom parameter [0,1]
2888         * @param timeoutMs
2889         *            Timeout value in ms. If nonzero, function will wait for config
2890         *            success and report an error if it times out. If zero, no
2891         *            blocking or checking is performed.
2892         * @return Error Code generated by function. 0 indicates no error.
2893         */
2894        public ErrorCode configSetCustomParam(int newValue, int paramIndex, int timeoutMs) {
2895                int retval = MotControllerJNI.ConfigSetCustomParam(m_handle, newValue, paramIndex, timeoutMs);
2896                return ErrorCode.valueOf(retval);
2897        }
2898        /**
2899         * Sets the value of a custom parameter. This is for arbitrary use.
2900         *
2901         * Sometimes it is necessary to save calibration/limit/target information in
2902         * the device. Particularly if the device is part of a subsystem that can be
2903         * replaced.
2904         *
2905         * @param newValue
2906         *            Value for custom parameter.
2907         * @param paramIndex
2908         *            Index of custom parameter [0,1]
2909         * @return Error Code generated by function. 0 indicates no error.
2910         */
2911        public ErrorCode configSetCustomParam(int newValue, int paramIndex) {
2912                int timeoutMs = 0;
2913                return configSetCustomParam( newValue,  paramIndex,  timeoutMs);
2914        }
2915
2916        /**
2917         * Gets the value of a custom parameter.
2918         *
2919         * @param paramIndex
2920         *            Index of custom parameter [0,1].
2921         * @param timeoutMs
2922         *            Timeout value in ms. If nonzero, function will wait for config
2923         *            success and report an error if it times out. If zero, no
2924         *            blocking or checking is performed.
2925         * @return Value of the custom param.
2926         */
2927        public int configGetCustomParam(int paramIndex, int timeoutMs) {
2928                int retval = MotControllerJNI.ConfigGetCustomParam(m_handle, paramIndex, timeoutMs);
2929                return retval;
2930        }
2931        /**
2932         * Gets the value of a custom parameter.
2933         *
2934         * @param paramIndex
2935         *            Index of custom parameter [0,1].
2936         * @return Value of the custom param.
2937         */
2938        public int configGetCustomParam(int paramIndex) {
2939                int timeoutMs = 0;
2940                return configGetCustomParam( paramIndex,  timeoutMs);
2941        }
2942
2943        // ------ Generic Param API ----------//
2944        /**
2945         * Sets a parameter. Generally this is not used. This can be utilized in -
2946         * Using new features without updating API installation. - Errata
2947         * workarounds to circumvent API implementation. - Allows for rapid testing
2948         * / unit testing of firmware.
2949         *
2950         * @param param
2951         *            Parameter enumeration.
2952         * @param value
2953         *            Value of parameter.
2954         * @param subValue
2955         *            Subvalue for parameter. Maximum value of 255.
2956         * @param ordinal
2957         *            Ordinal of parameter.
2958         * @param timeoutMs
2959         *            Timeout value in ms. If nonzero, function will wait for config
2960         *            success and report an error if it times out. If zero, no
2961         *            blocking or checking is performed.
2962         * @return Error Code generated by function. 0 indicates no error.
2963         */
2964        public ErrorCode configSetParameter(ParamEnum param, double value, int subValue, int ordinal, int timeoutMs) {
2965                return configSetParameter(param.value, value, subValue, ordinal, timeoutMs);
2966        }
2967        /**
2968         * Sets a parameter. Generally this is not used. This can be utilized in -
2969         * Using new features without updating API installation. - Errata
2970         * workarounds to circumvent API implementation. - Allows for rapid testing
2971         * / unit testing of firmware.
2972         *
2973         * @param param
2974         *            Parameter enumeration.
2975         * @param value
2976         *            Value of parameter.
2977         * @param subValue
2978         *            Subvalue for parameter. Maximum value of 255.
2979         * @param ordinal
2980         *            Ordinal of parameter.
2981         * @return Error Code generated by function. 0 indicates no error.
2982         */
2983        public ErrorCode configSetParameter(ParamEnum param, double value, int subValue, int ordinal) {
2984                int timeoutMs = 0;
2985                return configSetParameter(param, value,  subValue,  ordinal,  timeoutMs);
2986        }
2987        /**
2988         * Sets a parameter.
2989         *
2990         * @param param
2991         *            Parameter enumeration.
2992         * @param value
2993         *            Value of parameter.
2994         * @param subValue
2995         *            Subvalue for parameter. Maximum value of 255.
2996         * @param ordinal
2997         *            Ordinal of parameter.
2998         * @param timeoutMs
2999         *            Timeout value in ms. If nonzero, function will wait for
3000         *            config success and report an error if it times out.
3001         *            If zero, no blocking or checking is performed.
3002         * @return Error Code generated by function. 0 indicates no error.
3003         */
3004        public ErrorCode configSetParameter(int param, double value, int subValue, int ordinal, int timeoutMs) {
3005                int retval = MotControllerJNI.ConfigSetParameter(m_handle, param,  value, subValue, ordinal,
3006                                timeoutMs);
3007                return ErrorCode.valueOf(retval);
3008        }
3009        /**
3010         * Sets a parameter.
3011         *
3012         * @param param
3013         *            Parameter enumeration.
3014         * @param value
3015         *            Value of parameter.
3016         * @param subValue
3017         *            Subvalue for parameter. Maximum value of 255.
3018         * @param ordinal
3019         *            Ordinal of parameter.
3020         * @return Error Code generated by function. 0 indicates no error.
3021         */
3022        public ErrorCode configSetParameter(int param, double value, int subValue, int ordinal) {
3023                int timeoutMs = 0;
3024                return configSetParameter( param,  value,  subValue,  ordinal,  timeoutMs);
3025        }
3026        /**
3027         * Gets a parameter.
3028         *
3029         * @param param
3030         *            Parameter enumeration.
3031         * @param ordinal
3032         *            Ordinal of parameter.
3033         * @param timeoutMs
3034         *            Timeout value in ms. If nonzero, function will wait for
3035         *            config success and report an error if it times out.
3036         *            If zero, no blocking or checking is performed.
3037         * @return Value of parameter.
3038         */
3039        public double configGetParameter(ParamEnum param, int ordinal, int timeoutMs) {
3040                return configGetParameter(param.value, ordinal, timeoutMs);
3041        }
3042        /**
3043         * Gets a parameter.
3044         *
3045         * @param param
3046         *            Parameter enumeration.
3047         * @param ordinal
3048         *            Ordinal of parameter.
3049         * @return Value of parameter.
3050         */
3051        public double configGetParameter(ParamEnum param, int ordinal) {
3052                int timeoutMs = 0;
3053                return configGetParameter(param, ordinal, timeoutMs);
3054        }
3055        /**
3056         * Gets a parameter.
3057         *
3058         * @param param
3059         *            Parameter enumeration.
3060         * @param ordinal
3061         *            Ordinal of parameter.
3062         * @param timeoutMs
3063         *            Timeout value in ms. If nonzero, function will wait for
3064         *            config success and report an error if it times out.
3065         *            If zero, no blocking or checking is performed.
3066         * @return Value of parameter.
3067         */
3068        public double configGetParameter(int param, int ordinal, int timeoutMs) {
3069                return MotControllerJNI.ConfigGetParameter(m_handle, param, ordinal, timeoutMs);
3070        }
3071        /**
3072         * Gets a parameter.
3073         *
3074         * @param param
3075         *            Parameter enumeration.
3076         * @param ordinal
3077         *            Ordinal of parameter.
3078         * @return Value of parameter.
3079         */
3080        public double configGetParameter(int param, int ordinal) {
3081                int timeoutMs = 0;
3082                return configGetParameter( param,  ordinal,  timeoutMs);
3083        }
3084
3085        // ------ Misc. ----------//
3086        public int getBaseID() {
3087                return MotControllerJNI.GetBaseID(m_handle);
3088        }
3089
3090        /**
3091         * @return control mode motor controller is in
3092         */
3093        public ControlMode getControlMode() {
3094                return m_controlMode;
3095        }
3096
3097        // ----- Follower ------//
3098        /**
3099         * Set the control mode and output value so that this motor controller will
3100         * follow another motor controller. Currently supports following Victor SPX,
3101         * Talon SRX, and Talon FX.
3102         *
3103         * @param masterToFollow
3104         *                                              Motor Controller object to follow.
3105         * @param followerType
3106         *                                              Type of following control.  Use AuxOutput1 to follow the master
3107         *                                              device's auxiliary output 1.
3108         *                                              Use PercentOutput for standard follower mode.
3109         */
3110        public void follow(IMotorController masterToFollow, FollowerType followerType) {
3111                int id32 = masterToFollow.getBaseID();
3112                int id24 = id32;
3113                id24 >>= 16;
3114                id24 = (short) id24;
3115                id24 <<= 8;
3116                id24 |= (id32 & 0xFF);
3117
3118                switch (followerType){
3119                        case PercentOutput:
3120                                set(ControlMode.Follower, (double)id24);
3121                                break;
3122                        case AuxOutput1:
3123                          /* follow the motor controller, but set the aux flag
3124                     * to ensure we follow the processed output */
3125                          set(ControlMode.Follower, (double)id24, DemandType.AuxPID, 0);
3126                                break;
3127                        default:
3128                          neutralOutput();
3129                                break;
3130                }
3131        }
3132        /**
3133         * Set the control mode and output value so that this motor controller will
3134         * follow another motor controller. Currently supports following Victor SPX,
3135         * Talon SRX, and Talon FX.
3136         *
3137         * @param masterToFollow Motor Controller to follow
3138         */
3139        public void follow(IMotorController masterToFollow) {
3140    follow(masterToFollow, FollowerType.PercentOutput);
3141        }
3142        /**
3143         * When master makes a device, this routine is called to signal the update.
3144         */
3145        public void valueUpdated() {
3146                // MT
3147        }
3148
3149    //------Config All------//
3150
3151    /**
3152     * Configures all base persistant settings.
3153     *
3154         * @param allConfigs        Object with all of the base persistant settings
3155     * @param timeoutMs
3156     *              Timeout value in ms. If nonzero, function will wait for
3157     *              config success and report an error if it times out.
3158     *              If zero, no blocking or checking is performed.
3159     *
3160     * @return Error Code generated by function. 0 indicates no error.
3161     */
3162    protected ErrorCode baseConfigAllSettings(BaseMotorControllerConfiguration allConfigs, int timeoutMs) {
3163
3164
3165        ErrorCollection errorCollection = new ErrorCollection();
3166
3167        errorCollection.NewError(configFactoryDefault(timeoutMs));
3168
3169        if(BaseMotorControllerUtil.openloopRampDifferent(allConfigs)) errorCollection.NewError(configOpenloopRamp(allConfigs.openloopRamp, timeoutMs));
3170                if(BaseMotorControllerUtil.closedloopRampDifferent(allConfigs)) errorCollection.NewError(configClosedloopRamp(allConfigs.closedloopRamp, timeoutMs));
3171                if(BaseMotorControllerUtil.peakOutputForwardDifferent(allConfigs)) errorCollection.NewError(configPeakOutputForward(allConfigs.peakOutputForward, timeoutMs));
3172                if(BaseMotorControllerUtil.peakOutputReverseDifferent(allConfigs)) errorCollection.NewError(configPeakOutputReverse(allConfigs.peakOutputReverse, timeoutMs));
3173                if(BaseMotorControllerUtil.nominalOutputForwardDifferent(allConfigs)) errorCollection.NewError(configNominalOutputForward(allConfigs.nominalOutputForward, timeoutMs));
3174                if(BaseMotorControllerUtil.nominalOutputReverseDifferent(allConfigs)) errorCollection.NewError(configNominalOutputReverse(allConfigs.nominalOutputReverse, timeoutMs));
3175                if(BaseMotorControllerUtil.neutralDeadbandDifferent(allConfigs)) errorCollection.NewError(configNeutralDeadband(allConfigs.neutralDeadband, timeoutMs));
3176                if(BaseMotorControllerUtil.voltageCompSaturationDifferent(allConfigs)) errorCollection.NewError(configVoltageCompSaturation(allConfigs.voltageCompSaturation, timeoutMs));
3177                if(BaseMotorControllerUtil.voltageMeasurementFilterDifferent(allConfigs)) errorCollection.NewError(configVoltageMeasurementFilter(allConfigs.voltageMeasurementFilter, timeoutMs));
3178                if(BaseMotorControllerUtil.velocityMeasurementPeriodDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementPeriod(allConfigs.velocityMeasurementPeriod, timeoutMs));
3179                if(BaseMotorControllerUtil.velocityMeasurementWindowDifferent(allConfigs)) errorCollection.NewError(configVelocityMeasurementWindow(allConfigs.velocityMeasurementWindow, timeoutMs));
3180                if(BaseMotorControllerUtil.forwardSoftLimitThresholdDifferent(allConfigs)) errorCollection.NewError(configForwardSoftLimitThreshold(allConfigs.forwardSoftLimitThreshold, timeoutMs));
3181                if(BaseMotorControllerUtil.reverseSoftLimitThresholdDifferent(allConfigs)) errorCollection.NewError(configReverseSoftLimitThreshold(allConfigs.reverseSoftLimitThreshold, timeoutMs));
3182                if(BaseMotorControllerUtil.forwardSoftLimitEnableDifferent(allConfigs)) errorCollection.NewError(configForwardSoftLimitEnable(allConfigs.forwardSoftLimitEnable, timeoutMs));
3183                if(BaseMotorControllerUtil.reverseSoftLimitEnableDifferent(allConfigs)) errorCollection.NewError(configReverseSoftLimitEnable(allConfigs.reverseSoftLimitEnable, timeoutMs));
3184                if(BaseMotorControllerUtil.auxPIDPolarityDifferent(allConfigs)) errorCollection.NewError(configAuxPIDPolarity(allConfigs.auxPIDPolarity, timeoutMs));
3185                if(BaseMotorControllerUtil.motionCruiseVelocityDifferent(allConfigs)) errorCollection.NewError(configMotionCruiseVelocity(allConfigs.motionCruiseVelocity, timeoutMs));
3186                if(BaseMotorControllerUtil.motionAccelerationDifferent(allConfigs)) errorCollection.NewError(configMotionAcceleration(allConfigs.motionAcceleration, timeoutMs));
3187                if(BaseMotorControllerUtil.motionSCurveStrength(allConfigs)) errorCollection.NewError(configMotionSCurveStrength(allConfigs.motionCurveStrength, timeoutMs));
3188                if(BaseMotorControllerUtil.motionProfileTrajectoryPeriodDifferent(allConfigs)) errorCollection.NewError(configMotionProfileTrajectoryPeriod(allConfigs.motionProfileTrajectoryPeriod, timeoutMs));
3189                if(BaseMotorControllerUtil.feedbackNotContinuousDifferent(allConfigs)) errorCollection.NewError(configFeedbackNotContinuous(allConfigs.feedbackNotContinuous, timeoutMs));
3190                if(BaseMotorControllerUtil.remoteSensorClosedLoopDisableNeutralOnLOSDifferent(allConfigs)) errorCollection.NewError(configRemoteSensorClosedLoopDisableNeutralOnLOS(allConfigs.remoteSensorClosedLoopDisableNeutralOnLOS, timeoutMs));
3191                if(BaseMotorControllerUtil.clearPositionOnLimitFDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnLimitF(allConfigs.clearPositionOnLimitF, timeoutMs));
3192                if(BaseMotorControllerUtil.clearPositionOnLimitRDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnLimitR(allConfigs.clearPositionOnLimitR, timeoutMs));
3193                if(BaseMotorControllerUtil.clearPositionOnQuadIdxDifferent(allConfigs)) errorCollection.NewError(configClearPositionOnQuadIdx(allConfigs.clearPositionOnQuadIdx, timeoutMs));
3194                if(BaseMotorControllerUtil.limitSwitchDisableNeutralOnLOSDifferent(allConfigs)) errorCollection.NewError(configLimitSwitchDisableNeutralOnLOS(allConfigs.limitSwitchDisableNeutralOnLOS, timeoutMs));
3195                if(BaseMotorControllerUtil.softLimitDisableNeutralOnLOSDifferent(allConfigs)) errorCollection.NewError(configSoftLimitDisableNeutralOnLOS(allConfigs.softLimitDisableNeutralOnLOS, timeoutMs));
3196                if(BaseMotorControllerUtil.pulseWidthPeriod_EdgesPerRotDifferent(allConfigs)) errorCollection.NewError(configPulseWidthPeriod_EdgesPerRot(allConfigs.pulseWidthPeriod_EdgesPerRot, timeoutMs));
3197                if(BaseMotorControllerUtil.pulseWidthPeriod_FilterWindowSzDifferent(allConfigs)) errorCollection.NewError(configPulseWidthPeriod_FilterWindowSz(allConfigs.pulseWidthPeriod_FilterWindowSz, timeoutMs));
3198                if(BaseMotorControllerUtil.trajectoryInterpolationEnableDifferent(allConfigs)) errorCollection.NewError(configMotionProfileTrajectoryInterpolationEnable(allConfigs.trajectoryInterpolationEnable, timeoutMs));
3199
3200                //Custom Parameters
3201                if(BaseMotorControllerUtil.customParam0Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam0, 0, timeoutMs));
3202                if(BaseMotorControllerUtil.customParam1Different(allConfigs)) errorCollection.NewError(configSetCustomParam(allConfigs.customParam1, 1, timeoutMs));
3203
3204        //--------Slots---------------//
3205        errorCollection.NewError(configureSlotPrivate(allConfigs.slot0, 0, timeoutMs, allConfigs.enableOptimizations));
3206        errorCollection.NewError(configureSlotPrivate(allConfigs.slot1, 1, timeoutMs, allConfigs.enableOptimizations));
3207        errorCollection.NewError(configureSlotPrivate(allConfigs.slot2, 2, timeoutMs, allConfigs.enableOptimizations));
3208        errorCollection.NewError(configureSlotPrivate(allConfigs.slot3, 3, timeoutMs, allConfigs.enableOptimizations));
3209
3210        //----------Remote Feedback Filters----------//
3211                errorCollection.NewError(configureFilter(allConfigs.remoteFilter0, 0, timeoutMs, allConfigs.enableOptimizations));
3212        errorCollection.NewError(configureFilter(allConfigs.remoteFilter1, 1, timeoutMs, allConfigs.enableOptimizations));
3213
3214        return errorCollection._worstError;
3215    }
3216
3217
3218    private ErrorCode configureSlotPrivate( SlotConfiguration slot, int slotIdx, int timeoutMs, boolean enableOptimization) {
3219
3220        ErrorCollection errorCollection = new ErrorCollection();
3221        //------ General Close loop ----------//
3222
3223
3224
3225                if(SlotConfigurationUtil.kPDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kP(slotIdx, slot.kP, timeoutMs));
3226                if(SlotConfigurationUtil.kIDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kI(slotIdx, slot.kI, timeoutMs));
3227                if(SlotConfigurationUtil.kDDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kD(slotIdx, slot.kD, timeoutMs));
3228                if(SlotConfigurationUtil.kFDifferent(slot) || !enableOptimization) errorCollection.NewError(config_kF(slotIdx, slot.kF, timeoutMs));
3229                if(SlotConfigurationUtil.integralZoneDifferent(slot) || !enableOptimization) errorCollection.NewError(config_IntegralZone(slotIdx, slot.integralZone, timeoutMs));
3230                if(SlotConfigurationUtil.allowableClosedloopErrorDifferent(slot) || !enableOptimization) errorCollection.NewError(configAllowableClosedloopError(slotIdx, slot.allowableClosedloopError, timeoutMs));
3231                if(SlotConfigurationUtil.maxIntegralAccumulatorDifferent(slot) || !enableOptimization) errorCollection.NewError(configMaxIntegralAccumulator(slotIdx, slot.maxIntegralAccumulator, timeoutMs));
3232                if(SlotConfigurationUtil.closedLoopPeakOutputDifferent(slot) || !enableOptimization) errorCollection.NewError(configClosedLoopPeakOutput(slotIdx, slot.closedLoopPeakOutput, timeoutMs));
3233                if(SlotConfigurationUtil.closedLoopPeriodDifferent(slot) || !enableOptimization) errorCollection.NewError(configClosedLoopPeriod(slotIdx, slot.closedLoopPeriod, timeoutMs));
3234
3235        return errorCollection._worstError;
3236
3237    }
3238
3239
3240    /**
3241     * Configures all slot persistant settings (overloaded so timeoutMs is 50 ms
3242     * and slotIdx is 0
3243     *
3244         * @param slot        Object with all of the slot persistant settings
3245     *
3246     * @return Error Code generated by function. 0 indicates no error.
3247     */
3248    public ErrorCode configureSlot( SlotConfiguration slot) {
3249        int slotIdx = 0;
3250        int timeoutMs = 50;
3251        return configureSlotPrivate(slot, slotIdx, timeoutMs, false);
3252        }
3253        /**
3254     * Configures all slot persistant settings
3255     *
3256         * @param slot        Object with all of the slot persistant settings
3257         * @param slotIdx         Index of slot to configure
3258         * @param timeoutMs
3259     *              Timeout value in ms. If nonzero, function will wait for
3260     *              config success and report an error if it times out.
3261     *              If zero, no blocking or checking is performed.
3262     *
3263     * @return Error Code generated by function. 0 indicates no error.
3264     */
3265    public ErrorCode configureSlot( SlotConfiguration slot, int slotIdx, int timeoutMs) {
3266        return configureSlotPrivate(slot, slotIdx, timeoutMs, false);
3267    }
3268    /**
3269     * Gets all slot persistant settings.
3270     *
3271         * @param slot        Object with all of the slot persistant settings
3272         * @param slotIdx     Parameter slot for the constant.
3273     * @param timeoutMs
3274     *              Timeout value in ms. If nonzero, function will wait for
3275     *              config success and report an error if it times out.
3276     *              If zero, no blocking or checking is performed.
3277     */
3278    public void getSlotConfigs(SlotConfiguration slot, int slotIdx, int timeoutMs) {
3279        slot.kP = (double) configGetParameter(ParamEnum.eProfileParamSlot_P, slotIdx, timeoutMs);
3280        slot.kI = (double) configGetParameter(ParamEnum.eProfileParamSlot_I, slotIdx, timeoutMs);
3281        slot.kD = (double) configGetParameter(ParamEnum.eProfileParamSlot_D, slotIdx, timeoutMs);
3282        slot.kF = (double) configGetParameter(ParamEnum.eProfileParamSlot_F, slotIdx, timeoutMs);
3283        slot.integralZone = (int) configGetParameter(ParamEnum.eProfileParamSlot_IZone, slotIdx, timeoutMs);
3284        slot.allowableClosedloopError = (int) configGetParameter(ParamEnum.eProfileParamSlot_AllowableErr, slotIdx, timeoutMs);
3285        slot.maxIntegralAccumulator = (double) configGetParameter(ParamEnum.eProfileParamSlot_MaxIAccum, slotIdx, timeoutMs);
3286        slot.closedLoopPeakOutput = (double) configGetParameter(ParamEnum.eProfileParamSlot_PeakOutput, slotIdx, timeoutMs);
3287        slot.closedLoopPeriod = (int) configGetParameter(ParamEnum.ePIDLoopPeriod, slotIdx, timeoutMs);
3288    }
3289    /**
3290     * Gets all slot persistant settings (overloaded so timeoutMs is 50 ms
3291     * and slotIdx is 0
3292     *
3293         * @param slot        Object with all of the slot persistant settings
3294     */
3295    public void getSlotConfigs( SlotConfiguration slot) {
3296        int slotIdx = 0;
3297        int timeoutMs = 50;
3298        getSlotConfigs(slot, slotIdx, timeoutMs);
3299    }
3300
3301
3302    /**
3303     * Configures all filter persistant settings.
3304     *
3305         * @deprecated Use the 3-parameter configureFilter.  4-param version is deprecated and will be removed.
3306         * @param filter        Object with all of the filter persistant settings
3307     * @param ordinal       0 for remote sensor 0 and 1 for remote sensor 1.
3308     * @param timeoutMs
3309     *              Timeout value in ms. If nonzero, function will wait for
3310     *              config success and report an error if it times out.
3311     *              If zero, no blocking or checking is performed.
3312         * @param enableOptimizations   Enable the optimization technique
3313     *
3314     * @return Error Code generated by function. 0 indicates no error.
3315     */
3316        @Deprecated
3317    public ErrorCode configureFilter( FilterConfiguration filter, int ordinal, int timeoutMs, boolean enableOptimizations) {
3318                if(FilterConfigUtil.filterConfigurationDifferent(filter) || !enableOptimizations)
3319                        return configRemoteFeedbackFilter(filter.remoteSensorDeviceID, filter.remoteSensorSource, ordinal, timeoutMs);
3320
3321                return ErrorCode.OK;
3322        }
3323        /**
3324     * Configures all filter persistant settings.
3325     *
3326         * @deprecated Use configAll instead.
3327         * @param filter        Object with all of the filter persistant settings
3328     * @param ordinal       0 for remote sensor 0 and 1 for remote sensor 1.
3329     * @param timeoutMs
3330     *              Timeout value in ms. If nonzero, function will wait for
3331     *              config success and report an error if it times out.
3332     *              If zero, no blocking or checking is performed.
3333     *
3334     * @return Error Code generated by function. 0 indicates no error.
3335     */
3336        @Deprecated
3337    public ErrorCode configureFilter( FilterConfiguration filter, int ordinal, int timeoutMs) {
3338                return configureFilter(filter, ordinal, timeoutMs, false);
3339    }
3340    /**
3341     * Configures all filter persistant settings (overloaded so timeoutMs is 50 ms
3342     * and ordinal is 0).
3343     *
3344         * @deprecated Use configAll instead.
3345         * @param filter        Object with all of the filter persistant settings
3346     *
3347     * @return Error Code generated by function. 0 indicates no error.
3348     */
3349        @Deprecated
3350    public ErrorCode configureFilter( FilterConfiguration filter) {
3351        int ordinal = 0;
3352        int timeoutMs = 50;
3353        return configureFilter(filter, ordinal, timeoutMs, false);
3354    }
3355
3356    /**
3357     * Gets all filter persistant settings.
3358     *
3359         * @param filter        Object with all of the filter persistant settings
3360     * @param ordinal       0 for remote sensor 0 and 1 for remote sensor 1.
3361     * @param timeoutMs
3362     *              Timeout value in ms. If nonzero, function will wait for
3363     *              config success and report an error if it times out.
3364     *              If zero, no blocking or checking is performed.
3365     */
3366    public void getFilterConfigs(FilterConfiguration filter, int ordinal, int timeoutMs) {
3367
3368        filter.remoteSensorDeviceID = (int) configGetParameter(ParamEnum.eRemoteSensorDeviceID, ordinal, timeoutMs);
3369        filter.remoteSensorSource = RemoteSensorSource.valueOf(configGetParameter(ParamEnum.eRemoteSensorSource, ordinal, timeoutMs));
3370
3371    }
3372    /**
3373     * Gets all filter persistant settings (overloaded so timeoutMs is 50 ms
3374     * and ordinal is 0).
3375     *
3376         * @param filter        Object with all of the filter persistant settings
3377     */
3378    public void getFilterConfigs(FilterConfiguration filter) {
3379        int ordinal = 0;
3380        int timeoutMs = 50;
3381        getFilterConfigs(filter, ordinal, timeoutMs);
3382    }
3383    /**
3384     * Configures all base PID set persistant settings.
3385     *
3386         * @param pid           Object with all of the base PID set persistant settings
3387     * @param pidIdx        0 for Primary closed-loop. 1 for auxiliary closed-loop.
3388     * @param timeoutMs
3389     *              Timeout value in ms. If nonzero, function will wait for
3390     *              config success and report an error if it times out.
3391     *              If zero, no blocking or checking is performed.
3392     *
3393     * @return Error Code generated by function. 0 indicates no error.
3394     */
3395    protected ErrorCode baseConfigurePID(BasePIDSetConfiguration pid, int pidIdx, int timeoutMs) {
3396
3397        return configSelectedFeedbackCoefficient(pid.selectedFeedbackCoefficient, pidIdx, timeoutMs);
3398
3399    }
3400    /**
3401     * Gets all base PID set persistant settings.
3402     *
3403         * @param pid           Object with all of the base PID set persistant settings
3404     * @param pidIdx        0 for Primary closed-loop. 1 for auxiliary closed-loop.
3405     * @param timeoutMs
3406     *              Timeout value in ms. If nonzero, function will wait for
3407     *              config success and report an error if it times out.
3408     *              If zero, no blocking or checking is performed.
3409     */
3410    protected void baseGetPIDConfigs(BasePIDSetConfiguration pid, int pidIdx, int timeoutMs) {
3411
3412        pid.selectedFeedbackCoefficient = (double) configGetParameter(ParamEnum.eSelectedSensorCoefficient, pidIdx, timeoutMs);
3413
3414    }
3415    /**
3416     * Gets all base persistant settings.
3417     *
3418         * @param allConfigs        Object with all of the base persistant settings
3419     * @param timeoutMs
3420     *              Timeout value in ms. If nonzero, function will wait for
3421     *              config success and report an error if it times out.
3422     *              If zero, no blocking or checking is performed.
3423     */
3424    protected void baseGetAllConfigs(BaseMotorControllerConfiguration allConfigs, int timeoutMs) {
3425
3426
3427        allConfigs.openloopRamp = (double) configGetParameter(ParamEnum.eOpenloopRamp, 0, timeoutMs);
3428        allConfigs.closedloopRamp = (double) configGetParameter(ParamEnum.eClosedloopRamp, 0, timeoutMs);
3429        allConfigs.peakOutputForward = (double) configGetParameter(ParamEnum.ePeakPosOutput, 0, timeoutMs);
3430        allConfigs.peakOutputReverse = (double) configGetParameter(ParamEnum.ePeakNegOutput, 0, timeoutMs);
3431        allConfigs.nominalOutputForward = (double) configGetParameter(ParamEnum.eNominalPosOutput, 0, timeoutMs);
3432        allConfigs.nominalOutputReverse = (double) configGetParameter(ParamEnum.eNominalNegOutput, 0, timeoutMs);
3433        allConfigs.neutralDeadband = (double) configGetParameter(ParamEnum.eNeutralDeadband, 0, timeoutMs);
3434        allConfigs.voltageCompSaturation = (double) configGetParameter(ParamEnum.eNominalBatteryVoltage, 0, timeoutMs);
3435        allConfigs.voltageMeasurementFilter = (int) configGetParameter(ParamEnum.eBatteryVoltageFilterSize, 0, timeoutMs);
3436        allConfigs.velocityMeasurementPeriod = SensorVelocityMeasPeriod.valueOf(configGetParameter(ParamEnum.eSampleVelocityPeriod, 0, timeoutMs));
3437        allConfigs.velocityMeasurementWindow = (int) configGetParameter(ParamEnum.eSampleVelocityWindow, 0, timeoutMs);
3438        allConfigs.forwardSoftLimitThreshold = (int) configGetParameter(ParamEnum.eForwardSoftLimitThreshold, 0, timeoutMs);
3439        allConfigs.reverseSoftLimitThreshold = (int) configGetParameter(ParamEnum.eReverseSoftLimitThreshold, 0, timeoutMs);
3440        allConfigs.forwardSoftLimitEnable = configGetParameter(ParamEnum.eForwardSoftLimitEnable, 0, timeoutMs) != 0.0;
3441        allConfigs.reverseSoftLimitEnable = configGetParameter(ParamEnum.eReverseSoftLimitEnable, 0, timeoutMs) != 0.0; //Note, fix in firmware
3442
3443        getSlotConfigs(allConfigs.slot0, 0, timeoutMs);
3444        getSlotConfigs(allConfigs.slot1, 1, timeoutMs);
3445        getSlotConfigs(allConfigs.slot2, 2, timeoutMs);
3446        getSlotConfigs(allConfigs.slot3, 3, timeoutMs);
3447
3448        allConfigs.auxPIDPolarity = configGetParameter(ParamEnum.ePIDLoopPolarity, 1, timeoutMs) != 0.0;
3449
3450        getFilterConfigs(allConfigs.remoteFilter0, 0, timeoutMs);
3451        getFilterConfigs(allConfigs.remoteFilter1, 1, timeoutMs);
3452
3453        allConfigs.motionCruiseVelocity = (int) configGetParameter(ParamEnum.eMotMag_VelCruise, 0, timeoutMs);
3454                allConfigs.motionAcceleration = (int) configGetParameter(ParamEnum.eMotMag_Accel, 0, timeoutMs);
3455                allConfigs.motionCurveStrength = (int) configGetParameter(ParamEnum.eMotMag_SCurveLevel, 0, timeoutMs);
3456        allConfigs.motionProfileTrajectoryPeriod = (int) configGetParameter(ParamEnum.eMotionProfileTrajectoryPointDurationMs, 0, timeoutMs);
3457        allConfigs.customParam0 = (int) configGetParameter(ParamEnum.eCustomParam, 0,  timeoutMs);
3458        allConfigs.customParam1 = (int) configGetParameter(ParamEnum.eCustomParam, 1,  timeoutMs);
3459
3460
3461        allConfigs.feedbackNotContinuous = configGetParameter(ParamEnum.eFeedbackNotContinuous, 0, timeoutMs) != 0.0;
3462        allConfigs.remoteSensorClosedLoopDisableNeutralOnLOS = configGetParameter(ParamEnum.eRemoteSensorClosedLoopDisableNeutralOnLOS, 0, timeoutMs) != 0.0;
3463        allConfigs.clearPositionOnLimitF = configGetParameter(ParamEnum.eClearPositionOnLimitF, 0, timeoutMs) != 0.0;
3464        allConfigs.clearPositionOnLimitR = configGetParameter(ParamEnum.eClearPositionOnLimitR, 0, timeoutMs) != 0.0;
3465        allConfigs.clearPositionOnQuadIdx = configGetParameter(ParamEnum.eClearPositionOnQuadIdx, 0, timeoutMs) != 0.0;
3466        allConfigs.limitSwitchDisableNeutralOnLOS = configGetParameter(ParamEnum.eLimitSwitchDisableNeutralOnLOS, 0, timeoutMs) != 0.0;
3467        allConfigs.softLimitDisableNeutralOnLOS = configGetParameter(ParamEnum.eSoftLimitDisableNeutralOnLOS, 0, timeoutMs) != 0.0;
3468        allConfigs.pulseWidthPeriod_EdgesPerRot = (int) configGetParameter(ParamEnum.ePulseWidthPeriod_EdgesPerRot, 0, timeoutMs);
3469        allConfigs.pulseWidthPeriod_FilterWindowSz = (int) configGetParameter(ParamEnum.ePulseWidthPeriod_FilterWindowSz, 0, timeoutMs);
3470
3471
3472    }
3473
3474}