001/* Copyright (C) Cross The Road Electronics 2024 */
002/*
003 *  Software License Agreement
004 *
005 * Copyright (C) Cross The Road Electronics.  All rights
006 * reserved.
007 *
008 * Cross The Road Electronics (CTRE) licenses to you the right to
009 * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software
010 * API Libraries ONLY when in use with Cross The Road Electronics hardware products.
011 *
012 * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
013 * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT
014 * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A
015 * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL
016 * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL,
017 * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF
018 * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS
019 * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE
020 * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER
021 * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT
022 * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE
023 */
024package com.ctre.phoenix.sensors;
025import com.ctre.phoenix.ErrorCode;
026import com.ctre.phoenix.ParamEnum;
027import com.ctre.phoenix.motorcontrol.can.TalonSRX;
028import com.ctre.phoenix.ErrorCollection;
029import com.ctre.phoenix.CustomParamConfigUtil;
030
031//import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
032//import edu.wpi.first.wpilibj.hal.HAL;
033
034/**
035 * Pigeon IMU Class. Class supports communicating over CANbus and over
036 * ribbon-cable (CAN Talon SRX).
037 */
038public class PigeonIMU extends BasePigeon {
039
040        /** Data object for holding fusion information. */
041        public static class FusionStatus {
042                /**
043                 * Fused Heading
044                 */
045                public double heading;
046                /**
047                 * Whether the fusion is valid
048                 */
049                public boolean bIsValid;
050                /**
051                 * Whether the pigeon is fusing
052                 */
053                public boolean bIsFusing;
054
055                /**
056                 * Same as getLastError()
057                 */
058                public ErrorCode lastError;
059
060                /**
061                 * @return status of fusion as a string 
062                 */
063                public String toString() {
064                        String description;
065                        if (lastError != ErrorCode.OK) {
066                                description = "Could not receive status frame.  Check wiring and Phoenix Tuner.";
067                        } else if (bIsValid == false) {
068                                description = "Fused Heading is not valid.";
069                        } else if (bIsFusing == false) {
070                                description = "Fused Heading is valid.";
071                        } else {
072                                description = "Fused Heading is valid and is fusing compass.";
073                        }
074                        return description;
075                }
076        }
077
078        /** 
079         * Various calibration modes supported by Pigeon. 
080         *
081         * Note that you can instead use Phoenix Tuner to accomplish certain calibrations.
082         *
083         */
084        public enum CalibrationMode {
085                /**
086                 * Boot-Calibrate the pigeon
087                 */
088                BootTareGyroAccel(0), 
089                /**
090                 * Temperature-Calibrate the pigeon
091                 */
092                Temperature(1), 
093                /**
094                 * Magnetometer-Calibrate the pigeon using the 12pt process
095                 */
096                Magnetometer12Pt(2), 
097                /**
098                 * Magnetometer-Calibrate the pigeon using 360 turns
099                 */
100                Magnetometer360(3), 
101                /**
102                 * Calibrate the pigeon accelerometer
103                 */
104                Accelerometer(5), 
105                /**
106                 * Unknown calibration
107                 */
108                Unknown(-1);
109
110                /**
111                 * Value of CalibrationMode
112                 */
113                public final int value;
114
115                private CalibrationMode(int initValue) {
116                        this.value = initValue;
117                }
118
119                /**
120                 * Get a CalibrationMode of specified value
121                 * @param value Value of CalibrationMode
122                 * @return CalibrationMode of specified value
123                 */
124                public static CalibrationMode valueOf(int value) {
125                        for (CalibrationMode e : CalibrationMode.values()) {
126                                if (e.value == value) {
127                                        return e;
128                                }
129                        }
130                        return Unknown;
131                }
132        };
133
134        /** Overall state of the Pigeon. */
135        public enum PigeonState {
136                /**
137                 * No communications with Pigeon
138                 */
139                NoComm(0), 
140                /**
141                 * Pigeon is initializing
142                 */
143                Initializing(1), 
144                /**
145                 * Pigeon is ready
146                 */
147                Ready(2), 
148                /**
149                 * Pigeon is calibrating due to user
150                 */
151                UserCalibration(3), 
152                /**
153                 * Unknown state
154                 */
155                Unknown(-1);
156
157                /**
158                 * Value of PigeonState
159                 */
160                public final int value;
161
162                private PigeonState(int initValue) {
163                        this.value = initValue;
164                }
165
166                /**
167                 * Get a PigeonState of specified value
168                 * @param value Value of PigeonState
169                 * @return PigeonState of specified value
170                 */
171                public static PigeonState valueOf(int value) {
172                        for (PigeonState e : PigeonState.values()) {
173                                if (e.value == value) {
174                                        return e;
175                                }
176                        }
177                        return Unknown;
178                }
179        };
180
181        /**
182         * Data object for status on current calibration and general status.
183         *
184         * Pigeon has many calibration modes supported for a variety of uses. The
185         * modes generally collects and saves persistently information that makes
186         * the Pigeon signals more accurate. This includes collecting temperature,
187         * gyro, accelerometer, and compass information.
188         *
189         * For FRC use-cases, typically compass and temperature calibration is not
190         * required.
191         *
192         * Additionally when motion driver software in the Pigeon boots, it will
193         * perform a fast boot calibration to initially bias gyro and setup
194         * accelerometer.
195         *
196         * These modes can be enabled with the EnterCalibration mode.
197         *
198         * When a calibration mode is entered, caller can expect...
199         *
200         * - PigeonState to reset to Initializing and bCalIsBooting is set to true.
201         * Pigeon LEDs will blink the boot pattern. This is similar to the normal
202         * boot cal, however it can an additional ~30 seconds since calibration
203         * generally requires more information. currentMode will reflect the user's
204         * selected calibration mode.
205         *
206         * - PigeonState will eventually settle to UserCalibration and Pigeon LEDs
207         * will show cal specific blink patterns. bCalIsBooting is now false.
208         *
209         * - Follow the instructions in the Pigeon User Manual to meet the
210         * calibration specific requirements. When finished calibrationError will
211         * update with the result. Pigeon will solid-fill LEDs with red (for
212         * failure) or green (for success) for ~5 seconds. Pigeon then perform
213         * boot-cal to cleanly apply the newly saved calibration data.
214         */
215        public static class GeneralStatus {
216                /**
217                 * The current state of the motion driver. This reflects if the sensor
218                 * signals are accurate. Most calibration modes will force Pigeon to
219                 * reinit the motion driver.
220                 */
221                public PigeonState state;
222                /**
223                 * The currently applied calibration mode if state is in UserCalibration
224                 * or if bCalIsBooting is true. Otherwise it holds the last selected
225                 * calibration mode (when calibrationError was updated).
226                 */
227                public CalibrationMode currentMode;
228                /**
229                 * The error code for the last calibration mode. Zero represents a
230                 * successful cal (with solid green LEDs at end of cal) and nonzero is a
231                 * failed calibration (with solid red LEDs at end of cal). Different
232                 * calibration
233                 */
234                public int calibrationError;
235                /**
236                 * After caller requests a calibration mode, pigeon will perform a
237                 * boot-cal before entering the requested mode. During this period, this
238                 * flag is set to true.
239                 */
240                public boolean bCalIsBooting;
241                /**
242                 * Temperature in Celsius
243                 */
244                public double tempC;
245                /**
246                 * Number of seconds Pigeon has been up (since boot). This register is
247                 * reset on power boot or processor reset. Register is capped at 255
248                 * seconds with no wrap around.
249                 */
250                public int upTimeSec;
251                /**
252                 * Number of times the Pigeon has automatically rebiased the gyro. This
253                 * counter overflows from 15 -> 0 with no cap.
254                 */
255                public int noMotionBiasCount;
256                /**
257                 * Number of times the Pigeon has temperature compensated the various
258                 * signals. This counter overflows from 15 -> 0 with no cap.
259                 */
260                public int tempCompensationCount;
261                /**
262                 * Same as getLastError()
263                 */
264                public ErrorCode lastError;
265
266                /**
267                 * general string description of current status
268                 */
269                public String toString() {
270                        String description;
271                        /* build description string */
272                        if (lastError != ErrorCode.OK) { // same as NoComm
273                                description = "Status frame was not received, check wired connections and Phoenix Tuner.";
274                        } else if (bCalIsBooting) {
275                                description = "Pigeon is boot-caling to properly bias accel and gyro.  Do not move Pigeon.  When finished biasing, calibration mode will start.";
276                        } else if (state == PigeonState.UserCalibration) {
277                                /* mode specific descriptions */
278                                switch (currentMode) {
279                                case BootTareGyroAccel:
280                                        description = "Boot-Calibration: Gyro and Accelerometer are being biased.";
281                                        break;
282                                case Temperature:
283                                        description = "Temperature-Calibration: Pigeon is collecting temp data and will finish when temp range is reached. \n";
284                                        description += "Do not move Pigeon.";
285                                        break;
286                                case Magnetometer12Pt:
287                                        description = "Magnetometer Level 1 calibration: Orient the Pigeon PCB in the 12 positions documented in the User's Manual.";
288                                        break;
289                                case Magnetometer360:
290                                        description = "Magnetometer Level 2 calibration: Spin robot slowly in 360' fashion.  ";
291                                        break;
292                                case Accelerometer:
293                                        description = "Accelerometer Calibration: Pigeon PCB must be placed on a level source.  Follow User's Guide for how to level surfacee.  ";
294                                        break;
295                                default:
296                                case Unknown:
297                                        description = "Unknown status";
298                                        break;
299                                }
300                        } else if (state == PigeonState.Ready) {
301                                /*
302                                 * definitely not doing anything cal-related. So just instrument
303                                 * the motion driver state
304                                 */
305                                description = "Pigeon is running normally.  Last CAL error code was ";
306                                description += Integer.toString(calibrationError);
307                                description += ".";
308                        } else if (state == PigeonState.Initializing) {
309                                /*
310                                 * definitely not doing anything cal-related. So just instrument
311                                 * the motion driver state
312                                 */
313                                description = "Pigeon is boot-caling to properly bias accel and gyro.  Do not move Pigeon.";
314                        } else {
315                                description = "Not enough data to determine status.";
316                        }
317                        return description;
318                }
319        };
320
321        private double[] _generalStatus = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
322        private double[] _fusionStatus = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
323
324        /**
325         * Create a Pigeon object that communicates with Pigeon on CAN Bus.
326         *
327         * @param deviceNumber
328         *            CAN Device Id of Pigeon [0,62]
329         */
330        public PigeonIMU(int deviceNumber) {
331                super(deviceNumber, "v1");
332        }
333
334    //public static void DestroyAllPigeonIMUs() {
335    //    PigeonImuJNI.JNI_destroy_AllPigeonImus();
336    //}
337
338        /**
339         * Create a Pigeon object that communciates with Pigeon through the
340         * Gadgeteer ribbon cable connected to a Talon on CAN Bus.
341         *
342         * @param talonSrx
343         *            Object for the TalonSRX connected via ribbon cable.
344         */
345        public PigeonIMU(TalonSRX talonSrx) {
346                super(talonSrx);
347        }
348
349        /**
350         * Sets the Fused Heading to the specified value.
351         *
352         * @param angleDeg  New fused-heading in degrees [+/- 23,040 degrees]
353         * @param timeoutMs
354     *            Timeout value in ms. If nonzero, function will wait for
355     *            config success and report an error if it times out.
356     *            If zero, no blocking or checking is performed.
357         * @return Error Code generated by function. 0 indicates no error.
358         */
359        public ErrorCode setFusedHeading(double angleDeg, int timeoutMs) {
360                int retval = PigeonImuJNI.JNI_SetFusedHeading(getHandle(), angleDeg, timeoutMs);
361                return ErrorCode.valueOf(retval);
362        }
363        /**
364         * Sets the Fused Heading to the specified value.
365         *
366         * @param angleDeg  New fused-heading in degrees [+/- 23,040 degrees]
367         * @return Error Code generated by function. 0 indicates no error.
368         */
369        public ErrorCode setFusedHeading(double angleDeg) {
370                int timeoutMs = 0;
371                return setFusedHeading( angleDeg,  timeoutMs);
372        }
373        /**
374         * Atomically add to the Fused Heading register.
375         *
376         * @param angleDeg  Degrees to add to the Fused Heading register.
377         * @param timeoutMs
378     *            Timeout value in ms. If nonzero, function will wait for
379     *            config success and report an error if it times out.
380     *            If zero, no blocking or checking is performed.
381         * @return Error Code generated by function. 0 indicates no error.
382         */
383        public ErrorCode addFusedHeading(double angleDeg, int timeoutMs) {
384                int retval = PigeonImuJNI.JNI_AddFusedHeading(getHandle(), angleDeg, timeoutMs);
385                return ErrorCode.valueOf(retval);
386        }
387        /**
388         * Atomically add to the Fused Heading register.
389         *
390         * @param angleDeg  Degrees to add to the Fused Heading register
391         * @return Error Code generated by function. 0 indicates no error.
392         */
393        public ErrorCode addFusedHeading(double angleDeg) {
394                int timeoutMs = 0;
395                return addFusedHeading(angleDeg, timeoutMs);
396        }
397        /**
398         * Sets the Fused Heading register to match the current compass value.
399         *
400         * @param timeoutMs
401     *            Timeout value in ms. If nonzero, function will wait for
402     *            config success and report an error if it times out.
403     *            If zero, no blocking or checking is performed.
404         * @return Error Code generated by function. 0 indicates no error.
405         */
406        public ErrorCode setFusedHeadingToCompass(int timeoutMs) {
407                int retval = PigeonImuJNI.JNI_SetFusedHeadingToCompass(getHandle(), timeoutMs);
408                return ErrorCode.valueOf(retval);
409        }
410        /**
411         * Sets the Fused Heading register to match the current compass value.
412         *
413         * @return Error Code generated by function. 0 indicates no error.
414         */
415        public ErrorCode setFusedHeadingToCompass() {
416                int timeoutMs = 0;
417                return setFusedHeadingToCompass(timeoutMs);
418        }
419
420    /**
421     * Disable/Enable Temp compensation. Pigeon has this on/False at boot.
422     *
423     * @param bTempCompDisable Set to "False" to enable temperature compensation.
424     * @param timeoutMs
425     *            Timeout value in ms. If nonzero, function will wait for
426     *            config success and report an error if it times out.
427     *            If zero, no blocking or checking is performed.
428     * @return Error Code generated by function. 0 indicates no error.
429     */
430        public ErrorCode setTemperatureCompensationDisable(boolean bTempCompDisable, int timeoutMs) {
431                int retval = PigeonImuJNI.JNI_SetTemperatureCompensationDisable(getHandle(), bTempCompDisable ? 1 : 0, timeoutMs);
432                return ErrorCode.valueOf(retval);
433        }
434    /**
435     * Disable/Enable Temp compensation. Pigeon has this on/False at boot.
436     *
437     * @param bTempCompDisable Set to "False" to enable temperature compensation.
438     * @return Error Code generated by function. 0 indicates no error.
439     */
440        public ErrorCode setTemperatureCompensationDisable(boolean bTempCompDisable) {
441                int timeoutMs = 0;
442                return setTemperatureCompensationDisable(bTempCompDisable, timeoutMs);
443        }
444
445        /**
446         * Set the declination for compass. Declination is the difference between
447         * Earth Magnetic north, and the geographic "True North".
448         *
449         * @param angleDegOffset  Degrees to set Compass Declination to.
450         * @param timeoutMs
451     *            Timeout value in ms. If nonzero, function will wait for
452     *            config success and report an error if it times out.
453     *            If zero, no blocking or checking is performed.
454         * @return Error Code generated by function. 0 indicates no error.
455         */
456        public ErrorCode setCompassDeclination(double angleDegOffset, int timeoutMs) {
457                int retval = PigeonImuJNI.JNI_SetCompassDeclination(getHandle(), angleDegOffset, timeoutMs);
458                return ErrorCode.valueOf(retval);
459        }
460        /**
461         * Set the declination for compass. Declination is the difference between
462         * Earth Magnetic north, and the geographic "True North".
463         *
464         * @param angleDegOffset  Degrees to set Compass Declination to.
465         * @return Error Code generated by function. 0 indicates no error.
466         */
467        public ErrorCode setCompassDeclination(double angleDegOffset) {
468                int timeoutMs = 0;
469                return setCompassDeclination( angleDegOffset, timeoutMs);
470        }
471
472        /**
473         * Sets the compass angle. Although compass is absolute [0,360) degrees, the
474         * continuous compass register holds the wrap-arounds.
475         *
476         * @param angleDeg  Degrees to set continuous compass angle to.
477         * @param timeoutMs
478     *            Timeout value in ms. If nonzero, function will wait for
479     *            config success and report an error if it times out.
480     *            If zero, no blocking or checking is performed.
481         * @return Error Code generated by function. 0 indicates no error.
482         */
483        public ErrorCode setCompassAngle(double angleDeg, int timeoutMs) {
484                int retval = PigeonImuJNI.JNI_SetCompassAngle(getHandle(), angleDeg, timeoutMs);
485                return ErrorCode.valueOf(retval);
486        }
487        /**
488         * Sets the compass angle. Although compass is absolute [0,360) degrees, the
489         * continuous compass register holds the wrap-arounds.
490         *
491         * @param angleDeg  Degrees to set continuous compass angle to.
492         * @return Error Code generated by function. 0 indicates no error.
493         */
494        public ErrorCode setCompassAngle(double angleDeg) {
495                int timeoutMs = 0;
496                return setCompassAngle(angleDeg, timeoutMs);
497        }
498
499        // ----------------------- Calibration routines -----------------------//
500        /**
501         * Enters the Calbration mode.  See the Pigeon IMU documentation for More
502         * information on Calibration.
503         *
504         * Note that you can instead use Phoenix Tuner to accomplish this.
505         * Note you should NOT be calling this during normal robot operation.
506         *
507         * @param calMode  Calibration to execute
508         * @param timeoutMs
509     *            Timeout value in ms. If nonzero, function will wait for
510     *            config success and report an error if it times out.
511     *            If zero, no blocking or checking is performed.
512         * @return Error Code generated by function. 0 indicates no error.
513         */
514        public ErrorCode enterCalibrationMode(CalibrationMode calMode, int timeoutMs) {
515                int retval = PigeonImuJNI.JNI_EnterCalibrationMode(getHandle(), calMode.value, timeoutMs);
516                return ErrorCode.valueOf(retval);
517        }
518        /**
519         * Enters the Calbration mode.  See the Pigeon IMU documentation for More
520         * information on Calibration.
521         *
522         * Note that you can instead use Phoenix Tuner to accomplish this.
523         * Note you should not be using this in your normal robot application.
524         *
525         * @param calMode  Calibration to execute
526         * @return Error Code generated by function. 0 indicates no error.
527         */
528        public ErrorCode enterCalibrationMode(CalibrationMode calMode) {
529                int timeoutMs = 0;
530                return enterCalibrationMode(calMode, timeoutMs);
531        }
532
533        /**
534         * Get the status of the current (or previousley complete) calibration.
535         *
536         * @param toFill Container for the status information.
537         * @return Error Code generated by function. 0 indicates no error.
538         */
539        public ErrorCode getGeneralStatus(GeneralStatus toFill) {
540                int retval = PigeonImuJNI.JNI_GetGeneralStatus(getHandle(), _generalStatus);
541                toFill.state = PigeonState.valueOf((int) _generalStatus[0]);
542                toFill.currentMode = CalibrationMode.valueOf((int) _generalStatus[1]);
543                toFill.calibrationError = (int) _generalStatus[2];
544                toFill.bCalIsBooting = _generalStatus[3] != 0;
545                toFill.tempC = _generalStatus[4];
546                toFill.upTimeSec = (int) _generalStatus[5];
547                toFill.noMotionBiasCount = (int) _generalStatus[6];
548                toFill.tempCompensationCount = (int) _generalStatus[7];
549                toFill.lastError = ErrorCode.valueOf(retval);
550                return toFill.lastError;
551        }
552
553        /**
554         * Gets the current Pigeon state
555         *
556         * @return PigeonState enum
557         */
558        public PigeonState getState() {
559                int retval = PigeonImuJNI.JNI_GetState(getHandle());
560                return PigeonState.valueOf(retval);
561        }
562
563        /**
564         * Get the current Fusion Status (including fused heading)
565         *
566         * @param toFill        object reference to fill with fusion status flags.
567         *                                      Caller may pass null if flags are not needed.
568         * @return The fused heading in degrees.
569         */
570        public double getFusedHeading(FusionStatus toFill) {
571                int errorCode = PigeonImuJNI.JNI_GetFusedHeading(getHandle(), _fusionStatus);
572
573                if (toFill != null) {
574                        toFill.heading = _fusionStatus[0];
575                        toFill.bIsFusing = (_fusionStatus[1] != 0);
576                        toFill.bIsValid = (_fusionStatus[2] != 0);
577                        toFill.lastError = ErrorCode.valueOf(errorCode);
578                }
579
580                return _fusionStatus[0];
581        }
582        /**
583         * Gets the Fused Heading
584         *
585         * @return The fused heading in degrees.
586         */
587        public double getFusedHeading() {
588                PigeonImuJNI.JNI_GetFusedHeading(getHandle(), _fusionStatus);
589
590                return _fusionStatus[0];
591        }
592        
593        /**
594         * Get Accelerometer tilt angles.
595         *
596         * @param tiltAngles Array to fill with x[0], y[1], and z[2] angles in degrees.
597         * @return The last ErrorCode generated.
598         */
599        public ErrorCode getAccelerometerAngles(double[] tiltAngles) {
600                int retval = PigeonImuJNI.JNI_GetAccelerometerAngles(getHandle(), tiltAngles);
601                return ErrorCode.valueOf(retval);
602        }
603
604    /**
605     * Configures all persistent settings.
606     *
607         * @param allConfigs        Object with all of the persistant settings
608     * @param timeoutMs
609     *              Timeout value in ms. If nonzero, function will wait for
610     *              config success and report an error if it times out.
611     *              If zero, no blocking or checking is performed.
612     *
613     * @return Error Code generated by function. 0 indicates no error. 
614     */
615        public ErrorCode configAllSettings(PigeonIMUConfiguration allConfigs, int timeoutMs) {
616        ErrorCollection errorCollection = new ErrorCollection();
617                
618                errorCollection.NewError(configFactoryDefault(timeoutMs));
619                
620                if(CustomParamConfigUtil.customParam0Different(allConfigs))
621                        errorCollection.NewError(configSetCustomParam(allConfigs.customParam0, 0, timeoutMs));
622                if(CustomParamConfigUtil.customParam1Different(allConfigs))
623                        errorCollection.NewError(configSetCustomParam(allConfigs.customParam1, 1, timeoutMs));
624        
625
626        return errorCollection._worstError;
627
628        }
629    /**
630     * Configures all persistent settings (overloaded so timeoutMs is 50 ms).
631     *
632         * @param allConfigs        Object with all of the persistant settings
633     *
634     * @return Error Code generated by function. 0 indicates no error. 
635     */
636        public ErrorCode configAllSettings(PigeonIMUConfiguration allConfigs) {
637                int timeoutMs = 0;
638                return  configAllSettings(allConfigs, timeoutMs);
639        }
640    /**
641     * Gets all persistant settings.
642     *
643         * @param allConfigs        Object with all of the persistant settings
644     * @param timeoutMs
645     *              Timeout value in ms. If nonzero, function will wait for
646     *              config success and report an error if it times out.
647     *              If zero, no blocking or checking is performed.
648     */
649    public void getAllConfigs(PigeonIMUConfiguration allConfigs, int timeoutMs) {
650
651        allConfigs.customParam0 = (int) configGetParameter(ParamEnum.eCustomParam, 0,  timeoutMs);
652        allConfigs.customParam1 = (int) configGetParameter(ParamEnum.eCustomParam, 1,  timeoutMs);
653    }
654    /**
655     * Gets all persistant settings (overloaded so timeoutMs is 50 ms).
656     *
657         * @param allConfigs        Object with all of the persistant settings
658     */
659    public void getAllConfigs(PigeonIMUConfiguration allConfigs) {
660        int timeoutMs = 50;
661        getAllConfigs(allConfigs, timeoutMs);
662    }   
663    /**
664     * Configures all persistent settings to defaults.
665     *
666     * @param timeoutMs
667     *              Timeout value in ms. If nonzero, function will wait for
668     *              config success and report an error if it times out.
669     *              If zero, no blocking or checking is performed.
670     *
671     * @return Error Code generated by function. 0 indicates no error. 
672     */
673        public ErrorCode configFactoryDefault(int timeoutMs) {
674                return ErrorCode.valueOf(PigeonImuJNI.JNI_ConfigFactoryDefault(getHandle(), timeoutMs));
675        }
676    /**
677     * Configures all persistent settings to defaults (overloaded so timeoutMs is 50 ms).
678     *
679     * @return Error Code generated by function. 0 indicates no error. 
680     */
681        public ErrorCode configFactoryDefault() {
682                int timeoutMs = 50;
683                return configFactoryDefault(timeoutMs);
684                
685        }
686        /**
687         * Gets the fault status
688         *
689         * @param toFill
690         *            Container for fault statuses.
691         * @return Error Code generated by function. 0 indicates no error.
692         */
693        public ErrorCode getFaults(PigeonIMU_Faults toFill) {
694                int bits = PigeonImuJNI.JNI_GetFaults(getHandle());
695                toFill.update(bits);
696                return getLastError();
697        }
698        /**
699         * Gets the sticky fault status
700         *
701         * @param toFill
702         *            Container for sticky fault statuses.
703         * @return Error Code generated by function. 0 indicates no error.
704         */
705        public ErrorCode getStickyFaults(PigeonIMU_Faults toFill) {
706                int bits = PigeonImuJNI.JNI_GetStickyFaults(getHandle());
707                toFill.update(bits);
708                return getLastError();
709        }
710
711}