A B C D E F G I K L N O P R S T U V W Y Z
All Classes All Packages
All Classes All Packages
All Classes All Packages
A
- ABSOLUTE - com.kauailabs.navx.ftc.navXPIDController.ToleranceType
- AHRS - Class in com.kauailabs.navx.ftc
-
The AHRS class provides an interface to AHRS capabilities of the KauaiLabs navX2 and navX Robotics Navigation Sensor via I2Cs on the Android- based FTC robotics control system, where communications occur via an I2C port on the REV Expansion Hub or REV Control Hub.
- AHRS(NavxMicroNavigationSensor, AHRS.DeviceDataType, int) - Constructor for class com.kauailabs.navx.ftc.AHRS
- AHRS.BoardAxis - Enum in com.kauailabs.navx.ftc
-
Identifies one of the three sensing axes on the navX sensor board.
- AHRS.BoardYawAxis - Class in com.kauailabs.navx.ftc
-
Indicates which sensor board axis is used as the "yaw" (gravity) axis.
- AHRS.DeviceDataType - Enum in com.kauailabs.navx.ftc
-
The DeviceDataType specifies the type of data to be retrieved from the sensor.
- ALTITUDE - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
B
- board_axis - Variable in class com.kauailabs.navx.ftc.AHRS.BoardYawAxis
- BoardYawAxis() - Constructor for class com.kauailabs.navx.ftc.AHRS.BoardYawAxis
C
- close() - Method in class com.kauailabs.navx.ftc.AHRS
- close() - Method in class com.kauailabs.navx.ftc.navXPIDController
- com.kauailabs.navx.ftc - package com.kauailabs.navx.ftc
- COMPASS_HEADING - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
D
- deregisterCallback(IDataArrivalSubscriber) - Method in class com.kauailabs.navx.ftc.AHRS
-
Deregisters a previously registered callback interface.
E
- enable(boolean) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Enables/disables the PID controller.
F
- FUSED_HEADING - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
G
- get() - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Returns the current output value calculated by the navXPIDController based upon the last navX-Model device data sample received.
- getActualUpdateRate() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the navX-Model device's currently configured update rate.
- getAltitude() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current altitude, based upon calibrated readings from a barometric pressure sensor, and the currently-configured sea-level barometric pressure [navX Aero only].
- getBoardYawAxis() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns information regarding which sensor board axis (X,Y or Z) and direction (up/down) is currently configured to report Yaw (Z) angle values.
- getByteCount() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the count in bytes of data received from the sensor.
- getCompassHeading() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current tilt-compensated compass heading value (in degrees, from 0 to 360) reported by the sensor.
- getCurrentTransferRate() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current number of data samples being transferred from the navX-Model device in the last second.
- getDeliveredRateHz() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
The delivered rate is the rate at which samples are delivered to the Android-based FTC robotics control application.
- getDeviceDataType() - Method in class com.kauailabs.navx.ftc.AHRS
- getDimTransferRateHz() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
The rate at which the Core Device Interface Module (DIM) is currently delivering data samples to the navx_ftc library IO thread.
- getDuplicateDataCount() - Method in class com.kauailabs.navx.ftc.AHRS
- getError() - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Returns the current amount of error calculated by the navXPIDController based upon the last navX-Model device data sample.
- getFirmwareVersion() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the version number of the firmware currently executing on the sensor.
- getFusedHeading() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the "fused" (9-axis) heading.
- getInstance(NavxMicroNavigationSensor, AHRS.DeviceDataType) - Static method in class com.kauailabs.navx.ftc.AHRS
-
Returns the single instance (singleton) of the AHRS class.
- getInstance(NavxMicroNavigationSensor, AHRS.DeviceDataType, byte) - Static method in class com.kauailabs.navx.ftc.AHRS
-
Returns the single instance (singleton) of the AHRS class.
- getLastSensorTimestampDeltaMS() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
The last sensor timestamp delta indicates the period of time between reception of the last two samples from the navX-Model device, for those data samples which are timestamped with a sensor timestamp.
- getLastSystemTimestampDeltaMS() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
The last system timestamp delta indicates the period of time between reception of the last two samples from the navX-Model device, for those data samples which do not provide a corresponding sensor timestamp and are instead timestamped using the Android OS system timestamp.
- getLogging() - Static method in class com.kauailabs.navx.ftc.AHRS
- getNumEstimatedMissedUntimestampedSamples() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
The number of samples which were expected to be received from the navX-Model device which are believed to have not arrived based upon the Android OS system timestamp.
- getNumMissedSensorTimestampedSamples() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
The number of samples which were expected to be received from the navX-Model device which never arrived, since the last time the navXPerformanceMonitor's statistics were reset.
- getOutput() - Method in class com.kauailabs.navx.ftc.navXPIDController.PIDResult
-
Returns the output value calculated by the navXPIDController which corresponds to the most recent input data sample.
- getPitch() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor.
- getPressure() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current barometric pressure (in millibar) [navX Aero only].
- getQuaternionW() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the imaginary portion (W) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last "zeroed".
- getQuaternionX() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the real portion (X axis) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last "zeroed".
- getQuaternionY() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the real portion (X axis) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last "zeroed".
- getQuaternionZ() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the real portion (X axis) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last "zeroed".
- getRawAccelX() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) X-axis acceleration rate (in G).
- getRawAccelY() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) Y-axis acceleration rate (in G).
- getRawAccelZ() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) Z-axis acceleration rate (in G).
- getRawGyroX() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) X-axis gyro rotation rate (in degrees/sec).
- getRawGyroY() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) Y-axis gyro rotation rate (in degrees/sec).
- getRawGyroZ() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) Z-axis gyro rotation rate (in degrees/sec).
- getRawMagX() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) X-axis magnetometer reading (in uTesla).
- getRawMagY() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) Y-axis magnetometer reading (in uTesla).
- getRawMagZ() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current raw (unprocessed) Z-axis magnetometer reading (in uTesla).
- getRoll() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current roll value (in degrees, from -180 to 180) reported by the sensor.
- getSensorRateHz() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
The sensor tate is the rate at which the navX-Model device sensor is currently configured to deliver sample.
- getSetpoint() - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Returns the currently configured setpoint.
- getTempC() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current temperature (in degrees centigrade) reported by the sensor's gyro/accelerometer circuit.
- getTimestamp() - Method in class com.kauailabs.navx.ftc.navXPIDController.PIDResult
-
Returns the timestamp of the last data sample processed by the navXPIDController.
- getUpdateCount() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the count of valid updates which have been received from the sensor.
- getValue() - Method in enum com.kauailabs.navx.ftc.AHRS.BoardAxis
- getValue() - Method in enum com.kauailabs.navx.ftc.AHRS.DeviceDataType
- getWorldLinearAccelX() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current linear acceleration in the X-axis (in G).
- getWorldLinearAccelY() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current linear acceleration in the Y-axis (in G).
- getWorldLinearAccelZ() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current linear acceleration in the Z-axis (in G).
- getYaw() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns the current yaw value (in degrees, from -180 to 180) reported by the sensor.
I
- IDataArrivalSubscriber - Interface in com.kauailabs.navx.ftc
-
The IDataArrivalSubscriber interface provides a method for consumers of navX-Model device data to be rapidly notified whenever new data has arrived.
- isAltitudeValid() - Method in class com.kauailabs.navx.ftc.AHRS
-
Indicates whether the current altitude (and barometric pressure) data is valid.
- isCalibrating() - Method in class com.kauailabs.navx.ftc.AHRS
-
Returns true if the sensor is currently performing automatic gyro/accelerometer calibration.
- isConnected() - Method in class com.kauailabs.navx.ftc.AHRS
-
Indicates whether the sensor is currently connected to the host computer.
- isEnabled() - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Returns true if the navXPIDController is currently enabled, otherwise return false.
- isMagneticDisturbance() - Method in class com.kauailabs.navx.ftc.AHRS
-
Indicates whether the current magnetic field strength diverges from the calibrated value for the earth's magnetic field by more than the currently- configured Magnetic Disturbance Ratio.
- isMagnetometerCalibrated() - Method in class com.kauailabs.navx.ftc.AHRS
-
Indicates whether the magnetometer has been calibrated.
- isMoving() - Method in class com.kauailabs.navx.ftc.AHRS
-
Indicates if the sensor is currently detecting motion, based upon the X and Y-axis world linear acceleration values.
- isNewUpdateAvailable(navXPIDController.PIDResult) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
isNewUpdateAvailable() should be called by clients of the navXPIDController which need to "poll" to determine whether new navX-Model device data has been received.
- isOnTarget() - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Indicates whether the navXPIDController has determined that it is "on_target" based upon whether the current error is within the range defined by the tolerance.
- isOnTarget() - Method in class com.kauailabs.navx.ftc.navXPIDController.PIDResult
-
Returns true if the navXPIDController indicated that it is currently "on target" as defined by the configured tolerances and the most recent input data sample.
- isRotating() - Method in class com.kauailabs.navx.ftc.AHRS
-
Indicates if the sensor is currently detecting yaw rotation, based upon whether the change in yaw over the last second exceeds the "Rotation Threshold."
K
- kAll - com.kauailabs.navx.ftc.AHRS.DeviceDataType
-
All processed and raw data, sensor status and timestamps.
- kBoardAxisX - com.kauailabs.navx.ftc.AHRS.BoardAxis
- kBoardAxisY - com.kauailabs.navx.ftc.AHRS.BoardAxis
- kBoardAxisZ - com.kauailabs.navx.ftc.AHRS.BoardAxis
- kProcessedData - com.kauailabs.navx.ftc.AHRS.DeviceDataType
-
(default): All 6 and 9-axis processed data, sensor status and timestamp
- kQuatAndRawData - com.kauailabs.navx.ftc.AHRS.DeviceDataType
-
Unit Quaternions and unprocessed data from each individual sensor.
L
- LINEAR_ACCEL_X - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
- LINEAR_ACCEL_Y - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
- LINEAR_ACCEL_Z - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
N
- navXPerformanceMonitor - Class in com.kauailabs.navx.ftc
-
The navXPerformanceMonitor class is designed to provide performance data to help tune the navx_ftc library's AHRS_OLD class to retrieve navX-Model device data using tuning parameters appropriate for a particular FTC robotic controller configuration.
- navXPerformanceMonitor(AHRS) - Constructor for class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
Constructor for the navXPerformanceMonitor class.
- navXPIDController - Class in com.kauailabs.navx.ftc
-
The navXPIDController implements a timestamped PID controller (designed to deal with the jitter which is typically present in a networked control system scenario).
- navXPIDController(AHRS, navXPIDController.navXTimestampedDataSource) - Constructor for class com.kauailabs.navx.ftc.navXPIDController
-
This navXPIDController constructor is used when the PID Controller is to be driven by a navX-Model device input data source which is accompanied by a high-accuracy "sensor" timestamp.
- navXPIDController(AHRS, navXPIDController.navXUntimestampedDataSource) - Constructor for class com.kauailabs.navx.ftc.navXPIDController
-
This navXPIDController constructor is used when the PID Controller is to be driven by a navX-Model device input data source which is not accompanied by a high-accuracy "sensor" timestamp.
- navXPIDController.navXTimestampedDataSource - Enum in com.kauailabs.navx.ftc
-
The navXTimestampedDataSources specifies the navX-Model device sensor data source type used by the navXPIDController as it's input data source.
- navXPIDController.navXUntimestampedDataSource - Enum in com.kauailabs.navx.ftc
-
The navXUntimestampedDataSources specifies the navX-Model device sensor data source type used by the navXPIDController as it's input data source.
- navXPIDController.PIDResult - Class in com.kauailabs.navx.ftc
-
The PIDResult class encapsulates the data used by the navXPIDController to communicate current state to a client of the navXPIDController.
- navXPIDController.TimestampType - Enum in com.kauailabs.navx.ftc
- navXPIDController.ToleranceType - Enum in com.kauailabs.navx.ftc
-
The ToleranceType enumeration defines the type of tolerance to be used by the navXPIDController to determine whether the controller is "on_target".
- NONE - com.kauailabs.navx.ftc.navXPIDController.ToleranceType
O
- on_target - Variable in class com.kauailabs.navx.ftc.navXPIDController.PIDResult
- output - Variable in class com.kauailabs.navx.ftc.navXPIDController.PIDResult
P
- PERCENT - com.kauailabs.navx.ftc.navXPIDController.ToleranceType
- PIDResult() - Constructor for class com.kauailabs.navx.ftc.navXPIDController.PIDResult
- PITCH - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
R
- RAW_ACCEL_X - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_ACCEL_Y - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_ACCEL_Z - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_GYRO_X - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_GYRO_Y - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_GYRO_Z - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_MAG_X - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_MAG_Y - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- RAW_MAG_Z - com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
- registerCallback(IDataArrivalSubscriber) - Method in class com.kauailabs.navx.ftc.AHRS
-
Registers a callback interface.
- reset() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
-
Resets the peformance monitoring statistics.
- reset() - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Resets the PIDController's current error value as well as the integrated error.
- ROLL - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
S
- SENSOR - com.kauailabs.navx.ftc.navXPIDController.TimestampType
- setContinuous(boolean) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
setContinuous() is used to enable/disable the continuous mode of operation.
- setInputRange(double, double) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Defines the range of possible input values received from the currently-selected navX-Model device data source.
- setLogging(boolean) - Static method in class com.kauailabs.navx.ftc.AHRS
- setOutputRange(double, double) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Defines the range of output values calculated by the navXPIDController.
- setPID(double, double, double) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
setPID() is used to set the Proportional, Integral and Differential coefficients used by the navXPIDController.
- setPID(double, double, double, double) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
setPID() is used to set the Proportional, Integral, Differential and FeedForward coefficients used by the navXPIDController.
- setSetpoint(double) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Defines the "target" value the navXPIDController attempts to reach.
- setTolerance(navXPIDController.ToleranceType, double) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
Used to specify the tolerance used to determine whether the navXPIDController is "on_target".
- stepController(double, int) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
stepController() is the PIDController worker function, which is used internally by the navXPIDController whenever a new navX-Model device sensor data value is received.
- SYSTEM - com.kauailabs.navx.ftc.navXPIDController.TimestampType
T
- timestamp - Variable in class com.kauailabs.navx.ftc.navXPIDController.PIDResult
- timestampedDataReceived(long, long, Object) - Method in interface com.kauailabs.navx.ftc.IDataArrivalSubscriber
- timestampedDataReceived(long, long, Object) - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
- timestampedDataReceived(long, long, Object) - Method in class com.kauailabs.navx.ftc.navXPIDController
U
- untimestampedDataReceived(long, Object) - Method in interface com.kauailabs.navx.ftc.IDataArrivalSubscriber
- untimestampedDataReceived(long, Object) - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
- untimestampedDataReceived(long, Object) - Method in class com.kauailabs.navx.ftc.navXPIDController
- up - Variable in class com.kauailabs.navx.ftc.AHRS.BoardYawAxis
V
- valueOf(String) - Static method in enum com.kauailabs.navx.ftc.AHRS.BoardAxis
-
Returns the enum constant of this type with the specified name.
- valueOf(String) - Static method in enum com.kauailabs.navx.ftc.AHRS.DeviceDataType
-
Returns the enum constant of this type with the specified name.
- valueOf(String) - Static method in enum com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
-
Returns the enum constant of this type with the specified name.
- valueOf(String) - Static method in enum com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
-
Returns the enum constant of this type with the specified name.
- valueOf(String) - Static method in enum com.kauailabs.navx.ftc.navXPIDController.TimestampType
-
Returns the enum constant of this type with the specified name.
- valueOf(String) - Static method in enum com.kauailabs.navx.ftc.navXPIDController.ToleranceType
-
Returns the enum constant of this type with the specified name.
- values() - Static method in enum com.kauailabs.navx.ftc.AHRS.BoardAxis
-
Returns an array containing the constants of this enum type, in the order they are declared.
- values() - Static method in enum com.kauailabs.navx.ftc.AHRS.DeviceDataType
-
Returns an array containing the constants of this enum type, in the order they are declared.
- values() - Static method in enum com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
-
Returns an array containing the constants of this enum type, in the order they are declared.
- values() - Static method in enum com.kauailabs.navx.ftc.navXPIDController.navXUntimestampedDataSource
-
Returns an array containing the constants of this enum type, in the order they are declared.
- values() - Static method in enum com.kauailabs.navx.ftc.navXPIDController.TimestampType
-
Returns an array containing the constants of this enum type, in the order they are declared.
- values() - Static method in enum com.kauailabs.navx.ftc.navXPIDController.ToleranceType
-
Returns an array containing the constants of this enum type, in the order they are declared.
W
- waitForNewUpdate(navXPIDController.PIDResult, int) - Method in class com.kauailabs.navx.ftc.navXPIDController
-
waitForNewUpdate() should be called by clients of the navXPIDController which want to "wait" until new navX-Model device data has been received.
Y
- YAW - com.kauailabs.navx.ftc.navXPIDController.navXTimestampedDataSource
- yawReset() - Method in interface com.kauailabs.navx.ftc.IDataArrivalSubscriber
- yawReset() - Method in class com.kauailabs.navx.ftc.navXPerformanceMonitor
- yawReset() - Method in class com.kauailabs.navx.ftc.navXPIDController
Z
- zeroYaw() - Method in class com.kauailabs.navx.ftc.AHRS
-
Sets the user-specified yaw offset to the current yaw value reported by the sensor.
All Classes All Packages