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