001/* Copyright (C) Cross The Road Electronics 2024 */
002package com.ctre.phoenix.motorcontrol.can;
003
004import com.ctre.phoenix.CTREJNIWrapper;
005
006public class MotControllerJNI extends CTREJNIWrapper {
007
008        public static native long Create(int baseArbId);
009
010        public static native long Create2(int deviceID, String model, String canbus);
011
012    public static native int JNI_destroy_MotController(long handle);
013
014        //public static native void JNI_destroy_AllMotControllers();
015
016        /**
017         * Returns the Device ID
018         *
019         * @param handle
020         *            handle of device.
021         *
022         * @return Device number.
023         */
024        public static native int GetDeviceNumber(long handle);
025
026        public static native int GetBaseID(long handle);
027
028        /**
029         * Sets the demand (output) of the motor controller.
030         *
031         * @param handle
032         *            handle of device.
033         * @param mode
034         *            Control Mode of the Motor Controller
035         * @param demand0
036         *            Primary Demand value
037         * @param demand1
038         *            Secondary Demand value
039         **/
040        public static native void SetDemand(long handle, int mode, int demand0, int demand1);
041
042        /**
043         * Sets the demand (output) of the motor controller.
044         **/
045        public static native void Set_4(long handle, int mode, double demand0, double demand1, int demand1Type);
046
047        /**
048         * Sets the mode of operation during neutral throttle output.
049         *
050         * @param handle
051         *            handle of device.
052         * @param neutralMode
053         *            The desired mode of operation when the Controller output
054         *            throttle is neutral (ie brake/coast)
055         **/
056        public static native void SetNeutralMode(long handle, int neutralMode);
057
058        /**
059         * Sets the phase of the sensor. Use when controller forward/reverse output
060         * doesn't correlate to appropriate forward/reverse reading of sensor.
061         *
062         * @param handle
063         *            handle of device.
064         * @param PhaseSensor
065         *            Indicates whether to invert the phase of the sensor.
066         **/
067        public static native void SetSensorPhase(long handle, boolean PhaseSensor);
068
069        /**
070         * Inverts the output of the motor controller. LEDs, sensor phase, and limit
071         * switches will also be inverted to match the new forward/reverse
072         * directions.
073         *
074         * @param handle
075         *            handle of device.
076         * @param invert
077         *            Invert state to set.
078         **/
079        public static native void SetInverted(long handle, boolean invert);
080
081        /**
082         * Inverts the output of the motor controller. LEDs, sensor phase, and limit
083         * switches will also be inverted to match the new forward/reverse
084         * directions.
085         *
086         * @param handle
087         *            handle of device.
088         * @param invert
089         *            Invert state to set.
090         **/
091        public static native void SetInverted_2(long handle, int invert);
092
093        /**
094         * Revert all configurations to factory default values.
095         * Use this before your individual config* calls to avoid having to config every single param.
096         *
097         * Alternatively you can use the configAllSettings routine.
098         *
099         * @param handle
100         *            handle of device.
101         * @param timeoutMs
102         *            Timeout value in ms. Function will generate error if config is
103         *            not successful within timeout.
104         * @return Error Code generated by function. 0 indicates no error.
105         */
106        public static native int ConfigFactoryDefault(long handle, int timeoutMs);
107
108        /**
109         * Configures the open-loop ramp rate of throttle output.
110         *
111         * @param handle
112         *            handle of device.
113         * @param secondsFromNeutralToFull
114         *            Minimum desired time to go from neutral to full throttle. A
115         *            value of '0' will disable the ramp.
116         * @param timeoutMs
117         *            Timeout value in ms. Function will generate error if config is
118         *            not successful within timeout.
119         * @return Error Code generated by function. 0 indicates no error.
120         */
121        public static native int ConfigOpenLoopRamp(long handle, double secondsFromNeutralToFull, int timeoutMs);
122
123        /**
124         * Configures the closed-loop ramp rate of throttle output.
125         *
126         * @param handle
127         *            handle of device.
128         * @param secondsFromNeutralToFull
129         *            Minimum desired time to go from neutral to full throttle. A
130         *            value of '0' will disable the ramp.
131         * @param timeoutMs
132         *            Timeout value in ms. @see #ConfigOpenLoopRamp
133         * @return Error Code generated by function. 0 indicates no error.
134         */
135        public static native int ConfigClosedLoopRamp(long handle, double secondsFromNeutralToFull, int timeoutMs);
136
137        /**
138         * Configures the forward peak output percentage.
139         *
140         * @param handle
141         *            handle of device.
142         * @param percentOut
143         *            Desired peak output percentage.
144         * @param timeoutMs
145         *            Timeout value in ms. @see #ConfigOpenLoopRamp
146         * @return Error Code generated by function. 0 indicates no error.
147         */
148        public static native int ConfigPeakOutputForward(long handle, double percentOut, int timeoutMs);
149
150        /**
151         * Configures the reverse peak output percentage.
152         *
153         * @param handle
154         *            handle of device.
155         * @param percentOut
156         *            Desired peak output percentage.
157         * @param timeoutMs
158         *            Timeout value in ms. @see #ConfigOpenLoopRamp
159         * @return Error Code generated by function. 0 indicates no error.
160         */
161        public static native int ConfigPeakOutputReverse(long handle, double percentOut, int timeoutMs);
162
163        /**
164         * Configures the forward nominal output percentage.
165         *
166         * @param handle
167         *            handle of device.
168         * @param percentOut
169         *            Nominal (minimum) percent output.
170         * @param timeoutMs
171         *            Timeout value in ms. @see #ConfigOpenLoopRamp
172         * @return Error Code generated by function. 0 indicates no error.
173         */
174        public static native int ConfigNominalOutputForward(long handle, double percentOut, int timeoutMs);
175
176        /**
177         * Configures the reverse nominal output percentage.
178         *
179         * @param handle
180         *            handle of device.
181         * @param percentOut
182         *            Nominal (minimum) percent output.
183         * @param timeoutMs
184         *            Timeout value in ms. @see #ConfigOpenLoopRamp
185         * @return Error Code generated by function. 0 indicates no error.
186         */
187        public static native int ConfigNominalOutputReverse(long handle, double percentOut, int timeoutMs);
188
189        /**
190         * Configures the output deadband percentage.
191         *
192         * @param handle
193         *            handle of device.
194         * @param percentDeadband
195         *            Desired deadband percentage. Minimum is 0.1%, Maximum is 25%.
196         * @param timeoutMs
197         *            Timeout value in ms. @see #ConfigOpenLoopRamp
198         * @return Error Code generated by function. 0 indicates no error.
199         */
200        public static native int ConfigNeutralDeadband(long handle, double percentDeadband, int timeoutMs);
201
202        /**
203         * Configures the Voltage Compensation saturation voltage.
204         *
205         * @param handle
206         *            handle of device.
207         * @param voltage
208         *            TO-DO: Comment me!
209         * @param timeoutMs
210         *            Timeout value in ms. @see #ConfigOpenLoopRamp
211         * @return Error Code generated by function. 0 indicates no error.
212         */
213        public static native int ConfigVoltageCompSaturation(long handle, double voltage, int timeoutMs);
214
215        /**
216         * Configures the voltage measurement filter.
217         *
218         * @param handle
219         *            handle of device.
220         * @param filterWindowSamples
221         *            Number of samples in the rolling average of voltage
222         *            measurement.
223         * @param timeoutMs
224         *            Timeout value in ms. @see #ConfigOpenLoopRamp
225         * @return Error Code generated by function. 0 indicates no error.
226         */
227        public static native int ConfigVoltageMeasurementFilter(long handle, int filterWindowSamples, int timeoutMs);
228
229        /**
230         * Enables voltage compensation. If enabled, voltage compensation works in
231         * all control modes.
232         *
233         * Be sure to configure the saturation voltage before enabling this.
234         *
235         * @param handle
236         *            handle of device.
237         * @param enable
238         *            Enable state of voltage compensation.
239         **/
240        public static native void EnableVoltageCompensation(long handle, boolean enable);
241
242        /**
243         * Gets the invert state of the motor controller.
244         *
245         * @param handle
246         *            handle of device.
247         * @return The invert state.
248         */
249        public static native boolean GetInverted(long handle);
250
251        /**
252         * Gets the bus voltage seen by the motor controller.
253         *
254         * @param handle
255         *            handle of device.
256         * @return The bus voltage value (in volts).
257         */
258        public static native double GetBusVoltage(long handle);
259
260        /**
261         * Gets the output percentage of the motor controller.
262         *
263         * @param handle
264         *            handle of device.
265         * @return Output of the motor controller (in percent).
266         */
267        public static native double GetMotorOutputPercent(long handle);
268
269        /**
270         * Gets the output current of the motor controller.
271         * In the case of TalonSRX class, this routine returns supply current for legacy reasons.  In order to get the "true" output current, call GetStatorCurrent().
272         *
273         * @deprecated Use getStatorCurrent/getSupplyCurrent instead.
274         * @param handle
275         *                        handle of device
276         *
277         * @return The output current (in amps).
278         */
279        @Deprecated
280        public static native double GetOutputCurrent(long handle);
281
282        /**
283         * Gets the stator/output current of the motor controller.
284         *
285         * @param handle
286         *                        handle of device
287         * @return The stator/output current (in amps).
288         */
289        public static native double GetSupplyCurrent(long handle);
290
291        /**
292         * Gets the stator/output current of the motor controller.
293         *
294         * @param handle
295         *                        handle of device
296         * @return The stator/output current (in amps).
297         */
298        public static native double GetStatorCurrent(long handle);
299
300        /**
301         * Gets the temperature of the motor controller.
302         *
303         * @param handle
304         *            handle of device.
305         * @return The temperature of the motor controller (in 'C)
306         */
307        public static native double GetTemperature(long handle);
308
309        /**
310         * Configures the remote feedback filter.
311         *
312         * @param handle
313         *            handle of device.
314         * @param deviceID
315         *            ID of remote device.
316         * @param remoteSensorSource
317         *            Type of remote sensor.
318         * @param remoteOrdinal
319         *            Ordinal of remote source [0-1].
320         * @param timeoutMs
321         *            Timeout value in ms. @see #ConfigOpenLoopRamp
322         * @return Error Code generated by function. 0 indicates no error.
323         */
324        public static native int ConfigRemoteFeedbackFilter(long handle, int deviceID, int remoteSensorSource,
325                        int remoteOrdinal, int timeoutMs);
326
327        /**
328         * Select the feedback device for the motor controller.
329         *
330         * @param handle
331         *            handle of device.
332         * @param feedbackDevice
333         *            Feedback Device to select.
334         * @param pidIdx
335         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
336         * @param timeoutMs
337         *            Timeout value in ms. @see #ConfigOpenLoopRamp
338         * @return Error Code generated by function. 0 indicates no error.
339         */
340        public static native int ConfigSelectedFeedbackSensor(long handle, int feedbackDevice, int pidIdx, int timeoutMs);
341
342        public static native int ConfigSensorTerm(long handle, int sensorTerm, int feedbackDevice, int timeoutMs);
343
344        /**
345         * Get the selected sensor position.
346         *
347         * @param handle
348         *            handle of device.
349         * @param pidIdx
350         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
351         * @return Position of selected sensor (in Raw Sensor Units).
352         */
353        public static native int GetSelectedSensorPosition(long handle, int pidIdx);
354
355        /**
356         * Get the selected sensor velocity.
357         *
358         * @param handle
359         *            handle of device.
360         * @param pidIdx
361         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
362         * @return Velocity of selected sensor (in Raw Sensor Units per 100 ms).
363         */
364        public static native int GetSelectedSensorVelocity(long handle, int pidIdx);
365
366        /**
367         * Sets the sensor position to the given value.
368         *
369         * @param handle
370         *            handle of device.
371         * @param sensorPos
372         *            Position to set for the selected sensor (in Raw Sensor Units).
373         * @param pidIdx
374         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
375         * @param timeoutMs
376         *            Timeout value in ms. @see #ConfigOpenLoopRamp
377         * @return Error Code generated by function. 0 indicates no error.
378         */
379        public static native int SetSelectedSensorPosition(long handle, int sensorPos, int pidIdx, int timeoutMs);
380
381        /**
382         * Sets the period of the given control frame.
383         *
384         * @param handle
385         *            handle of device.
386         * @param frame
387         *            Frame whose period is to be changed.
388         * @param periodMs
389         *            Period in ms for the given frame.
390         * @return Error Code generated by function. 0 indicates no error.
391         */
392        public static native int SetControlFramePeriod(long handle, int frame, int periodMs);
393
394        /**
395         * Sets the period of the given status frame.
396         *
397         * @param handle
398         *            handle of device.
399         * @param frame
400         *            Frame whose period is to be changed.
401         * @param periodMs
402         *            Period in ms for the given frame.
403         * @param timeoutMs
404         *            Timeout value in ms. @see #ConfigOpenLoopRamp
405         * @return Error Code generated by function. 0 indicates no error.
406         */
407        public static native int SetStatusFramePeriod(long handle, int frame, int periodMs, int timeoutMs);
408
409        /**
410         * Gets the period of the given status frame.
411         *
412         * @param handle
413         *            handle of device.
414         * @param frame
415         *            Frame to get the period of.
416         * @param timeoutMs
417         *            Timeout value in ms. @see #ConfigOpenLoopRamp
418         * @return The period of the given status frame.
419         */
420        public static native int GetStatusFramePeriod(long handle, int frame, int timeoutMs);
421
422        /**
423         * Sets the period over which velocity measurements are taken.
424         *
425         * @param handle
426         *            handle of device.
427         * @param period
428         *            Desired period for the velocity measurement. @see
429         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
430         * @param timeoutMs
431         *            Timeout value in ms. @see #ConfigOpenLoopRamp
432         * @return Error Code generated by function. 0 indicates no error.
433         */
434        public static native int ConfigVelocityMeasurementPeriod(long handle, int period, int timeoutMs);
435
436        /**
437         * Sets the number of velocity samples used in the rolling average velocity
438         * measurement.
439         *
440         * @param handle
441         *            handle of device.
442         * @param windowSize
443         *            Number of samples in the rolling average of velocity
444         *            measurement.
445         * @param timeoutMs
446         *            Timeout value in ms. @see #ConfigOpenLoopRamp
447         * @return Error Code generated by function. 0 indicates no error.
448         */
449        public static native int ConfigVelocityMeasurementWindow(long handle, int windowSize, int timeoutMs);
450
451        /**
452         * Configures the forward limit switch for a remote source.
453         *
454         * @param handle
455         *            handle of device.
456         * @param type
457         *            Remote limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource
458         * @param normalOpenOrClose
459         *            Setting for normally open or normally closed.
460         * @param deviceID
461         *            Device ID of remote source.
462         * @param timeoutMs
463         *            Timeout value in ms. @see #ConfigOpenLoopRamp
464         * @return Error Code generated by function. 0 indicates no error.
465         */
466        public static native int ConfigForwardLimitSwitchSource(long handle, int type, int normalOpenOrClose, int deviceID,
467                        int timeoutMs);
468
469        /**
470         * Configures the reverse limit switch for a remote source.
471         *
472         * @param handle
473         *            handle of device.
474         * @param type
475         *            Remote limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource
476         * @param normalOpenOrClose
477         *            Setting for normally open or normally closed.
478         * @param deviceID
479         *            Device ID of remote source.
480         * @param timeoutMs
481         *            Timeout value in ms. @see #ConfigOpenLoopRamp
482         * @return Error Code generated by function. 0 indicates no error.
483         */
484        public static native int ConfigReverseLimitSwitchSource(long handle, int type, int normalOpenOrClose, int deviceID,
485                        int timeoutMs);
486
487        /**
488         * Sets the enable state for limit switches.
489         *
490         * @param handle
491         *            handle of device.
492         * @param enable
493         *            Enable state for limit switches.
494         **/
495        public static native void OverrideLimitSwitchesEnable(long handle, boolean enable);
496
497        /**
498         * Configures the forward soft limit.
499         *
500         * @param handle
501         *            handle of device.
502         * @param forwardSensorLimit
503         *            Forward Sensor Position Limit (in Raw Sensor Units).
504         * @param timeoutMs
505         *            Timeout value in ms. @see #ConfigOpenLoopRamp
506         * @return Error Code generated by function. 0 indicates no error.
507         */
508        public static native int ConfigForwardSoftLimitThreshold(long handle, int forwardSensorLimit, int timeoutMs);
509
510        /**
511         * Configures the reverse soft limit.
512         *
513         * @param handle
514         *            handle of device.
515         * @param reverseSensorLimit
516         *            Reverse Sensor Position Limit (in Raw Sensor Units).
517         * @param timeoutMs
518         *            Timeout value in ms. @see #ConfigOpenLoopRamp
519         * @return Error Code generated by function. 0 indicates no error.
520         */
521        public static native int ConfigReverseSoftLimitThreshold(long handle, int reverseSensorLimit, int timeoutMs);
522
523        public static native int ConfigForwardSoftLimitEnable(long handle, boolean enable, int timeoutMs);
524
525        public static native int ConfigReverseSoftLimitEnable(long handle, boolean enable, int timeoutMs);
526
527        /**
528         * Sets the enable state for soft limit switches.
529         *
530         * @param handle
531         *            handle of device.
532         * @param enable
533         *            Enable state for soft limit switches.
534         **/
535        public static native void OverrideSoftLimitsEnable(long handle, boolean enable);
536
537        /**
538         * Sets the 'P' constant in the given parameter slot.
539         * This is multiplied by closed loop error in sensor units.
540         * Note the closed loop output interprets a final value of 1023 as full output.
541         * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation)
542         *
543         * @param handle
544         *            handle of device.
545         * @param slotIdx
546         *            Parameter slot for the constant.
547         * @param value
548         *            Value of the P constant.
549         * @param timeoutMs
550         *            Timeout value in ms. @see #ConfigOpenLoopRamp
551         * @return Error Code generated by function. 0 indicates no error.
552         */
553        public static native int Config_kP(long handle, int slotIdx, double value, int timeoutMs);
554
555        /**
556         * Sets the 'I' constant in the given parameter slot.
557         * This is multiplied by accumulated closed loop error in sensor units every PID Loop.
558         * Note the closed loop output interprets a final value of 1023 as full output.
559         * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000),
560         * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].
561         *
562         * @param handle
563         *            handle of device.
564         * @param slotIdx
565         *            Parameter slot for the constant.
566         * @param value
567         *            Value of the I constant.
568         * @param timeoutMs
569         *            Timeout value in ms. @see #ConfigOpenLoopRamp
570         * @return Error Code generated by function. 0 indicates no error.
571         */
572        public static native int Config_kI(long handle, int slotIdx, double value, int timeoutMs);
573
574        /**
575         * Sets the 'D' constant in the given parameter slot.
576         *
577         * This is multiplied by derivative error (sensor units per PID loop, typically 1ms).
578         * Note the closed loop output interprets a final value of 1023 as full output.
579         * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)
580         *
581         * @param handle
582         *            handle of device.
583         * @param slotIdx
584         *            Parameter slot for the constant.
585         * @param value
586         *            Value of the D constant.
587         * @param timeoutMs
588         *            Timeout value in ms. @see #ConfigOpenLoopRamp
589         * @return Error Code generated by function. 0 indicates no error.
590         */
591        public static native int Config_kD(long handle, int slotIdx, double value, int timeoutMs);
592
593        /**
594         * Sets the 'F' constant in the given parameter slot.
595         *
596         * See documentation for calculation details.
597         * If using velocity, motion magic, or motion profile,
598         * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).
599         *
600         * @param handle
601         *            handle of device.
602         * @param slotIdx
603         *            Parameter slot for the constant.
604         * @param value
605         *            Value of the F constant.
606         * @param timeoutMs
607         *            Timeout value in ms. @see #ConfigOpenLoopRamp
608         * @return Error Code generated by function. 0 indicates no error.
609         */
610        public static native int Config_kF(long handle, int slotIdx, double value, int timeoutMs);
611
612        /**
613         * Sets the Integral Zone constant in the given parameter slot.
614         *
615         * @param handle
616         *            handle of device.
617         * @param slotIdx
618         *            Parameter slot for the constant.
619         * @param izone
620         *            Value of the Integral Zone constant.
621         * @param timeoutMs
622         *            Timeout value in ms. @see #ConfigOpenLoopRamp
623         * @return Error Code generated by function. 0 indicates no error.
624         */
625        public static native int Config_IntegralZone(long handle, int slotIdx, double izone, int timeoutMs);
626
627        /**
628         * Sets the allowable closed-loop error in the given parameter slot.
629         *
630         * @param handle
631         *            handle of device.
632         * @param slotIdx
633         *            Parameter slot for the constant.
634         * @param allowableClosedLoopError
635         *            Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity).
636         * @param timeoutMs
637         *            Timeout value in ms. @see #ConfigOpenLoopRamp
638         * @return Error Code generated by function. 0 indicates no error.
639         */
640        public static native int ConfigAllowableClosedloopError(long handle, int slotIdx, int allowableClosedLoopError,
641                        int timeoutMs);
642
643        /**
644         * Sets the maximum integral accumulator in the given parameter slot.
645         *
646         * @param handle
647         *            handle of device.
648         * @param slotIdx
649         *            Parameter slot for the constant.
650         * @param iaccum
651         *            Value of the maximum integral accumulator.
652         * @param timeoutMs
653         *            Timeout value in ms. @see #ConfigOpenLoopRamp
654         * @return Error Code generated by function. 0 indicates no error.
655         */
656        public static native int ConfigMaxIntegralAccumulator(long handle, int slotIdx, double iaccum, int timeoutMs);
657
658        /**
659         * Sets the integral accumulator.
660         *
661         * @param handle
662         *            handle of device.
663         * @param iaccum
664         *            Value to set for the integral accumulator.
665         * @param timeoutMs
666         *            Timeout value in ms. @see #ConfigOpenLoopRamp
667         * @param pidIdx
668         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
669         *            secondary loop.
670         * @return Error Code generated by function. 0 indicates no error.
671         */
672        public static native int SetIntegralAccumulator(long handle, double iaccum, int pidIdx, int timeoutMs);
673
674        /**
675         * Gets the closed-loop error. The units depend on which control mode is in
676         * use.
677         *
678         * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target
679         * and current sensor value (in sensor units.  Example 4096 units per rotation for CTRE Mag Encoder).
680         *
681         * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target
682         * and current sensor value (in sensor units per 100ms).
683         *
684         * If using motion profiling or Motion Magic, closed loop error is calculated against the current target,
685         * and not the "final" target at the end of the profile/movement.
686         *
687         * See Phoenix-Documentation information on units.
688         *
689         * @param handle
690         *            handle of device.
691         * @param pidIdx
692         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
693         *            secondary loop.
694         * @return Closed-loop error value.
695         */
696        public static native int GetClosedLoopError(long handle, int pidIdx);
697
698        /**
699         * Gets the iaccum value.
700         *
701         * @param handle
702         *            handle of device.
703         * @param pidIdx
704         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
705         *            secondary loop.
706         * @return Integral accumulator value.
707         */
708        public static native double GetIntegralAccumulator(long handle, int pidIdx);
709
710        /**
711         * Gets the derivative of the closed-loop error.
712         *
713         * @param handle
714         *            handle of device.
715         * @param pidIdx
716         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
717         *            secondary loop.
718         * @return Error derivative value.
719         */
720        public static native double GetErrorDerivative(long handle, int pidIdx);
721
722        /**
723         * Selects which profile slot to use for closed-loop control.
724         *
725         * @param handle
726         *            handle of device.
727         * @param slotIdx
728         *            Profile slot to select.
729         * @param pidIdx
730         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
731         *            secondary loop.
732         **/
733        public static native void SelectProfileSlot(long handle, int slotIdx, int pidIdx);
734
735        public static native int GetActiveTrajectoryPosition(long handle);
736
737        public static native int GetActiveTrajectoryVelocity(long handle);
738
739        public static native double GetActiveTrajectoryHeading(long handle);
740
741        public static native int GetActiveTrajectoryPosition3(long handle, int pidIdx);
742        public static native int GetActiveTrajectoryVelocity3(long handle, int pidIdx);
743
744        public static native double GetActiveTrajectoryArbFeedFwd3(long handle, int pidIdx);
745
746        /**
747         * Sets the Motion Magic Cruise Velocity.
748         *
749         * @param handle
750         *            handle of device.
751         * @param sensorUnitsPer100ms
752         *            Motion Magic Cruise Velocity (in Raw Sensor Units per 100 ms).
753         * @param timeoutMs
754         *            Timeout value in ms. @see #ConfigOpenLoopRamp
755         * @return Error Code generated by function. 0 indicates no error.
756         */
757        public static native int ConfigMotionCruiseVelocity(long handle, int sensorUnitsPer100ms, int timeoutMs);
758
759        /**
760         * Sets the Motion Magic Acceleration.
761         *
762         * @param handle
763         *            handle of device.
764         * @param sensorUnitsPer100msPerSec
765         *            Motion Magic Acceleration (in Raw Sensor Units per 100 ms per
766         *            second).
767         * @param timeoutMs
768         *            Timeout value in ms. @see #ConfigOpenLoopRamp
769         * @return Error Code generated by function. 0 indicates no error.
770         */
771        public static native int ConfigMotionAcceleration(long handle, int sensorUnitsPer100msPerSec, int timeoutMs);
772
773        public static native int ConfigMotionSCurveStrength(long m_handle, int curveStrength, int timeoutMs);
774
775        public static native int ClearMotionProfileTrajectories(long handle);
776
777        public static native int GetMotionProfileTopLevelBufferCount(long handle);
778
779        public static native int PushMotionProfileTrajectory(long handle, double position, double velocity,
780                        double headingDeg, int profileSlotSelect, boolean isLastPoint, boolean zeroPos);
781
782        public static native int PushMotionProfileTrajectory2(long handle, double position, double velocity, double headingDeg,
783                        int profileSlotSelect0, int profileSlotSelect1, boolean isLastPoint, boolean zeroPos, int durationMs);
784
785        public static native int PushMotionProfileTrajectory3(long handle, double position, double velocity, double arbFeedFwd, double auxiliaryPos, double auxiliaryVel, double auxiliaryArbFeedFwd, int profileSlotSelect0, int profileSlotSelect1, boolean isLastPoint, boolean zeroPos0, int timeDur, boolean useAuxPID);
786
787        public static native int StartMotionProfile(long handle, long streamHandle, int minBufferedPts, int controlMode);
788
789        public static native boolean IsMotionProfileTopLevelBufferFull(long handle);
790
791        public static native boolean IsMotionProfileFinished(long handle);
792
793        public static native int ProcessMotionProfileBuffer(long handle);
794
795        public static native int GetMotionProfileStatus(long handle, int[] toFill_9);
796
797        public static native int GetMotionProfileStatus2(long handle, int[] toFill_11);
798
799        public static native int ClearMotionProfileHasUnderrun(long handle, int timeoutMs);
800
801        public static native int ChangeMotionControlFramePeriod(long handle, int periodMs);
802
803        public static native int ConfigMotionProfileTrajectoryPeriod(long handle, int periodMs, int timeoutMs);
804
805        public static native int ConfigMotionProfileTrajectoryInterpolationEnable(long handle, boolean enable, int timeoutMs);
806
807    public static native int ConfigFeedbackNotContinuous(long handle, boolean feedbackNotContinuous, int timeoutMs);
808
809    public static native int ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(long handle, boolean remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs);
810
811    public static native int ConfigClearPositionOnLimitF(long handle, boolean clearPositionOnLimitF, int timeoutMs);
812
813    public static native int ConfigClearPositionOnLimitR(long handle, boolean clearPositionOnLimitR, int timeoutMs);
814
815    public static native int ConfigClearPositionOnQuadIdx(long handle, boolean clearPositionOnQuadIdx, int timeoutMs);
816
817    public static native int ConfigLimitSwitchDisableNeutralOnLOS(long handle, boolean limitSwitchDisableNeutralOnLOS, int timeoutMs);
818
819    public static native int ConfigSoftLimitDisableNeutralOnLOS(long handle, boolean softLimitDisableNeutralOnLOS, int timeoutMs);
820
821    public static native int ConfigPulseWidthPeriod_EdgesPerRot(long handle, int pulseWidthPeriod_EdgesPerRot, int timeoutMs);
822
823    public static native int ConfigPulseWidthPeriod_FilterWindowSz(long handle, int pulseWidthPeriod_FilterWindowSz, int timeoutMs);
824
825        /**
826         * Gets the last error generated by this object.
827         *
828         * @param handle
829         *            handle of device.
830         * @return Last Error Code generated by a function.
831         */
832        public static native int GetLastError(long handle);
833
834        /**
835         * Gets the firmware version of the device.
836         *
837         * @param handle
838         *            handle of device.
839         * @return Firmware version of device.
840         */
841        public static native int GetFirmwareVersion(long handle);
842
843        /**
844         * Returns true if the device has reset.
845         *
846         * @param handle
847         *            handle of device.
848         * @return Has a Device Reset Occurred?
849         */
850        public static native boolean HasResetOccurred(long handle);
851
852        /**
853         * Sets the value of a custom parameter.
854         *
855         * @param handle
856         *            handle of device.
857         * @param newValue
858         *            Value for custom parameter.
859         * @param paramIndex
860         *            Index of custom parameter.
861         * @param timeoutMs
862         *            Timeout value in ms. @see #ConfigOpenLoopRamp
863         * @return Error Code generated by function. 0 indicates no error.
864         */
865        public static native int ConfigSetCustomParam(long handle, int newValue, int paramIndex, int timeoutMs);
866
867        /**
868         * Gets the value of a custom parameter.
869         *
870         * @param handle
871         *            handle of device.
872         * @param paramIndex
873         *            Index of custom parameter.
874         * @param timoutMs
875         *            Timeout value in ms. @see #ConfigOpenLoopRamp
876         * @return Value of the custom param.
877         */
878        public static native int ConfigGetCustomParam(long handle, int paramIndex, int timoutMs);
879
880        /**
881         * Sets a parameter.
882         *
883         * @param handle
884         *            handle of device.
885         * @param param
886         *            Parameter enumeration.
887         * @param value
888         *            Value of parameter.
889         * @param subValue
890         *            Subvalue for parameter. Maximum value of 255.
891         * @param ordinal
892         *            Ordinal of parameter.
893         * @param timeoutMs
894         *            Timeout value in ms. @see #ConfigOpenLoopRamp
895         * @return Error Code generated by function. 0 indicates no error.
896         */
897        public static native int ConfigSetParameter(long handle, int param, double value, int subValue, int ordinal,
898                        int timeoutMs);
899
900        /**
901         * Gets a parameter.
902         *
903         * @param handle
904         *            handle of device.
905         * @param param
906         *            Parameter enumeration.
907         * @param ordinal
908         *            Ordinal of parameter.
909         * @param timeoutMs
910         *            Timeout value in ms. @see #ConfigOpenLoopRamp
911         * @return Value of parameter.
912         */
913        public static native double ConfigGetParameter(long handle, int param, int ordinal, int timeoutMs);
914
915        /**
916         * Configures the peak current limit of the motor controller.
917         *
918         * @param handle
919         *            handle of device.
920         * @param amps
921         *            Peak current limit (in amps).
922         * @param timeoutMs
923         *            Timeout value in ms. @see #ConfigOpenLoopRamp
924         * @return Error Code generated by function. 0 indicates no error.
925         */
926        public static native int ConfigPeakCurrentLimit(long handle, int amps, int timeoutMs);
927
928        /**
929         * Configures the maximum time allowed at peak current limit of the motor
930         * controller.
931         *
932         * @param handle
933         *            handle of device.
934         * @param milliseconds
935         *            Maximum time allowed at peak current limit (in milliseconds).
936         * @param timeoutMs
937         *            Timeout value in ms. @see #ConfigOpenLoopRamp
938         * @return Error Code generated by function. 0 indicates no error.
939         */
940        public static native int ConfigPeakCurrentDuration(long handle, int milliseconds, int timeoutMs);
941
942        /**
943         * Configures the continuous current limit.
944         *
945         * @param handle
946         *            handle of device.
947         * @param amps
948         *            Continuous Current Limit.
949         * @param timeoutMs
950         *            Timeout value in ms. @see #ConfigOpenLoopRamp
951         * @return Error Code generated by function. 0 indicates no error.
952         */
953        public static native int ConfigContinuousCurrentLimit(long handle, int amps, int timeoutMs);
954
955        /**
956         * Enables the current limit feature.
957         *
958         * @param handle
959         *            handle of device.
960         * @param enable
961         *            Enable state of current limit.
962         **/
963        public static native int EnableCurrentLimit(long handle, boolean enable);
964
965        public static native int GetAnalogIn(long handle);
966
967        public static native int SetAnalogPosition(long handle, int newPosition, int timeoutMs);
968
969        public static native int GetAnalogInRaw(long handle);
970
971        public static native int GetAnalogInVel(long handle);
972
973        public static native int GetQuadraturePosition(long handle);
974
975        public static native int SetQuadraturePosition(long handle, int newPosition, int timeoutMs);
976
977        public static native int GetQuadratureVelocity(long handle);
978
979        public static native int GetPulseWidthPosition(long handle);
980
981        public static native int SetPulseWidthPosition(long handle, int newPosition, int timeoutMs);
982
983        public static native int GetPulseWidthVelocity(long handle);
984
985        public static native int GetPulseWidthRiseToFallUs(long handle);
986
987        public static native int GetPulseWidthRiseToRiseUs(long handle);
988
989        public static native int GetPinStateQuadA(long handle);
990
991        public static native int GetPinStateQuadB(long handle);
992
993        public static native int GetPinStateQuadIdx(long handle);
994
995        public static native int IsFwdLimitSwitchClosed(long handle);
996
997        public static native int IsRevLimitSwitchClosed(long handle);
998
999        public static native int GetFaults(long handle);
1000
1001        public static native int GetStickyFaults(long handle);
1002
1003        public static native int ClearStickyFaults(long handle, int timeoutMs);
1004
1005        public static native int SelectDemandType(long handle, int enable);
1006
1007        public static native int SetMPEOutput(long handle, int mpeOutput);
1008
1009        public static native int EnableHeadingHold(long handle, int enable);
1010
1011        public static native int GetClosedLoopTarget(long handle, int pidIdx);
1012
1013        public static native int ConfigSelectedFeedbackCoefficient(long handle, double coefficient, int pidIdx, int timeoutMs);
1014
1015        public static native int ConfigClosedLoopPeakOutput(long handle, int slotIdx, double percentOut, int timeoutMs);
1016
1017        public static native int ConfigClosedLoopPeriod(long handle, int slotIdx, int loopTimeMs, int timeoutMs);
1018
1019        public static native int ConfigSupplyCurrentLimit(long handle, double[] params, int timeoutMs);
1020
1021        public static native int ConfigSupplyCurrentLimitEnable(long handle, boolean enable, int timeoutMs);
1022
1023        public static native int ConfigBrakeCurrentLimitEnable(long handle, boolean enable, int timeoutMs);
1024
1025        public static native int ConfigGetSupplyCurrentLimit(long handle, double[] toFill, int timeoutMs);
1026}