Class AHRS

  • All Implemented Interfaces:
    edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj.interfaces.Gyro, java.lang.AutoCloseable

    public class AHRS
    extends java.lang.Object
    implements edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj.interfaces.Gyro
    The AHRS class provides an interface to AHRS capabilities of the KauaiLabs navX Robotics Navigation Sensor via SPI, I2C and Serial (TTL UART and USB) communications interfaces on the RoboRIO. The AHRS class enables access to basic connectivity and state information, as well as key 6-axis and 9-axis orientation information (yaw, pitch, roll, compass heading, fused (9-axis) heading and magnetic disturbance detection. Additionally, the ARHS class also provides access to extended information including linear acceleration, motion detection, rotation detection and sensor temperature. If used with the navX Aero, the AHRS class also provides access to altitude, barometric pressure and pressure sensor temperature data
    • Nested Class Summary

      Nested Classes 
      Modifier and Type Class Description
      static class  AHRS.BoardAxis
      Identifies one of the three sensing axes on the navX sensor board.
      static class  AHRS.BoardYawAxis
      Indicates which sensor board axis is used as the "yaw" (gravity) axis.
      static class  AHRS.SerialDataType
      For use with serial communications, the SerialDataType specifies the type of data to be streamed from the sensor.
    • Constructor Summary

      Constructors 
      Constructor Description
      AHRS()
      Constructs the AHRS class using SPI communication and the default update rate.
      AHRS​(edu.wpi.first.wpilibj.I2C.Port i2c_port_id)
      Constructs the AHRS class using I2C communication and the default update rate.
      AHRS​(edu.wpi.first.wpilibj.I2C.Port i2c_port_id, byte update_rate_hz)
      Constructs the AHRS class using I2C communication, overriding the default update rate with a custom rate which may be from 4 to 200, representing the number of updates per second sent by the sensor.
      AHRS​(edu.wpi.first.wpilibj.SerialPort.Port serial_port_id)
      Constructs the AHRS class using serial communication and the default update rate, and returning processed (rather than raw) data.
      AHRS​(edu.wpi.first.wpilibj.SerialPort.Port serial_port_id, AHRS.SerialDataType data_type, byte update_rate_hz)
      Constructs the AHRS class using serial communication, overriding the default update rate with a custom rate which may be from 4 to 200, representing the number of updates per second sent by the sensor.
      AHRS​(edu.wpi.first.wpilibj.SPI.Port spi_port_id)
      Constructs the AHRS class using SPI communication and the default update rate.
      AHRS​(edu.wpi.first.wpilibj.SPI.Port spi_port_id, byte update_rate_hz)
      Constructs the AHRS class using SPI communication, overriding the default update rate with a custom rate which may be from 4 to 200, representing the number of updates per second sent by the sensor.
      AHRS​(edu.wpi.first.wpilibj.SPI.Port spi_port_id, int spi_bitrate, byte update_rate_hz)
      The AHRS class provides an interface to AHRS capabilities of the KauaiLabs navX Robotics Navigation Sensor via SPI, I2C and Serial (TTL UART and USB) communications interfaces on the RoboRIO.
    • Method Summary

      All Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      void calibrate()  
      void close()  
      boolean deregisterCallback​(ITimestampedDataSubscriber callback)
      Deregisters a previously registered callback interface.
      void enableBoardlevelYawReset​(boolean enable)
      Enables or disables board-level yaw zero (reset) requests.
      void enableLogging​(boolean enable)
      Enables or disables logging (via Console I/O) of AHRS library internal behaviors, including events such as transient communication errors.
      short getAccelFullScaleRangeG()
      Returns the sensor full scale range (in G) of the X, Y and X-axis accelerometers.
      int getActualUpdateRate()
      Returns the navX-Model device's currently configured update rate.
      float getAltitude()
      Returns the current altitude, based upon calibrated readings from a barometric pressure sensor, and the currently-configured sea-level barometric pressure [navX Aero only].
      double getAngle()
      Returns the total accumulated yaw angle (Z Axis, in degrees) reported by the sensor.
      double getAngleAdjustment()
      Returns the currently configured adjustment angle.
      float getBarometricPressure()
      Returns the current barometric pressure, based upon calibrated readings from the onboard pressure sensor.
      AHRS.BoardYawAxis getBoardYawAxis()
      Returns information regarding which sensor board axis (X,Y or Z) and direction (up/down) is currently configured to report Yaw (Z) angle values.
      double getByteCount()
      Returns the count in bytes of data received from the sensor.
      float getCompassHeading()
      Returns the current tilt-compensated compass heading value (in degrees, from 0 to 360) reported by the sensor.
      float getDisplacementX()
      Returns the displacement (in meters) of the X axis since resetDisplacement() was last invoked [Experimental].
      float getDisplacementY()
      Returns the displacement (in meters) of the Y axis since resetDisplacement() was last invoked [Experimental].
      float getDisplacementZ()
      Returns the displacement (in meters) of the Z axis since resetDisplacement() was last invoked [Experimental].
      java.lang.String getFirmwareVersion()
      Returns the version number of the firmware currently executing on the sensor.
      float getFusedHeading()
      Returns the "fused" (9-axis) heading.
      short getGyroFullScaleRangeDPS()
      Returns the sensor full scale range (in degrees per second) of the X, Y and X-axis gyroscopes.
      long getLastSensorTimestamp()
      Returns the sensor timestamp corresponding to the last sample retrieved from the sensor.
      float getPitch()
      Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor.
      float getPressure()
      Returns the current barometric pressure (in millibar) [navX Aero only].
      float getQuaternionW()
      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".
      float getQuaternionX()
      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".
      float getQuaternionY()
      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".
      float getQuaternionZ()
      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".
      double getRate()
      Return the rate of rotation of the yaw (Z-axis) gyro, in degrees per second.
      float getRawAccelX()
      Returns the current raw (unprocessed) X-axis acceleration rate (in G).
      float getRawAccelY()
      Returns the current raw (unprocessed) Y-axis acceleration rate (in G).
      float getRawAccelZ()
      Returns the current raw (unprocessed) Z-axis acceleration rate (in G).
      float getRawGyroX()
      Returns the current raw (unprocessed) X-axis gyro rotation rate (in degrees/sec).
      float getRawGyroY()
      Returns the current raw (unprocessed) Y-axis gyro rotation rate (in degrees/sec).
      float getRawGyroZ()
      Returns the current raw (unprocessed) Z-axis gyro rotation rate (in degrees/sec).
      float getRawMagX()
      Returns the current raw (unprocessed) X-axis magnetometer reading (in uTesla).
      float getRawMagY()
      Returns the current raw (unprocessed) Y-axis magnetometer reading (in uTesla).
      float getRawMagZ()
      Returns the current raw (unprocessed) Z-axis magnetometer reading (in uTesla).
      int getRequestedUpdateRate()
      Returns the currently requested update rate.
      float getRoll()
      Returns the current roll value (in degrees, from -180 to 180) reported by the sensor.
      float getTempC()
      Returns the current temperature (in degrees centigrade) reported by the sensor's gyro/accelerometer circuit.
      double getUpdateCount()
      Returns the count of valid updates which have been received from the sensor.
      float getVelocityX()
      Returns the velocity (in meters/sec) of the X axis [Experimental].
      float getVelocityY()
      Returns the velocity (in meters/sec) of the Y axis [Experimental].
      float getVelocityZ()
      Returns the velocity (in meters/sec) of the Z axis [Experimental].
      float getWorldLinearAccelX()
      Returns the current linear acceleration in the X-axis (in G).
      float getWorldLinearAccelY()
      Returns the current linear acceleration in the Y-axis (in G).
      float getWorldLinearAccelZ()
      Returns the current linear acceleration in the Z-axis (in G).
      float getYaw()
      Returns the current yaw value (in degrees, from -180 to 180) reported by the sensor.
      void initSendable​(edu.wpi.first.util.sendable.SendableBuilder builder)
      Initializes smart dashboard communication.
      boolean isAltitudeValid()
      Indicates whether the current altitude (and barometric pressure) data is valid.
      boolean isBoardlevelYawResetEnabled()
      Returns true if Board-level yaw resets are enabled.
      boolean isCalibrating()
      Returns true if the sensor is currently performing automatic gyro/accelerometer calibration.
      boolean isConnected()
      Indicates whether the sensor is currently connected to the host computer.
      boolean isMagneticDisturbance()
      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.
      boolean isMagnetometerCalibrated()
      Indicates whether the magnetometer has been calibrated.
      boolean isMoving()
      Indicates if the sensor is currently detecting motion, based upon the X and Y-axis world linear acceleration values.
      boolean isRotating()
      Indicates if the sensor is currently detecting yaw rotation, based upon whether the change in yaw over the last second exceeds the "Rotation Threshold."
      boolean registerCallback​(ITimestampedDataSubscriber callback, java.lang.Object callback_context)
      Registers a callback interface.
      void reset()
      Reset the Yaw gyro.
      void resetDisplacement()
      Zeros the displacement integration variables.
      void setAngleAdjustment​(double adjustment)
      Sets an amount of angle to be automatically added before returning a angle from the getAngle() method.
      void zeroYaw()
      Sets the user-specified yaw offset to the current yaw value reported by the sensor.
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
      • Methods inherited from interface edu.wpi.first.wpilibj.interfaces.Gyro

        getRotation2d
    • Constructor Detail

      • AHRS

        public AHRS​(edu.wpi.first.wpilibj.SPI.Port spi_port_id,
                    byte update_rate_hz)
        Constructs the AHRS class using SPI communication, overriding the default update rate with a custom rate which may be from 4 to 200, representing the number of updates per second sent by the sensor.

        This constructor should be used if communicating via SPI.

        Note that increasing the update rate may increase the CPU utilization.

        Parameters:
        spi_port_id - SPI Port to use
        update_rate_hz - Custom Update Rate (Hz)
      • AHRS

        public AHRS​(edu.wpi.first.wpilibj.SPI.Port spi_port_id,
                    int spi_bitrate,
                    byte update_rate_hz)
        The AHRS class provides an interface to AHRS capabilities of the KauaiLabs navX Robotics Navigation Sensor via SPI, I2C and Serial (TTL UART and USB) communications interfaces on the RoboRIO. The AHRS class enables access to basic connectivity and state information, as well as key 6-axis and 9-axis orientation information (yaw, pitch, roll, compass heading, fused (9-axis) heading and magnetic disturbance detection. Additionally, the ARHS class also provides access to extended information including linear acceleration, motion detection, rotation detection and sensor temperature. If used with the navX Aero, the AHRS class also provides access to altitude, barometric pressure and pressure sensor temperature data This constructor allows the specification of a custom SPI bitrate, in bits/second.
        Parameters:
        spi_port_id - SPI Port to use
        spi_bitrate - SPI bitrate (Maximum: 2,000,000)
        update_rate_hz - Custom Update Rate (Hz)
      • AHRS

        public AHRS​(edu.wpi.first.wpilibj.I2C.Port i2c_port_id,
                    byte update_rate_hz)
        Constructs the AHRS class using I2C communication, overriding the default update rate with a custom rate which may be from 4 to 200, representing the number of updates per second sent by the sensor.

        This constructor should be used if communicating via I2C.

        Note that increasing the update rate may increase the CPU utilization.

        Parameters:
        i2c_port_id - I2C Port to use
        update_rate_hz - Custom Update Rate (Hz)
      • AHRS

        public AHRS​(edu.wpi.first.wpilibj.SerialPort.Port serial_port_id,
                    AHRS.SerialDataType data_type,
                    byte update_rate_hz)
        Constructs the AHRS class using serial communication, overriding the default update rate with a custom rate which may be from 4 to 200, representing the number of updates per second sent by the sensor.

        This constructor should be used if communicating via either TTL UART or USB Serial interface.

        Note that the serial interfaces can communicate either processed data, or raw data, but not both simultaneously. If simultaneous processed and raw data are needed, use one of the register-based interfaces (SPI or I2C).

        Note that increasing the update rate may increase the CPU utilization.

        Parameters:
        serial_port_id - SerialPort to use
        data_type - either kProcessedData or kRawData
        update_rate_hz - Custom Update Rate (Hz)
      • AHRS

        public AHRS()
        Constructs the AHRS class using SPI communication and the default update rate.

        This constructor should be used if communicating via SPI.

      • AHRS

        public AHRS​(edu.wpi.first.wpilibj.SPI.Port spi_port_id)
        Constructs the AHRS class using SPI communication and the default update rate.

        This constructor should be used if communicating via SPI.

        Parameters:
        spi_port_id - SPI port to use.
      • AHRS

        public AHRS​(edu.wpi.first.wpilibj.I2C.Port i2c_port_id)
        Constructs the AHRS class using I2C communication and the default update rate.

        This constructor should be used if communicating via I2C.

        Parameters:
        i2c_port_id - I2C port to use
      • AHRS

        public AHRS​(edu.wpi.first.wpilibj.SerialPort.Port serial_port_id)
        Constructs the AHRS class using serial communication and the default update rate, and returning processed (rather than raw) data.

        This constructor should be used if communicating via either TTL UART or USB Serial interface.

        Parameters:
        serial_port_id - SerialPort to use
    • Method Detail

      • getPitch

        public float getPitch()
        Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor. Pitch is a measure of rotation around the X Axis.
        Returns:
        The current pitch value in degrees (-180 to 180).
      • getRoll

        public float getRoll()
        Returns the current roll value (in degrees, from -180 to 180) reported by the sensor. Roll is a measure of rotation around the X Axis.
        Returns:
        The current roll value in degrees (-180 to 180).
      • getYaw

        public float getYaw()
        Returns the current yaw value (in degrees, from -180 to 180) reported by the sensor. Yaw is a measure of rotation around the Z Axis (which is perpendicular to the earth).

        Note that the returned yaw value will be offset by a user-specified offset value; this user-specified offset value is set by invoking the zeroYaw() method.

        Returns:
        The current yaw value in degrees (-180 to 180).
      • getCompassHeading

        public float getCompassHeading()
        Returns the current tilt-compensated compass heading value (in degrees, from 0 to 360) reported by the sensor.

        Note that this value is sensed by a magnetometer, which can be affected by nearby magnetic fields (e.g., the magnetic fields generated by nearby motors).

        Before using this value, ensure that (a) the magnetometer has been calibrated and (b) that a magnetic disturbance is not taking place at the instant when the compass heading was generated.

        Returns:
        The current tilt-compensated compass heading, in degrees (0-360).
      • zeroYaw

        public void zeroYaw()
        Sets the user-specified yaw offset to the current yaw value reported by the sensor.

        This user-specified yaw offset is automatically subtracted from subsequent yaw values reported by the getYaw() method. NOTE: This method has no effect if the sensor is currently calibrating, since resetting the yaw will interfere with the calibration process.

      • isCalibrating

        public boolean isCalibrating()
        Returns true if the sensor is currently performing automatic gyro/accelerometer calibration. Automatic calibration occurs when the sensor is initially powered on, during which time the sensor should be held still, with the Z-axis pointing up (perpendicular to the earth).

        NOTE: During this automatic calibration, the yaw, pitch and roll values returned may not be accurate.

        Once calibration is complete, the sensor will automatically remove an internal yaw offset value from all reported values.

        Returns:
        Returns true if the sensor is currently automatically calibrating the gyro and accelerometer sensors.
      • isConnected

        public boolean isConnected()
        Indicates whether the sensor is currently connected to the host computer. A connection is considered established whenever communication with the sensor has occurred recently.

        Returns:
        Returns true if a valid update has been recently received from the sensor.
      • getByteCount

        public double getByteCount()
        Returns the count in bytes of data received from the sensor. This could can be useful for diagnosing connectivity issues.

        If the byte count is increasing, but the update count (see getUpdateCount()) is not, this indicates a software misconfiguration.

        Returns:
        The number of bytes received from the sensor.
      • getActualUpdateRate

        public int getActualUpdateRate()
        Returns the navX-Model device's currently configured update rate. Note that the update rate that can actually be realized is a value evenly divisible by the navX-Model device's internal motion processor sample clock (200Hz). Therefore, the rate that is returned may be lower than the requested sample rate. The actual sample rate is rounded down to the nearest integer that is divisible by the number of Digital Motion Processor clock ticks. For instance, a request for 58 Hertz will result in an actual rate of 66Hz (200 / (200 / 58), using integer math.
        Returns:
        Returns the current actual update rate in Hz (cycles per second).
      • getRequestedUpdateRate

        public int getRequestedUpdateRate()
        Returns the currently requested update rate. rate. Note that not every update rate can actually be realized, since the actual update rate must be a value evenly divisible by the navX-Model device's internal motion processor sample clock (200Hz). To determine the actual update rate, use the getActualUpdateRate() method.
        Returns:
        Returns the requested update rate in Hz (cycles per second).
      • getUpdateCount

        public double getUpdateCount()
        Returns the count of valid updates which have been received from the sensor. This count should increase at the same rate indicated by the configured update rate.
        Returns:
        The number of valid updates received from the sensor.
      • getLastSensorTimestamp

        public long getLastSensorTimestamp()
        Returns the sensor timestamp corresponding to the last sample retrieved from the sensor. Note that this sensor timestamp is only provided when the Register-based IO methods (SPI, I2C) are used; sensor timestamps are not provided when Serial-based IO methods (TTL UART, USB) are used.
        Returns:
        The sensor timestamp corresponding to the current AHRS sensor data.
      • getWorldLinearAccelX

        public float getWorldLinearAccelX()
        Returns the current linear acceleration in the X-axis (in G).

        World linear acceleration refers to raw acceleration data, which has had the gravity component removed, and which has been rotated to the same reference frame as the current yaw value. The resulting value represents the current acceleration in the x-axis of the body (e.g., the robot) on which the sensor is mounted.

        Returns:
        Current world linear acceleration in the X-axis (in G).
      • getWorldLinearAccelY

        public float getWorldLinearAccelY()
        Returns the current linear acceleration in the Y-axis (in G).

        World linear acceleration refers to raw acceleration data, which has had the gravity component removed, and which has been rotated to the same reference frame as the current yaw value. The resulting value represents the current acceleration in the Y-axis of the body (e.g., the robot) on which the sensor is mounted.

        Returns:
        Current world linear acceleration in the Y-axis (in G).
      • getWorldLinearAccelZ

        public float getWorldLinearAccelZ()
        Returns the current linear acceleration in the Z-axis (in G).

        World linear acceleration refers to raw acceleration data, which has had the gravity component removed, and which has been rotated to the same reference frame as the current yaw value. The resulting value represents the current acceleration in the Z-axis of the body (e.g., the robot) on which the sensor is mounted.

        Returns:
        Current world linear acceleration in the Z-axis (in G).
      • isMoving

        public boolean isMoving()
        Indicates if the sensor is currently detecting motion, based upon the X and Y-axis world linear acceleration values. If the sum of the absolute values of the X and Y axis exceed a "motion threshold", the motion state is indicated.

        Returns:
        Returns true if the sensor is currently detecting motion.
      • isRotating

        public boolean isRotating()
        Indicates if the sensor is currently detecting yaw rotation, based upon whether the change in yaw over the last second exceeds the "Rotation Threshold."

        Yaw Rotation can occur either when the sensor is rotating, or when the sensor is not rotating AND the current gyro calibration is insufficiently calibrated to yield the standard yaw drift rate.

        Returns:
        Returns true if the sensor is currently detecting motion.
      • getBarometricPressure

        public float getBarometricPressure()
        Returns the current barometric pressure, based upon calibrated readings from the onboard pressure sensor. This value is in units of millibar.

        NOTE: This value is only valid for a navX Aero. To determine whether this value is valid, see isAltitudeValid().

        Returns:
        Returns current barometric pressure (navX Aero only).
      • getAltitude

        public float getAltitude()
        Returns the current altitude, based upon calibrated readings from a barometric pressure sensor, and the currently-configured sea-level barometric pressure [navX Aero only]. This value is in units of meters.

        NOTE: This value is only valid sensors including a pressure sensor. To determine whether this value is valid, see isAltitudeValid().

        Returns:
        Returns current altitude in meters (as long as the sensor includes an installed on-board pressure sensor).
      • isAltitudeValid

        public boolean isAltitudeValid()
        Indicates whether the current altitude (and barometric pressure) data is valid. This value will only be true for a sensor with an onboard pressure sensor installed.

        If this value is false for a board with an installed pressure sensor, this indicates a malfunction of the onboard pressure sensor.

        Returns:
        Returns true if a working pressure sensor is installed.
      • getFusedHeading

        public float getFusedHeading()
        Returns the "fused" (9-axis) heading.

        The 9-axis heading is the fusion of the yaw angle, the tilt-corrected compass heading, and magnetic disturbance detection. Note that the magnetometer calibration procedure is required in order to achieve valid 9-axis headings.

        The 9-axis Heading represents the sensor's best estimate of current heading, based upon the last known valid Compass Angle, and updated by the change in the Yaw Angle since the last known valid Compass Angle. The last known valid Compass Angle is updated whenever a Calibrated Compass Angle is read and the sensor has recently rotated less than the Compass Noise Bandwidth (~2 degrees).

        Returns:
        Fused Heading in Degrees (range 0-360)
      • isMagneticDisturbance

        public boolean isMagneticDisturbance()
        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.

        This function will always return false if the sensor's magnetometer has not yet been calibrated; see isMagnetometerCalibrated().

        Returns:
        true if a magnetic disturbance is detected (or the magnetometer is uncalibrated).
      • isMagnetometerCalibrated

        public boolean isMagnetometerCalibrated()
        Indicates whether the magnetometer has been calibrated.

        Magnetometer Calibration must be performed by the user.

        Note that if this function does indicate the magnetometer is calibrated, this does not necessarily mean that the calibration quality is sufficient to yield valid compass headings.

        Returns:
        Returns true if magnetometer calibration has been performed.
      • getQuaternionW

        public float getQuaternionW()
        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".

        Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians.

        For more information on Quaternions and their use, please see this definition.

        Returns:
        Returns the imaginary portion (W) of the quaternion.
      • getQuaternionX

        public float getQuaternionX()
        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".

        Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians.

        For more information on Quaternions and their use, please see this description.

        Returns:
        Returns the real portion (X) of the quaternion.
      • getQuaternionY

        public float getQuaternionY()
        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". Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians. For more information on Quaternions and their use, please see: https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation
        Returns:
        Returns the real portion (X) of the quaternion.
      • getQuaternionZ

        public float getQuaternionZ()
        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". Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians. For more information on Quaternions and their use, please see: https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation
        Returns:
        Returns the real portion (X) of the quaternion.
      • resetDisplacement

        public void resetDisplacement()
        Zeros the displacement integration variables. Invoke this at the moment when integration begins.
      • getVelocityX

        public float getVelocityX()
        Returns the velocity (in meters/sec) of the X axis [Experimental]. NOTE: This feature is experimental. Velocity measures rely on integration of acceleration values from MEMS accelerometers which yield "noisy" values. The resulting velocities are not known to be very accurate.
        Returns:
        Current Velocity (in meters/squared).
      • getVelocityY

        public float getVelocityY()
        Returns the velocity (in meters/sec) of the Y axis [Experimental]. NOTE: This feature is experimental. Velocity measures rely on integration of acceleration values from MEMS accelerometers which yield "noisy" values. The resulting velocities are not known to be very accurate.
        Returns:
        Current Velocity (in meters/squared).
      • getVelocityZ

        public float getVelocityZ()
        Returns the velocity (in meters/sec) of the Z axis [Experimental]. NOTE: This feature is experimental. Velocity measures rely on integration of acceleration values from MEMS accelerometers which yield "noisy" values. The resulting velocities are not known to be very accurate.
        Returns:
        Current Velocity (in meters/squared).
      • getDisplacementX

        public float getDisplacementX()
        Returns the displacement (in meters) of the X axis since resetDisplacement() was last invoked [Experimental]. NOTE: This feature is experimental. Displacement measures rely on double-integration of acceleration values from MEMS accelerometers which yield "noisy" values. The resulting displacement are not known to be very accurate, and the amount of error increases quickly as time progresses.
        Returns:
        Displacement since last reset (in meters).
      • getDisplacementY

        public float getDisplacementY()
        Returns the displacement (in meters) of the Y axis since resetDisplacement() was last invoked [Experimental]. NOTE: This feature is experimental. Displacement measures rely on double-integration of acceleration values from MEMS accelerometers which yield "noisy" values. The resulting displacement are not known to be very accurate, and the amount of error increases quickly as time progresses.
        Returns:
        Displacement since last reset (in meters).
      • getDisplacementZ

        public float getDisplacementZ()
        Returns the displacement (in meters) of the Z axis since resetDisplacement() was last invoked [Experimental]. NOTE: This feature is experimental. Displacement measures rely on double-integration of acceleration values from MEMS accelerometers which yield "noisy" values. The resulting displacement are not known to be very accurate, and the amount of error increases quickly as time progresses.
        Returns:
        Displacement since last reset (in meters).
      • registerCallback

        public boolean registerCallback​(ITimestampedDataSubscriber callback,
                                        java.lang.Object callback_context)
        Registers a callback interface. This interface will be called back when new data is available, based upon a change in the sensor timestamp.

        Note that this callback will occur within the context of the device IO thread, which is not the same thread context the caller typically executes in.

        Parameters:
        callback - The callback object to be invoked when callbacks occur
        callback_context - The callback context object to be passed as a parameter to the callback object.
        Returns:
        returns true if callback was successfully registered.
      • deregisterCallback

        public boolean deregisterCallback​(ITimestampedDataSubscriber callback)
        Deregisters a previously registered callback interface. Be sure to deregister any callback which have been previously registered, to ensure that the object implementing the callback interface does not continue to be accessed when no longer necessary.
        Parameters:
        callback - The previously-registered callback object to be deregistered.
        Returns:
        returns true if callback was successfully deregistered.
      • getAngle

        public double getAngle()
        Returns the total accumulated yaw angle (Z Axis, in degrees) reported by the sensor.

        NOTE: The angle is continuous, meaning it's range is beyond 360 degrees. This ensures that algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.

        Note that the returned yaw value will be offset by a user-specified offset value; this user-specified offset value is set by invoking the zeroYaw() method.

        Specified by:
        getAngle in interface edu.wpi.first.wpilibj.interfaces.Gyro
        Returns:
        The current total accumulated yaw angle (Z axis) of the robot in degrees. This heading is based on integration of the returned rate from the Z-axis (yaw) gyro.
      • getRate

        public double getRate()
        Return the rate of rotation of the yaw (Z-axis) gyro, in degrees per second.

        The rate is based on the most recent reading of the yaw gyro angle.

        Specified by:
        getRate in interface edu.wpi.first.wpilibj.interfaces.Gyro
        Returns:
        The current rate of change in yaw angle (in degrees per second)
      • setAngleAdjustment

        public void setAngleAdjustment​(double adjustment)
        Sets an amount of angle to be automatically added before returning a angle from the getAngle() method. This allows users of the getAngle() method to logically rotate the sensor by a given amount of degrees.

        NOTE 1: The adjustment angle is only applied to the value returned from getAngle() - it does not adjust the value returned from getYaw(), nor any of the quaternion values.

        NOTE 2: The adjustment angle is notautomatically cleared whenever the sensor yaw angle is reset.

        If not set, the default adjustment angle is 0 degrees (no adjustment).

        Parameters:
        adjustment - , in degrees (range: -360 to 360)
      • getAngleAdjustment

        public double getAngleAdjustment()
        Returns the currently configured adjustment angle. See setAngleAdjustment() for more details. If this method returns 0 degrees, no adjustment to the value returned via getAngle() will occur.
        Returns:
        adjustment, in degrees (range: -360 to 360)
      • reset

        public void reset()
        Reset the Yaw gyro.

        Resets the Gyro Z (Yaw) axis to a heading of zero. This can be used if there is significant drift in the gyro and it needs to be recalibrated after it has been running.

        Specified by:
        reset in interface edu.wpi.first.wpilibj.interfaces.Gyro
      • getRawGyroX

        public float getRawGyroX()
        Returns the current raw (unprocessed) X-axis gyro rotation rate (in degrees/sec). NOTE: this value is un-processed, and should only be accessed by advanced users. Typically, rotation about the X Axis is referred to as "Pitch". Calibrated and Integrated Pitch data is accessible via the getPitch() method.

        Returns:
        Returns the current rotation rate (in degrees/sec).
      • getRawGyroY

        public float getRawGyroY()
        Returns the current raw (unprocessed) Y-axis gyro rotation rate (in degrees/sec). NOTE: this value is un-processed, and should only be accessed by advanced users. Typically, rotation about the T Axis is referred to as "Roll". Calibrated and Integrated Pitch data is accessible via the getRoll() method.

        Returns:
        Returns the current rotation rate (in degrees/sec).
      • getRawGyroZ

        public float getRawGyroZ()
        Returns the current raw (unprocessed) Z-axis gyro rotation rate (in degrees/sec). NOTE: this value is un-processed, and should only be accessed by advanced users. Typically, rotation about the T Axis is referred to as "Yaw". Calibrated and Integrated Pitch data is accessible via the getYaw() method.

        Returns:
        Returns the current rotation rate (in degrees/sec).
      • getRawAccelX

        public float getRawAccelX()
        Returns the current raw (unprocessed) X-axis acceleration rate (in G). NOTE: this value is unprocessed, and should only be accessed by advanced users. This raw value has not had acceleration due to gravity removed from it, and has not been rotated to the world reference frame. Gravity-corrected, world reference frame-corrected X axis acceleration data is accessible via the getWorldLinearAccelX() method.

        Returns:
        Returns the current acceleration rate (in G).
      • getRawAccelY

        public float getRawAccelY()
        Returns the current raw (unprocessed) Y-axis acceleration rate (in G). NOTE: this value is unprocessed, and should only be accessed by advanced users. This raw value has not had acceleration due to gravity removed from it, and has not been rotated to the world reference frame. Gravity-corrected, world reference frame-corrected Y axis acceleration data is accessible via the getWorldLinearAccelY() method.

        Returns:
        Returns the current acceleration rate (in G).
      • getRawAccelZ

        public float getRawAccelZ()
        Returns the current raw (unprocessed) Z-axis acceleration rate (in G). NOTE: this value is unprocessed, and should only be accessed by advanced users. This raw value has not had acceleration due to gravity removed from it, and has not been rotated to the world reference frame. Gravity-corrected, world reference frame-corrected Z axis acceleration data is accessible via the getWorldLinearAccelZ() method.

        Returns:
        Returns the current acceleration rate (in G).
      • getRawMagX

        public float getRawMagX()
        Returns the current raw (unprocessed) X-axis magnetometer reading (in uTesla). NOTE: this value is unprocessed, and should only be accessed by advanced users. This raw value has not been tilt-corrected, and has not been combined with the other magnetometer axis data to yield a compass heading. Tilt-corrected compass heading data is accessible via the getCompassHeading() method.

        Returns:
        Returns the mag field strength (in uTesla).
      • getRawMagY

        public float getRawMagY()
        Returns the current raw (unprocessed) Y-axis magnetometer reading (in uTesla). NOTE: this value is unprocessed, and should only be accessed by advanced users. This raw value has not been tilt-corrected, and has not been combined with the other magnetometer axis data to yield a compass heading. Tilt-corrected compass heading data is accessible via the getCompassHeading() method.

        Returns:
        Returns the mag field strength (in uTesla).
      • getRawMagZ

        public float getRawMagZ()
        Returns the current raw (unprocessed) Z-axis magnetometer reading (in uTesla). NOTE: this value is unprocessed, and should only be accessed by advanced users. This raw value has not been tilt-corrected, and has not been combined with the other magnetometer axis data to yield a compass heading. Tilt-corrected compass heading data is accessible via the getCompassHeading() method.

        Returns:
        Returns the mag field strength (in uTesla).
      • getPressure

        public float getPressure()
        Returns the current barometric pressure (in millibar) [navX Aero only].

        This value is valid only if a barometric pressure sensor is onboard.

        Returns:
        Returns the current barometric pressure (in millibar).
      • getTempC

        public float getTempC()
        Returns the current temperature (in degrees centigrade) reported by the sensor's gyro/accelerometer circuit.

        This value may be useful in order to perform advanced temperature- correction of raw gyroscope and accelerometer values.

        Returns:
        The current temperature (in degrees centigrade).
      • getBoardYawAxis

        public AHRS.BoardYawAxis getBoardYawAxis()
        Returns information regarding which sensor board axis (X,Y or Z) and direction (up/down) is currently configured to report Yaw (Z) angle values. NOTE: If the board firmware supports Omnimount, the board yaw axis/direction are configurable.

        For more information on Omnimount, please see:

        http://navx-mxp.kauailabs.com/navx-mxp/installation/omnimount/

        Returns:
        The currently-configured board yaw axis/direction.
      • getFirmwareVersion

        public java.lang.String getFirmwareVersion()
        Returns the version number of the firmware currently executing on the sensor.

        To update the firmware to the latest version, please see:

        http://navx-mxp.kauailabs.com/navx-mxp/support/updating-firmware/

        Returns:
        The firmware version in the format [MajorVersion].[MinorVersion]
      • enableLogging

        public void enableLogging​(boolean enable)
        Enables or disables logging (via Console I/O) of AHRS library internal behaviors, including events such as transient communication errors.
        Parameters:
        enable - true to enable logging; false to disable logging
      • enableBoardlevelYawReset

        public void enableBoardlevelYawReset​(boolean enable)
        Enables or disables board-level yaw zero (reset) requests. Board-level yaw resets are processed by the sensor board and the resulting yaw angle may not be available to the client software until at least 2 update cycles have occurred. Board-level yaw resets however do maintain synchronization between the yaw angle and the sensor-generated Quaternion and Fused Heading values. Conversely, Software-based yaw resets occur instantaneously; however, Software- based yaw resets do not update the yaw angle component of the sensor-generated Quaternion values or the Fused Heading values.
        Parameters:
        enable - true to enable board-level yaw resets; false to enable software-based yaw resets.
      • isBoardlevelYawResetEnabled

        public boolean isBoardlevelYawResetEnabled()
        Returns true if Board-level yaw resets are enabled. Conversely, returns false if Software-based yaw resets are active.
        Returns:
        true if Board-level yaw resets are enabled; false if software-based yaw resets are active.
      • getGyroFullScaleRangeDPS

        public short getGyroFullScaleRangeDPS()
        Returns the sensor full scale range (in degrees per second) of the X, Y and X-axis gyroscopes.
        Returns:
        gyroscope full scale range in degrees/second.
      • getAccelFullScaleRangeG

        public short getAccelFullScaleRangeG()
        Returns the sensor full scale range (in G) of the X, Y and X-axis accelerometers.
        Returns:
        accelerometer full scale range in G.
      • initSendable

        public void initSendable​(edu.wpi.first.util.sendable.SendableBuilder builder)
        Initializes smart dashboard communication.
        Specified by:
        initSendable in interface edu.wpi.first.util.sendable.Sendable
        Parameters:
        builder - The SendableBuilder which will be registered with.
      • close

        public void close()
        Specified by:
        close in interface java.lang.AutoCloseable
      • calibrate

        public void calibrate()
        Specified by:
        calibrate in interface edu.wpi.first.wpilibj.interfaces.Gyro