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;
025
026import com.ctre.phoenix.ErrorCode;
027import com.ctre.phoenix.ErrorCollection;
028import com.ctre.phoenix.ParamEnum;
029
030/**
031 * Pigeon 2 Class. Class supports communicating over CANbus.
032 *
033 * <pre>
034 * {@code
035 * // Example usage of a Pigeon 2
036 * Pigeon2 pigeon = new Pigeon2(0); // creates a new Pigeon2 with ID 0
037 *
038 * Pigeon2Configuration config = new Pigeon2Configuration();
039 * // set mount pose as rolled 90 degrees counter-clockwise
040 * config.MountPoseYaw = 0;
041 * config.MountPosePitch = 0;
042 * config.MountPoseRoll = 90;
043 * pigeon.configAllSettings(config);
044 *
045 * System.out.println(pigeon.getYaw()); // prints the yaw of the Pigeon
046 * System.out.println(pigeon.getPitch()); // prints the pitch of the Pigeon
047 * System.out.println(pigeon.getRoll()); // prints the roll of the Pigeon
048 *
049 * double gravityVec[] = new double[3];
050 * pigeon.getGravityVector(gravityVec); // gets the gravity vector of the Pigeon 2
051 *
052 * ErrorCode error = pigeon.getLastError(); // gets the last error generated by the Pigeon
053 * Pigeon2_Faults faults = new Pigeon2_Faults();
054 * ErrorCode faultsError = pigeon.getFaults(faults); // fills faults with the current Pigeon 2 faults; returns the last error generated
055 * }
056 * </pre>
057 *
058 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
059 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
060 * Phoenix 6 API. A migration guide is available at
061 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
062 * <p>
063 * If the Phoenix 5 API must be used for this device, the device must have 22.X
064 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
065 * the firmware year dropdown.
066 */
067@Deprecated(since = "2024", forRemoval = true)
068public class Pigeon2 extends BasePigeon {
069        /**
070         * Create a Pigeon object that communicates with Pigeon on CAN Bus.
071         *
072         * @param deviceNumber
073         *            CAN Device Id of Pigeon [0,62]
074         * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux),
075         *               or a CANivore device name or serial number
076         */
077        public Pigeon2(int deviceNumber, String canbus) {
078                super(deviceNumber, "v2", canbus);
079        }
080        /**
081         * Create a Pigeon object that communicates with Pigeon on CAN Bus.
082         *
083         * @param deviceNumber
084         *            CAN Device Id of Pigeon [0,62]
085         */
086        public Pigeon2(int deviceNumber) {
087                this(deviceNumber, "");
088        }
089
090        /**
091         * Enumerations for what primary axis to talk about
092         * Positive indicates in the direction, negative indicates in the opposite direction
093         */
094        public enum AxisDirection {
095                PositiveZ,
096                PositiveY,
097                PositiveX,
098                NegativeZ,
099                NegativeY,
100                NegativeX,
101        }
102        /**
103         * Configure the Mount Pose using the primary axis.
104         * This is useful if the Pigeon 2.0 is mounted straight, and you only
105         * need to describe what axis is forward and what axis is up.
106         * 
107         * @param forward Axis that points forward from the robot
108         * @param up Axis that points up from the robot
109         * @return OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.
110         */
111        public ErrorCode configMountPose(AxisDirection forward, AxisDirection up) {
112                int timeoutMs = 50;
113                return configMountPose(forward, up, timeoutMs);
114        }
115
116        /**
117         * Configure the Mount Pose using the primary axis.
118         * This is useful if the Pigeon 2.0 is mounted straight, and you only
119         * need to describe what axis is forward and what axis is up.
120         * 
121         * @param forward Axis that points forward from the robot
122         * @param up Axis that points up from the robot
123         * @param timeoutMs Config timeout in milliseconds.
124         * @return OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.
125         */
126        public ErrorCode configMountPose(AxisDirection forward, AxisDirection up, int timeoutMs) {
127                switch(forward) {
128                        case PositiveX:
129                        case NegativeX:
130                        {
131                                // Positive and negative X is only dictated by if we don't rotate or rotate 180
132                                double yaw = forward == AxisDirection.PositiveX ? 0 : 180;
133                                switch(up) {
134                                        case PositiveX:
135                                        case NegativeX:
136                                                return ErrorCode.InvalidParamValue;
137                                        case PositiveZ:
138                                                return configMountPose(yaw, 0, 0, timeoutMs); // No rotation
139                                        case NegativeZ:
140                                                return configMountPose(yaw, 0, 180, timeoutMs); // Flip upside down
141                                        case PositiveY:
142                                                return configMountPose(yaw, 0, 90, timeoutMs); // Roll 90 degrees right
143                                        case NegativeY:
144                                                return configMountPose(yaw, 0, -90, timeoutMs); // Roll 90 degrees left
145                                }
146                        }
147                        case PositiveY:
148                        case NegativeY:
149                        {
150                                // Positive and negative Y is mostly only dictated by if we yaw left or right 90 degrees
151                                double yaw = forward == AxisDirection.PositiveY ? -90 : 90;
152                                switch(up) {
153                                        case PositiveY:
154                                        case NegativeY:
155                                                return ErrorCode.InvalidParamValue;
156                                        case PositiveZ:
157                                                return configMountPose(yaw, 0, 0, timeoutMs); // No rotation
158                                        case NegativeZ:
159                                                return configMountPose(-yaw, 0, 180, timeoutMs); // Reverse the yaw, and flip 180
160                                        case PositiveX:
161                                                return configMountPose(yaw, -90, 0, timeoutMs); // Pitch 90 degrees up
162                                        case NegativeX:
163                                                return configMountPose(yaw, 90, 0, timeoutMs); // Pitch 90 degrees down
164                                }
165                        }
166                        // Positive and negative Z are very different configurations, spell each of them out
167                        case PositiveZ:
168                        {
169                                switch(up) {
170                                        case PositiveZ:
171                                        case NegativeZ:
172                                                return ErrorCode.InvalidParamValue;
173                                        case PositiveX:
174                                                return configMountPose(180, -90, 0, timeoutMs); // Flip around and pitch up
175                                        case NegativeX:
176                                                return configMountPose(0, 90, 0, timeoutMs); // Just pitch down
177                                        case PositiveY:
178                                                return configMountPose(90, 0, 90, timeoutMs); // Yaw 90 left then Roll 90 right
179                                        case NegativeY:
180                                                return configMountPose(-90, 0, -90, timeoutMs); // Yaw 90 right then Roll 90 left
181                                }
182                        }
183                        case NegativeZ:
184                        {
185                                switch(up) {
186                                        case PositiveZ:
187                                        case NegativeZ:
188                                                return ErrorCode.InvalidParamValue;
189                                        case PositiveX:
190                                                return configMountPose(0, -90, 0, timeoutMs); // Just pitch up 
191                                        case NegativeX:
192                                                return configMountPose(180, 90, 0, timeoutMs); // Flip around and pitch down
193                                        case PositiveY:
194                                                return configMountPose(-90, 0, 90, timeoutMs); // Yaw 90 right then Roll 90 right
195                                        case NegativeY:
196                                                return configMountPose(90, 0, -90, timeoutMs); // Yaw 90 left then Roll 90 left
197                                }
198                        }
199                }
200                return ErrorCode.InvalidParamValue;
201        }
202
203        /**
204         * Configure the mounting pose of the Pigeon2.<p>
205         * This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current
206         *  orientation, referenced from the robot's point of view.<p>
207         * This is only necessary if the Pigeon2 is mounted at an exotic angle
208         *  near the gimbal lock point or not forward. <p>
209         * If the pigeon is relatively flat and pointed forward, this is not needed.<p>
210         * <p>
211         * Examples:<p>
212         * If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw,
213         *  0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.<p>
214         * If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it
215         *  pitched 90 degrees clockwise. <p>
216         * @param yaw Yaw angle needed to reach the current orientation in degrees.
217         * @param pitch Pitch angle needed to reach the current orientation in degrees.
218         * @param roll Roll angle needed to reach the current orientation in degrees.
219         * @param timeoutMs Config timeout in milliseconds.
220         * @return Worst error code of all config sets.
221         */
222        public ErrorCode configMountPose(double yaw, double pitch, double roll, int timeoutMs) {
223                ErrorCode err = ErrorCode.OK;
224                if(err == ErrorCode.OK) {
225                        err = configMountPoseYaw(yaw, timeoutMs);
226                }
227                if(err == ErrorCode.OK) {
228                        err = configMountPosePitch(pitch, timeoutMs);
229                }
230                if(err == ErrorCode.OK) {
231                        err = configMountPoseRoll(roll, timeoutMs);
232                }
233                return err;
234        }
235        /**
236         * Configure the mounting pose of the Pigeon2.<p>
237         * This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current
238         *  orientation, referenced from the robot's point of view.<p>
239         * This is only necessary if the Pigeon2 is mounted at an exotic angle
240         *  near the gimbal lock point or not forward. <p>
241         * If the pigeon is relatively flat and pointed forward, this is not needed.<p>
242         * <p>
243         * Examples:<p>
244         * If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw,
245         *  0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.<p>
246         * If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it
247         *  pitched 90 degrees clockwise. <p>
248         * @param yaw Yaw angle needed to reach the current orientation in degrees.
249         * @param pitch Pitch angle needed to reach the current orientation in degrees.
250         * @param roll Roll angle needed to reach the current orientation in degrees.
251         * @return Worst error code of all config sets.
252         */
253        public ErrorCode configMountPose(double yaw, double pitch, double roll) {
254                return configMountPose(yaw, pitch, roll, 0);
255        }
256
257        /**
258         * Configure the mounting pose Yaw of the Pigeon2.
259         * See {@link #configMountPose(double, double, double, int)}
260         * 
261         * @param yaw Yaw angle needed to reach the current orientation in degrees.
262         * @param timeoutMs Config timeout in milliseconds.
263         * @return ErrorCode of configSet
264         */
265        public ErrorCode configMountPoseYaw(double yaw, int timeoutMs) {
266                return configSetParameter(ParamEnum.eConfigMountPoseYaw, yaw, 0, 0, timeoutMs);
267        }
268        /**
269         * Configure the mounting pose Yaw of the Pigeon2.
270         * See {@link #configMountPose(double, double, double)}
271         * 
272         * @param yaw Yaw angle needed to reach the current orientation in degrees.
273         * @return ErrorCode of configSet
274         */
275        public ErrorCode configMountPoseYaw(double yaw) {
276                return configMountPoseYaw(yaw, 0);
277        }
278
279        /**
280         * Configure the mounting pose Pitch of the Pigeon2.
281         * See {@link #configMountPose(double, double, double, int)}
282         * 
283         * @param pitch Pitch angle needed to reach the current orientation in degrees.
284         * @param timeoutMs Config timeout in milliseconds.
285         * @return ErrorCode of configSet
286         */
287        public ErrorCode configMountPosePitch(double pitch, int timeoutMs) {
288                return configSetParameter(ParamEnum.eConfigMountPosePitch, pitch, 0, 0, timeoutMs);
289        }
290        /**
291         * Configure the mounting pose Pitch of the Pigeon2.
292         * See {@link #configMountPose(double, double, double)}
293         * 
294         * @param pitch Pitch angle needed to reach the current orientation in degrees.
295         * @return ErrorCode of configSet
296         */
297        public ErrorCode configMountPosePitch(double pitch) {
298                return configMountPosePitch(pitch, 0);
299        }
300
301        /**
302         * Configure the mounting pose Roll of the Pigeon2.
303         * See {@link #configMountPose(double, double, double, int)}
304         * 
305         * @param roll Roll angle needed to reach the current orientation in degrees.
306         * @param timeoutMs Config timeout in milliseconds.
307         * @return ErrorCode of configSet
308         */
309        public ErrorCode configMountPoseRoll(double roll, int timeoutMs) {
310                return configSetParameter(ParamEnum.eConfigMountPoseRoll, roll, 0, 0, timeoutMs);
311        }
312        /**
313         * Configure the mounting pose Roll of the Pigeon2.
314         * See {@link #configMountPose(double, double, double)}
315         * 
316         * @param roll Roll angle needed to reach the current orientation in degrees.
317         * @return ErrorCode of configSet
318         */
319        public ErrorCode configMountPoseRoll(double roll) {
320                return configMountPoseRoll(roll, 0);
321        }
322        /**
323         * Configures the X Axis Gyroscope Error for 1 rotation
324         * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
325         * @param timeoutMs Config timeout in milliseconds.
326         * @return ErrorCode fo configSet
327         */
328        public ErrorCode configXAxisGyroError(double err, int timeoutMs) {
329                return configSetParameter(ParamEnum.eConfigGyroScalarX, err, 0, 0, timeoutMs);
330        }
331        /**
332         * Configures the X Axis Gyroscope Error for 1 rotation
333         * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
334         * @return ErrorCode fo configSet
335         */
336        public ErrorCode configXAxisGyroError(double err) {
337                return configXAxisGyroError(err, 0);
338        }
339        /**
340         * Configures the Y Axis Gyroscope Error for 1 rotation
341         * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
342         * @param timeoutMs Config timeout in milliseconds.
343         * @return ErrorCode fo configSet
344         */
345        public ErrorCode configYAxisGyroError(double err, int timeoutMs) {
346                return configSetParameter(ParamEnum.eConfigGyroScalarY, err, 0, 0, timeoutMs);
347        }
348        /**
349         * Configures the Y Axis Gyroscope Error for 1 rotation
350         * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
351         * @return ErrorCode fo configSet
352         */
353        public ErrorCode configYAxisGyroError(double err) {
354                return configYAxisGyroError(err, 0);
355        }
356        /**
357         * Configures the Z Axis Gyroscope Error for 1 rotation
358         * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
359         * @param timeoutMs Config timeout in milliseconds.
360         * @return ErrorCode fo configSet
361         */
362        public ErrorCode configZAxisGyroError(double err, int timeoutMs) {
363                return configSetParameter(ParamEnum.eConfigGyroScalarZ, err, 0, 0, timeoutMs);
364        }
365        /**
366         * Configures the Z Axis Gyroscope Error for 1 rotation
367         * @param err Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
368         * @return ErrorCode fo configSet
369         */
370        public ErrorCode configZAxisGyroError(double err) {
371                return configZAxisGyroError(err, 0);
372        }
373        /**
374         * Enables the magnetometer fusion for Pigeon2. This is **not** recommended for FRC use
375         * 
376         * @param enable Boolean to enable/disable magnetometer fusion
377         * @param timeoutMs Config timeout in milliseconds.
378         * @return ErrorCode Status of the config response
379         */
380        public ErrorCode configEnableCompass(boolean enable, int timeoutMs) {
381                return configSetParameter(ParamEnum.eChangeCompassUse, enable ? 1 : 0, 0, 0, timeoutMs);
382        }
383        /**
384         * Enables the magnetometer fusion for Pigeon2. This is **not** recommended for FRC use
385         * 
386         * @param enable Boolean to enable/disable magnetometer fusion
387         * @return ErrorCode Status of the config response
388         */
389        public ErrorCode configEnableCompass(boolean enable) {
390                return configEnableCompass(enable, 0);
391        }
392        /**
393         * Disables temperature compensation from Pigeon2.
394         * 
395         * @param disable Boolean to disable/enable temperature compensation
396         * @param timeoutMs Config timeout in milliseconds.
397         * @return ErrorCode Status of the config response
398         */
399        public ErrorCode configDisableTemperatureCompensation(boolean disable, int timeoutMs) {
400                return configSetParameter(ParamEnum.eDontRunThermComp, disable ? 1 : 0, 0, 0, timeoutMs);
401        }
402        /**
403         * Disables temperature compensation from Pigeon2.
404         * 
405         * @param disable Boolean to disable/enable temperature compensation
406         * @return ErrorCode Status of the config response
407         */
408        public ErrorCode configDisableTemperatureCompensation(boolean disable) {
409                return configDisableTemperatureCompensation(disable, 0);
410        }
411        /**
412         * Disables the no-motion calibration from Pigeon2
413         * 
414         * @param disable Boolean to disable/enable no-motion calibration
415         * @param timeoutMs Config timeout in milliseconds.
416         * @return ErrorCode Status of the config response
417         */
418        public ErrorCode configDisableNoMotionCalibration(boolean disable, int timeoutMs) {
419                return configSetParameter(ParamEnum.eSetNoMotionCalDisable, disable ? 1 : 0, 0, 0, timeoutMs);
420        }
421        /**
422         * Disables the no-motion calibration from Pigeon2
423         * 
424         * @param disable Boolean to disable/enable no-motion calibration
425         * @return ErrorCode Status of the config response
426         */
427        public ErrorCode configDisableNoMotionCalibration(boolean disable) {
428                return configDisableNoMotionCalibration(disable, 0);
429        }
430        /**
431         * Performs an offset calibration on gyro bias
432         * 
433         * @param timeoutMs Config timeout in milliseconds.
434         * @return ErrorCode Status of the config response
435         */
436        public ErrorCode zeroGyroBiasNow(int timeoutMs) {
437                return configSetParameter(ParamEnum.eGyroBias, 1, 0, 0, timeoutMs);
438        }
439        /**
440         * Performs an offset calibration on gyro bias
441         * 
442         * @return ErrorCode Status of the config response
443         */
444        public ErrorCode zeroGyroBiasNow() {
445                return zeroGyroBiasNow(0);
446        }
447
448    /**
449     * Configures all persistent settings.
450     *
451     * @param allConfigs        Object with all of the persistant settings
452     * @param timeoutMs
453     *              Timeout value in ms. If nonzero, function will wait for
454     *              config success and report an error if it times out.
455     *              If zero, no blocking or checking is performed.
456     *
457     * @return Error Code generated by function. 0 indicates no error.
458     */
459        public ErrorCode configAllSettings(Pigeon2Configuration settings, int timeoutMs) {
460        ErrorCollection errorCollection = new ErrorCollection();
461        errorCollection.NewError(configFactoryDefault(timeoutMs));
462
463                if(Pigeon2ConfigUtil.mountPoseYawDifferent(settings)) errorCollection.NewError(configMountPoseYaw(settings.MountPoseYaw, timeoutMs));
464                if(Pigeon2ConfigUtil.mountPosePitchDifferent(settings)) errorCollection.NewError(configMountPosePitch(settings.MountPosePitch, timeoutMs));
465                if(Pigeon2ConfigUtil.mountPoseRollDifferent(settings)) errorCollection.NewError(configMountPoseRoll(settings.MountPoseRoll, timeoutMs));
466                if(Pigeon2ConfigUtil.enableCompassDifferent(settings)) errorCollection.NewError(configEnableCompass(settings.EnableCompass, timeoutMs));
467                if(Pigeon2ConfigUtil.disableNoMotionCalibrationDifferent(settings)) errorCollection.NewError(configDisableNoMotionCalibration(settings.DisableNoMotionCalibration, timeoutMs));
468                if(Pigeon2ConfigUtil.disableTemperatureCompensationDifferent(settings)) errorCollection.NewError(configDisableTemperatureCompensation(settings.DisableTemperatureCompensation, timeoutMs));
469                if(Pigeon2ConfigUtil.xAxisGyroErrorDifferent(settings)) errorCollection.NewError(configXAxisGyroError(settings.XAxisGyroError, timeoutMs));
470                if(Pigeon2ConfigUtil.yAxisGyroErrorDifferent(settings)) errorCollection.NewError(configYAxisGyroError(settings.YAxisGyroError, timeoutMs));
471                if(Pigeon2ConfigUtil.zAxisGyroErrorDifferent(settings)) errorCollection.NewError(configZAxisGyroError(settings.ZAxisGyroError, timeoutMs));
472                if(Pigeon2ConfigUtil.customParam0Different(settings)) errorCollection.NewError(configSetCustomParam(settings.customParam0, 0, timeoutMs));
473                if(Pigeon2ConfigUtil.customParam1Different(settings)) errorCollection.NewError(configSetCustomParam(settings.customParam1, 1, timeoutMs));
474
475                return errorCollection._worstError;
476        }
477    /**
478     * Configures all persistent settings.
479     *
480     * @param allConfigs        Object with all of the persistant settings
481     *
482     * @return Error Code generated by function. 0 indicates no error.
483     */
484        public ErrorCode configAllSettings(Pigeon2Configuration settings) {
485                int timeoutMs = 50;
486                return configAllSettings(settings, timeoutMs);
487        }
488
489        /**
490         * Get the Gravity Vector.
491         * 
492         * This provides a vector that points toward ground. This is useful for applications like
493         *  an arm, where the z-value of the gravity vector corresponds to the feed-forward needed
494         *  to hold the arm steady.
495         * The gravity vector is calculated after the mount pose, so if the pigeon is where it was
496         *  mounted, the gravity vector is {0, 0, 1}.
497         * @param gravVector Pass in a double array of size 3 to get the gravity vector
498         * @return Errorcode of getter
499         */
500        public ErrorCode getGravityVector(double[] gravVector) {
501                int retval = PigeonImuJNI.JNI_GetGravityVector(getHandle(), gravVector);
502                return ErrorCode.valueOf(retval);
503        }
504        /**
505         * Gets the fault status
506         *
507         * @param toFill
508         *            Container for fault statuses.
509         * @return Error Code generated by function. 0 indicates no error.
510         */
511        public ErrorCode getFaults(Pigeon2_Faults toFill) {
512                int bits = PigeonImuJNI.JNI_GetFaults(getHandle());
513                toFill.update(bits);
514                return getLastError();
515        }
516        /**
517         * Gets the sticky fault status
518         *
519         * @param toFill
520         *            Container for sticky fault statuses.
521         * @return Error Code generated by function. 0 indicates no error.
522         */
523        public ErrorCode getStickyFaults(Pigeon2_Faults toFill) {
524                int bits = PigeonImuJNI.JNI_GetStickyFaults(getHandle());
525                toFill.update(bits);
526                return getLastError();
527        }
528    /**
529     * Gets all persistant settings.
530     *
531     * @param allConfigs        Object with all of the persistant settings
532     * @param timeoutMs
533     *              Timeout value in ms. If nonzero, function will wait for
534     *              config success and report an error if it times out.
535     *              If zero, no blocking or checking is performed.
536     */
537    public void getAllConfigs(Pigeon2Configuration allConfigs, int timeoutMs) {
538                allConfigs.MountPoseYaw = configGetParameter(ParamEnum.eConfigMountPoseYaw, 0, timeoutMs);
539                allConfigs.MountPosePitch = configGetParameter(ParamEnum.eConfigMountPosePitch, 0, timeoutMs);
540                allConfigs.MountPoseRoll = configGetParameter(ParamEnum.eConfigMountPoseRoll, 0, timeoutMs);
541                allConfigs.DisableNoMotionCalibration = configGetParameter(ParamEnum.eSetNoMotionCalDisable, 0, timeoutMs) != 0;
542                allConfigs.DisableTemperatureCompensation = configGetParameter(ParamEnum.eDontRunThermComp, 0, timeoutMs) != 0;
543                allConfigs.EnableCompass = configGetParameter(ParamEnum.eChangeCompassUse, 0, timeoutMs) != 0;
544                allConfigs.XAxisGyroError = configGetParameter(ParamEnum.eConfigGyroScalarX, 0, timeoutMs);
545                allConfigs.YAxisGyroError = configGetParameter(ParamEnum.eConfigGyroScalarY, 0, timeoutMs);
546                allConfigs.ZAxisGyroError = configGetParameter(ParamEnum.eConfigGyroScalarZ, 0, timeoutMs);
547
548        allConfigs.customParam0 = (int)configGetParameter(ParamEnum.eCustomParam, 0, timeoutMs);
549        allConfigs.customParam1 = (int)configGetParameter(ParamEnum.eCustomParam, 1, timeoutMs);
550    }
551    /**
552     * Gets all persistant settings.
553     *
554     * @param allConfigs        Object with all of the persistant settings
555     */
556    public void getAllConfigs(Pigeon2Configuration allConfigs) {
557        int timeoutMs = 50;
558        getAllConfigs(allConfigs, timeoutMs);
559    }
560}