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         * In the case of TalonFX class, this routine returns the true output stator current.
273         *
274         * @deprecated Use getStatorCurrent/getSupplyCurrent instead.
275         * @param handle
276         *                        handle of device
277         *
278         * @return The output current (in amps).
279         */
280        @Deprecated
281        public static native double GetOutputCurrent(long handle);
282
283        /**
284         * Gets the stator/output current of the motor controller.
285         *
286         * @param handle
287         *                        handle of device
288         * @return The stator/output current (in amps).
289         */
290        public static native double GetSupplyCurrent(long handle);
291
292        /**
293         * Gets the stator/output current of the motor controller.
294         *
295         * @param handle
296         *                        handle of device
297         * @return The stator/output current (in amps).
298         */
299        public static native double GetStatorCurrent(long handle);
300
301        /**
302         * Gets the temperature of the motor controller.
303         *
304         * @param handle
305         *            handle of device.
306         * @return The temperature of the motor controller (in 'C)
307         */
308        public static native double GetTemperature(long handle);
309
310        /**
311         * Configures the remote feedback filter.
312         *
313         * @param handle
314         *            handle of device.
315         * @param deviceID
316         *            ID of remote device.
317         * @param remoteSensorSource
318         *            Type of remote sensor.
319         * @param remoteOrdinal
320         *            Ordinal of remote source [0-1].
321         * @param timeoutMs
322         *            Timeout value in ms. @see #ConfigOpenLoopRamp
323         * @return Error Code generated by function. 0 indicates no error.
324         */
325        public static native int ConfigRemoteFeedbackFilter(long handle, int deviceID, int remoteSensorSource,
326                        int remoteOrdinal, int timeoutMs);
327
328        /**
329         * Select the feedback device for the motor controller.
330         *
331         * @param handle
332         *            handle of device.
333         * @param feedbackDevice
334         *            Feedback Device to select.
335         * @param pidIdx
336         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
337         * @param timeoutMs
338         *            Timeout value in ms. @see #ConfigOpenLoopRamp
339         * @return Error Code generated by function. 0 indicates no error.
340         */
341        public static native int ConfigSelectedFeedbackSensor(long handle, int feedbackDevice, int pidIdx, int timeoutMs);
342
343        public static native int ConfigSensorTerm(long handle, int sensorTerm, int feedbackDevice, int timeoutMs);
344
345        /**
346         * Get the selected sensor position.
347         *
348         * @param handle
349         *            handle of device.
350         * @param pidIdx
351         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
352         * @return Position of selected sensor (in Raw Sensor Units).
353         */
354        public static native int GetSelectedSensorPosition(long handle, int pidIdx);
355
356        /**
357         * Get the selected sensor velocity.
358         *
359         * @param handle
360         *            handle of device.
361         * @param pidIdx
362         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
363         * @return Velocity of selected sensor (in Raw Sensor Units per 100 ms).
364         */
365        public static native int GetSelectedSensorVelocity(long handle, int pidIdx);
366
367        /**
368         * Sets the sensor position to the given value.
369         *
370         * @param handle
371         *            handle of device.
372         * @param sensorPos
373         *            Position to set for the selected sensor (in Raw Sensor Units).
374         * @param pidIdx
375         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
376         * @param timeoutMs
377         *            Timeout value in ms. @see #ConfigOpenLoopRamp
378         * @return Error Code generated by function. 0 indicates no error.
379         */
380        public static native int SetSelectedSensorPosition(long handle, int sensorPos, int pidIdx, int timeoutMs);
381
382        /**
383         * Sets the period of the given control frame.
384         *
385         * @param handle
386         *            handle of device.
387         * @param frame
388         *            Frame whose period is to be changed.
389         * @param periodMs
390         *            Period in ms for the given frame.
391         * @return Error Code generated by function. 0 indicates no error.
392         */
393        public static native int SetControlFramePeriod(long handle, int frame, int periodMs);
394
395        /**
396         * Sets the period of the given status frame.
397         *
398         * @param handle
399         *            handle of device.
400         * @param frame
401         *            Frame whose period is to be changed.
402         * @param periodMs
403         *            Period in ms for the given frame.
404         * @param timeoutMs
405         *            Timeout value in ms. @see #ConfigOpenLoopRamp
406         * @return Error Code generated by function. 0 indicates no error.
407         */
408        public static native int SetStatusFramePeriod(long handle, int frame, int periodMs, int timeoutMs);
409
410        /**
411         * Gets the period of the given status frame.
412         *
413         * @param handle
414         *            handle of device.
415         * @param frame
416         *            Frame to get the period of.
417         * @param timeoutMs
418         *            Timeout value in ms. @see #ConfigOpenLoopRamp
419         * @return The period of the given status frame.
420         */
421        public static native int GetStatusFramePeriod(long handle, int frame, int timeoutMs);
422
423        /**
424         * Sets the period over which velocity measurements are taken.
425         *
426         * @param handle
427         *            handle of device.
428         * @param period
429         *            Desired period for the velocity measurement. @see
430         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
431         * @param timeoutMs
432         *            Timeout value in ms. @see #ConfigOpenLoopRamp
433         * @return Error Code generated by function. 0 indicates no error.
434         */
435        public static native int ConfigVelocityMeasurementPeriod(long handle, int period, int timeoutMs);
436
437        /**
438         * Sets the number of velocity samples used in the rolling average velocity
439         * measurement.
440         *
441         * @param handle
442         *            handle of device.
443         * @param windowSize
444         *            Number of samples in the rolling average of velocity
445         *            measurement.
446         * @param timeoutMs
447         *            Timeout value in ms. @see #ConfigOpenLoopRamp
448         * @return Error Code generated by function. 0 indicates no error.
449         */
450        public static native int ConfigVelocityMeasurementWindow(long handle, int windowSize, int timeoutMs);
451
452        /**
453         * Configures the forward limit switch for a remote source.
454         *
455         * @param handle
456         *            handle of device.
457         * @param type
458         *            Remote limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource
459         * @param normalOpenOrClose
460         *            Setting for normally open or normally closed.
461         * @param deviceID
462         *            Device ID of remote source.
463         * @param timeoutMs
464         *            Timeout value in ms. @see #ConfigOpenLoopRamp
465         * @return Error Code generated by function. 0 indicates no error.
466         */
467        public static native int ConfigForwardLimitSwitchSource(long handle, int type, int normalOpenOrClose, int deviceID,
468                        int timeoutMs);
469
470        /**
471         * Configures the reverse limit switch for a remote source.
472         *
473         * @param handle
474         *            handle of device.
475         * @param type
476         *            Remote limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource
477         * @param normalOpenOrClose
478         *            Setting for normally open or normally closed.
479         * @param deviceID
480         *            Device ID of remote source.
481         * @param timeoutMs
482         *            Timeout value in ms. @see #ConfigOpenLoopRamp
483         * @return Error Code generated by function. 0 indicates no error.
484         */
485        public static native int ConfigReverseLimitSwitchSource(long handle, int type, int normalOpenOrClose, int deviceID,
486                        int timeoutMs);
487
488        /**
489         * Sets the enable state for limit switches.
490         *
491         * @param handle
492         *            handle of device.
493         * @param enable
494         *            Enable state for limit switches.
495         **/
496        public static native void OverrideLimitSwitchesEnable(long handle, boolean enable);
497
498        /**
499         * Configures the forward soft limit.
500         *
501         * @param handle
502         *            handle of device.
503         * @param forwardSensorLimit
504         *            Forward Sensor Position Limit (in Raw Sensor Units).
505         * @param timeoutMs
506         *            Timeout value in ms. @see #ConfigOpenLoopRamp
507         * @return Error Code generated by function. 0 indicates no error.
508         */
509        public static native int ConfigForwardSoftLimitThreshold(long handle, int forwardSensorLimit, int timeoutMs);
510
511        /**
512         * Configures the reverse soft limit.
513         *
514         * @param handle
515         *            handle of device.
516         * @param reverseSensorLimit
517         *            Reverse Sensor Position Limit (in Raw Sensor Units).
518         * @param timeoutMs
519         *            Timeout value in ms. @see #ConfigOpenLoopRamp
520         * @return Error Code generated by function. 0 indicates no error.
521         */
522        public static native int ConfigReverseSoftLimitThreshold(long handle, int reverseSensorLimit, int timeoutMs);
523
524        public static native int ConfigForwardSoftLimitEnable(long handle, boolean enable, int timeoutMs);
525
526        public static native int ConfigReverseSoftLimitEnable(long handle, boolean enable, int timeoutMs);
527
528        /**
529         * Sets the enable state for soft limit switches.
530         *
531         * @param handle
532         *            handle of device.
533         * @param enable
534         *            Enable state for soft limit switches.
535         **/
536        public static native void OverrideSoftLimitsEnable(long handle, boolean enable);
537
538        /**
539         * Sets the 'P' constant in the given parameter slot.
540         * This is multiplied by closed loop error in sensor units.
541         * Note the closed loop output interprets a final value of 1023 as full output.
542         * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation)
543         *
544         * @param handle
545         *            handle of device.
546         * @param slotIdx
547         *            Parameter slot for the constant.
548         * @param value
549         *            Value of the P constant.
550         * @param timeoutMs
551         *            Timeout value in ms. @see #ConfigOpenLoopRamp
552         * @return Error Code generated by function. 0 indicates no error.
553         */
554        public static native int Config_kP(long handle, int slotIdx, double value, int timeoutMs);
555
556        /**
557         * Sets the 'I' constant in the given parameter slot.
558         * This is multiplied by accumulated closed loop error in sensor units every PID Loop.
559         * Note the closed loop output interprets a final value of 1023 as full output.
560         * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000),
561         * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].
562         *
563         * @param handle
564         *            handle of device.
565         * @param slotIdx
566         *            Parameter slot for the constant.
567         * @param value
568         *            Value of the I constant.
569         * @param timeoutMs
570         *            Timeout value in ms. @see #ConfigOpenLoopRamp
571         * @return Error Code generated by function. 0 indicates no error.
572         */
573        public static native int Config_kI(long handle, int slotIdx, double value, int timeoutMs);
574
575        /**
576         * Sets the 'D' constant in the given parameter slot.
577         *
578         * This is multiplied by derivative error (sensor units per PID loop, typically 1ms).
579         * Note the closed loop output interprets a final value of 1023 as full output.
580         * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)
581         *
582         * @param handle
583         *            handle of device.
584         * @param slotIdx
585         *            Parameter slot for the constant.
586         * @param value
587         *            Value of the D constant.
588         * @param timeoutMs
589         *            Timeout value in ms. @see #ConfigOpenLoopRamp
590         * @return Error Code generated by function. 0 indicates no error.
591         */
592        public static native int Config_kD(long handle, int slotIdx, double value, int timeoutMs);
593
594        /**
595         * Sets the 'F' constant in the given parameter slot.
596         *
597         * See documentation for calculation details.
598         * If using velocity, motion magic, or motion profile,
599         * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).
600         *
601         * @param handle
602         *            handle of device.
603         * @param slotIdx
604         *            Parameter slot for the constant.
605         * @param value
606         *            Value of the F constant.
607         * @param timeoutMs
608         *            Timeout value in ms. @see #ConfigOpenLoopRamp
609         * @return Error Code generated by function. 0 indicates no error.
610         */
611        public static native int Config_kF(long handle, int slotIdx, double value, int timeoutMs);
612
613        /**
614         * Sets the Integral Zone constant in the given parameter slot.
615         *
616         * @param handle
617         *            handle of device.
618         * @param slotIdx
619         *            Parameter slot for the constant.
620         * @param izone
621         *            Value of the Integral Zone constant.
622         * @param timeoutMs
623         *            Timeout value in ms. @see #ConfigOpenLoopRamp
624         * @return Error Code generated by function. 0 indicates no error.
625         */
626        public static native int Config_IntegralZone(long handle, int slotIdx, double izone, int timeoutMs);
627
628        /**
629         * Sets the allowable closed-loop error in the given parameter slot.
630         *
631         * @param handle
632         *            handle of device.
633         * @param slotIdx
634         *            Parameter slot for the constant.
635         * @param allowableClosedLoopError
636         *            Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity).
637         * @param timeoutMs
638         *            Timeout value in ms. @see #ConfigOpenLoopRamp
639         * @return Error Code generated by function. 0 indicates no error.
640         */
641        public static native int ConfigAllowableClosedloopError(long handle, int slotIdx, int allowableClosedLoopError,
642                        int timeoutMs);
643
644        /**
645         * Sets the maximum integral accumulator in the given parameter slot.
646         *
647         * @param handle
648         *            handle of device.
649         * @param slotIdx
650         *            Parameter slot for the constant.
651         * @param iaccum
652         *            Value of the maximum integral accumulator.
653         * @param timeoutMs
654         *            Timeout value in ms. @see #ConfigOpenLoopRamp
655         * @return Error Code generated by function. 0 indicates no error.
656         */
657        public static native int ConfigMaxIntegralAccumulator(long handle, int slotIdx, double iaccum, int timeoutMs);
658
659        /**
660         * Sets the integral accumulator.
661         *
662         * @param handle
663         *            handle of device.
664         * @param iaccum
665         *            Value to set for the integral accumulator.
666         * @param timeoutMs
667         *            Timeout value in ms. @see #ConfigOpenLoopRamp
668         * @param pidIdx
669         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
670         *            secondary loop.
671         * @return Error Code generated by function. 0 indicates no error.
672         */
673        public static native int SetIntegralAccumulator(long handle, double iaccum, int pidIdx, int timeoutMs);
674
675        /**
676         * Gets the closed-loop error. The units depend on which control mode is in
677         * use.
678         *
679         * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target
680         * and current sensor value (in sensor units.  Example 4096 units per rotation for CTRE Mag Encoder).
681         *
682         * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target
683         * and current sensor value (in sensor units per 100ms).
684         *
685         * If using motion profiling or Motion Magic, closed loop error is calculated against the current target,
686         * and not the "final" target at the end of the profile/movement.
687         *
688         * See Phoenix-Documentation information on units.
689         *
690         * @param handle
691         *            handle of device.
692         * @param pidIdx
693         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
694         *            secondary loop.
695         * @return Closed-loop error value.
696         */
697        public static native int GetClosedLoopError(long handle, int pidIdx);
698
699        /**
700         * Gets the iaccum value.
701         *
702         * @param handle
703         *            handle of device.
704         * @param pidIdx
705         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
706         *            secondary loop.
707         * @return Integral accumulator value.
708         */
709        public static native double GetIntegralAccumulator(long handle, int pidIdx);
710
711        /**
712         * Gets the derivative of the closed-loop error.
713         *
714         * @param handle
715         *            handle of device.
716         * @param pidIdx
717         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
718         *            secondary loop.
719         * @return Error derivative value.
720         */
721        public static native double GetErrorDerivative(long handle, int pidIdx);
722
723        /**
724         * Selects which profile slot to use for closed-loop control.
725         *
726         * @param handle
727         *            handle of device.
728         * @param slotIdx
729         *            Profile slot to select.
730         * @param pidIdx
731         *            Which closed loop to manipulate. 0 for primary, 1 for auxiliary
732         *            secondary loop.
733         **/
734        public static native void SelectProfileSlot(long handle, int slotIdx, int pidIdx);
735
736        public static native int GetActiveTrajectoryPosition(long handle);
737
738        public static native int GetActiveTrajectoryVelocity(long handle);
739
740        public static native double GetActiveTrajectoryHeading(long handle);
741
742        public static native int GetActiveTrajectoryPosition3(long handle, int pidIdx);
743        public static native int GetActiveTrajectoryVelocity3(long handle, int pidIdx);
744
745        public static native double GetActiveTrajectoryArbFeedFwd3(long handle, int pidIdx);
746
747        /**
748         * Sets the Motion Magic Cruise Velocity.
749         *
750         * @param handle
751         *            handle of device.
752         * @param sensorUnitsPer100ms
753         *            Motion Magic Cruise Velocity (in Raw Sensor Units per 100 ms).
754         * @param timeoutMs
755         *            Timeout value in ms. @see #ConfigOpenLoopRamp
756         * @return Error Code generated by function. 0 indicates no error.
757         */
758        public static native int ConfigMotionCruiseVelocity(long handle, int sensorUnitsPer100ms, int timeoutMs);
759
760        /**
761         * Sets the Motion Magic Acceleration.
762         *
763         * @param handle
764         *            handle of device.
765         * @param sensorUnitsPer100msPerSec
766         *            Motion Magic Acceleration (in Raw Sensor Units per 100 ms per
767         *            second).
768         * @param timeoutMs
769         *            Timeout value in ms. @see #ConfigOpenLoopRamp
770         * @return Error Code generated by function. 0 indicates no error.
771         */
772        public static native int ConfigMotionAcceleration(long handle, int sensorUnitsPer100msPerSec, int timeoutMs);
773
774        public static native int ConfigMotionSCurveStrength(long m_handle, int curveStrength, int timeoutMs);
775
776        public static native int ClearMotionProfileTrajectories(long handle);
777
778        public static native int GetMotionProfileTopLevelBufferCount(long handle);
779
780        public static native int PushMotionProfileTrajectory(long handle, double position, double velocity,
781                        double headingDeg, int profileSlotSelect, boolean isLastPoint, boolean zeroPos);
782
783        public static native int PushMotionProfileTrajectory2(long handle, double position, double velocity, double headingDeg,
784                        int profileSlotSelect0, int profileSlotSelect1, boolean isLastPoint, boolean zeroPos, int durationMs);
785
786        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);
787
788        public static native int StartMotionProfile(long handle, long streamHandle, int minBufferedPts, int controlMode);
789
790        public static native boolean IsMotionProfileTopLevelBufferFull(long handle);
791
792        public static native boolean IsMotionProfileFinished(long handle);
793
794        public static native int ProcessMotionProfileBuffer(long handle);
795
796        public static native int GetMotionProfileStatus(long handle, int[] toFill_9);
797
798        public static native int GetMotionProfileStatus2(long handle, int[] toFill_11);
799
800        public static native int ClearMotionProfileHasUnderrun(long handle, int timeoutMs);
801
802        public static native int ChangeMotionControlFramePeriod(long handle, int periodMs);
803
804        public static native int ConfigMotionProfileTrajectoryPeriod(long handle, int periodMs, int timeoutMs);
805
806        public static native int ConfigMotionProfileTrajectoryInterpolationEnable(long handle, boolean enable, int timeoutMs);
807
808    public static native int ConfigFeedbackNotContinuous(long handle, boolean feedbackNotContinuous, int timeoutMs);
809
810    public static native int ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(long handle, boolean remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs);
811
812    public static native int ConfigClearPositionOnLimitF(long handle, boolean clearPositionOnLimitF, int timeoutMs);
813
814    public static native int ConfigClearPositionOnLimitR(long handle, boolean clearPositionOnLimitR, int timeoutMs);
815
816    public static native int ConfigClearPositionOnQuadIdx(long handle, boolean clearPositionOnQuadIdx, int timeoutMs);
817
818    public static native int ConfigLimitSwitchDisableNeutralOnLOS(long handle, boolean limitSwitchDisableNeutralOnLOS, int timeoutMs);
819
820    public static native int ConfigSoftLimitDisableNeutralOnLOS(long handle, boolean softLimitDisableNeutralOnLOS, int timeoutMs);
821
822    public static native int ConfigPulseWidthPeriod_EdgesPerRot(long handle, int pulseWidthPeriod_EdgesPerRot, int timeoutMs);
823
824    public static native int ConfigPulseWidthPeriod_FilterWindowSz(long handle, int pulseWidthPeriod_FilterWindowSz, int timeoutMs);
825
826        /**
827         * Gets the last error generated by this object.
828         *
829         * @param handle
830         *            handle of device.
831         * @return Last Error Code generated by a function.
832         */
833        public static native int GetLastError(long handle);
834
835        /**
836         * Gets the firmware version of the device.
837         *
838         * @param handle
839         *            handle of device.
840         * @return Firmware version of device.
841         */
842        public static native int GetFirmwareVersion(long handle);
843
844        /**
845         * Returns true if the device has reset.
846         *
847         * @param handle
848         *            handle of device.
849         * @return Has a Device Reset Occurred?
850         */
851        public static native boolean HasResetOccurred(long handle);
852
853        /**
854         * Sets the value of a custom parameter.
855         *
856         * @param handle
857         *            handle of device.
858         * @param newValue
859         *            Value for custom parameter.
860         * @param paramIndex
861         *            Index of custom parameter.
862         * @param timeoutMs
863         *            Timeout value in ms. @see #ConfigOpenLoopRamp
864         * @return Error Code generated by function. 0 indicates no error.
865         */
866        public static native int ConfigSetCustomParam(long handle, int newValue, int paramIndex, int timeoutMs);
867
868        /**
869         * Gets the value of a custom parameter.
870         *
871         * @param handle
872         *            handle of device.
873         * @param paramIndex
874         *            Index of custom parameter.
875         * @param timoutMs
876         *            Timeout value in ms. @see #ConfigOpenLoopRamp
877         * @return Value of the custom param.
878         */
879        public static native int ConfigGetCustomParam(long handle, int paramIndex, int timoutMs);
880
881        /**
882         * Sets a parameter.
883         *
884         * @param handle
885         *            handle of device.
886         * @param param
887         *            Parameter enumeration.
888         * @param value
889         *            Value of parameter.
890         * @param subValue
891         *            Subvalue for parameter. Maximum value of 255.
892         * @param ordinal
893         *            Ordinal of parameter.
894         * @param timeoutMs
895         *            Timeout value in ms. @see #ConfigOpenLoopRamp
896         * @return Error Code generated by function. 0 indicates no error.
897         */
898        public static native int ConfigSetParameter(long handle, int param, double value, int subValue, int ordinal,
899                        int timeoutMs);
900
901        /**
902         * Gets a parameter.
903         *
904         * @param handle
905         *            handle of device.
906         * @param param
907         *            Parameter enumeration.
908         * @param ordinal
909         *            Ordinal of parameter.
910         * @param timeoutMs
911         *            Timeout value in ms. @see #ConfigOpenLoopRamp
912         * @return Value of parameter.
913         */
914        public static native double ConfigGetParameter(long handle, int param, int ordinal, int timeoutMs);
915
916        /**
917         * Configures the peak current limit of the motor controller.
918         *
919         * @param handle
920         *            handle of device.
921         * @param amps
922         *            Peak current limit (in amps).
923         * @param timeoutMs
924         *            Timeout value in ms. @see #ConfigOpenLoopRamp
925         * @return Error Code generated by function. 0 indicates no error.
926         */
927        public static native int ConfigPeakCurrentLimit(long handle, int amps, int timeoutMs);
928
929        /**
930         * Configures the maximum time allowed at peak current limit of the motor
931         * controller.
932         *
933         * @param handle
934         *            handle of device.
935         * @param milliseconds
936         *            Maximum time allowed at peak current limit (in milliseconds).
937         * @param timeoutMs
938         *            Timeout value in ms. @see #ConfigOpenLoopRamp
939         * @return Error Code generated by function. 0 indicates no error.
940         */
941        public static native int ConfigPeakCurrentDuration(long handle, int milliseconds, int timeoutMs);
942
943        /**
944         * Configures the continuous current limit.
945         *
946         * @param handle
947         *            handle of device.
948         * @param amps
949         *            Continuous Current Limit.
950         * @param timeoutMs
951         *            Timeout value in ms. @see #ConfigOpenLoopRamp
952         * @return Error Code generated by function. 0 indicates no error.
953         */
954        public static native int ConfigContinuousCurrentLimit(long handle, int amps, int timeoutMs);
955
956        /**
957         * Enables the current limit feature.
958         *
959         * @param handle
960         *            handle of device.
961         * @param enable
962         *            Enable state of current limit.
963         **/
964        public static native int EnableCurrentLimit(long handle, boolean enable);
965
966        public static native int GetAnalogIn(long handle);
967
968        public static native int SetAnalogPosition(long handle, int newPosition, int timeoutMs);
969
970        public static native int GetAnalogInRaw(long handle);
971
972        public static native int GetAnalogInVel(long handle);
973
974        public static native int GetQuadraturePosition(long handle);
975
976        public static native int SetQuadraturePosition(long handle, int newPosition, int timeoutMs);
977
978        public static native int GetQuadratureVelocity(long handle);
979
980        public static native int GetPulseWidthPosition(long handle);
981
982        public static native int SetPulseWidthPosition(long handle, int newPosition, int timeoutMs);
983
984        public static native int GetPulseWidthVelocity(long handle);
985
986        public static native int GetPulseWidthRiseToFallUs(long handle);
987
988        public static native int GetPulseWidthRiseToRiseUs(long handle);
989
990        public static native int GetPinStateQuadA(long handle);
991
992        public static native int GetPinStateQuadB(long handle);
993
994        public static native int GetPinStateQuadIdx(long handle);
995
996        public static native int IsFwdLimitSwitchClosed(long handle);
997
998        public static native int IsRevLimitSwitchClosed(long handle);
999
1000        public static native int GetFaults(long handle);
1001
1002        public static native int GetStickyFaults(long handle);
1003
1004        public static native int ClearStickyFaults(long handle, int timeoutMs);
1005
1006        public static native int SelectDemandType(long handle, int enable);
1007
1008        public static native int SetMPEOutput(long handle, int mpeOutput);
1009
1010        public static native int EnableHeadingHold(long handle, int enable);
1011
1012        public static native int GetClosedLoopTarget(long handle, int pidIdx);
1013
1014        public static native int ConfigSelectedFeedbackCoefficient(long handle, double coefficient, int pidIdx, int timeoutMs);
1015
1016        public static native int ConfigClosedLoopPeakOutput(long handle, int slotIdx, double percentOut, int timeoutMs);
1017
1018        public static native int ConfigClosedLoopPeriod(long handle, int slotIdx, int loopTimeMs, int timeoutMs);
1019
1020        public static native int ConfigMotorCommutation(long handle, int motorCommutation, int timeoutMs);
1021
1022        public static native int ConfigGetMotorCommutation(long handle, int timeoutMs);
1023
1024        public static native int ConfigSupplyCurrentLimit(long handle, double[] params, int timeoutMs);
1025
1026        public static native int ConfigStatorCurrentLimit(long handle, double[] params, int timeoutMs);
1027
1028        public static native int ConfigSupplyCurrentLimitEnable(long handle, boolean enable, int timeoutMs);
1029
1030        public static native int ConfigStatorCurrentLimitEnable(long handle, boolean enable, int timeoutMs);
1031
1032        public static native int ConfigBrakeCurrentLimitEnable(long handle, boolean enable, int timeoutMs);
1033
1034        public static native int ConfigGetSupplyCurrentLimit(long handle, double[] toFill, int timeoutMs);
1035
1036        public static native int ConfigGetStatorCurrentLimit(long handle, double[] toFill, int timeoutMs);
1037
1038        public static native int SetIntegratedSensorPosition(long handle, double newPos, int timeoutMs);
1039
1040        public static native int SetIntegratedSensorPositionToAbsolute(long handle, int timeoutMs);
1041
1042        public static native double GetIntegratedSensorPosition(long handle);
1043
1044        public static native double GetIntegratedSensorAbsolutePosition(long handle);
1045
1046        public static native double GetIntegratedSensorVelocity(long handle);
1047
1048    public static native int ConfigIntegratedSensorAbsoluteRange(long handle, int absoluteSensorRange, int timeoutMs);
1049
1050    public static native int ConfigIntegratedSensorOffset(long handle, double offsetDegrees, int timeoutMs);
1051
1052    public static native int ConfigIntegratedSensorInitializationStrategy(long handle, int initStrategy, int timeoutMs);
1053}