Class Navx

java.lang.Object
com.studica.frc.Navx

public class Navx extends Object
  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Class
    Description
    static enum 
    Enum for the user to select which USB port they connect the
  • Constructor Summary

    Constructors
    Constructor
    Description
    Navx(int deviceId)
    NavX3 object constructor with default 100Hz update rate.
    Navx(int deviceId, int updateRate)
    NavX3 object constructor with custom update rate.
    NavX3 object constructor for USB communication with default 100Hz update rate
    Navx(Navx.Port port, int updateRate)
    NavX3 object constructor for USB communication.
  • Method Summary

    Modifier and Type
    Method
    Description
    void
    Destructs the NavX C++ Instance
    int
    enable9DYaw(boolean enable)
    Enable Yaw to use 9D instead of 6D
    int
    enableOptionalMessages(boolean yaw, boolean angle, boolean quat6d, boolean quat9d, boolean algoStates, boolean pitchRoll, boolean angularVel, boolean linearAccel, boolean compass, boolean temperature)
    Used to pick what sort of data is needed to be sent via the CAN bus
    int
    getAlgoStates(float[] states)
    Get selected filtering algorithm parameters to observe settings or calibration
    Gets the countinous angle from the IMU filtering algorithm.
    Get angular velocity measurements from the gyroscope when not at rest
    int
    getCompass(float[] mag)
    Get raw, yaw offsetted magnetic field values from the magnetometer
    Get linear acceleration measurements from the accelerometer when not at rest
    Gets the converted pitch angle from the IMU filtering algorithm.
    Gets the 6-axis quaternion (no magnetometer).
    Gets the 9-axis quaternion (with magnetometer).
    Gets the converted roll angle from the IMU filtering algorithm.
    Gets the robot heading as a Rotation2d based on yaw.
    Gets a Rotation3d constructed from the navx quaternion.
    int
    getSensorUUID(int[] uuid)
    Get internal sensor UUID
    Get the gyroscope chip temperature
    Gets the converted yaw angle from the IMU filtering algorithm.
    int
    Reset IMU Yaw back to 0
    int
    selfTest(int[] ret)
    Trigger IMU self test functionality on gyroscope and accelerometer unit
    int
    setODRHz(int odr_hz)
    Set the CAN and USB user data output rate, must be less than 1000Hz (IMU update rate)

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • Navx

      public Navx(int deviceId)
      NavX3 object constructor with default 100Hz update rate.
      Parameters:
      deviceId - CAN ID for the IMU connected to the Rio.
    • Navx

      public Navx(int deviceId, int updateRate)
      NavX3 object constructor with custom update rate.
      Parameters:
      deviceId - CAN ID for the IMU connected to the Rio.
      updateRate - CAN message output rate.
    • Navx

      public Navx(Navx.Port port)
      NavX3 object constructor for USB communication with default 100Hz update rate
      Parameters:
      port - The USB port in use
    • Navx

      public Navx(Navx.Port port, int updateRate)
      NavX3 object constructor for USB communication.
      Parameters:
      port - The USB port in use
      updateRate - USB data output rate (Hz)
  • Method Details

    • destroy

      public void destroy()
      Destructs the NavX C++ Instance
    • getYaw

      public Angle getYaw()
      Gets the converted yaw angle from the IMU filtering algorithm.
      Returns:
      The yaw as a WPILib units Angle, 360 deg indicates an error.
    • getPitch

      public Angle getPitch()
      Gets the converted pitch angle from the IMU filtering algorithm.
      Returns:
      The pitch as a WPILib units Angle, 360 deg indicates an error.
    • getRoll

      public Angle getRoll()
      Gets the converted roll angle from the IMU filtering algorithm.
      Returns:
      The roll as a float constrained between 180 and -180, 360 for errors.
    • getAngle

      public Angle getAngle()
      Gets the countinous angle from the IMU filtering algorithm.
      Returns:
      The angle as a WPILib units Angle, NaN for errors.
    • getAlgoStates

      public int getAlgoStates(float[] states)
      Get selected filtering algorithm parameters to observe settings or calibration
      Parameters:
      states - Array of 9 elements: - [0..2] Estimated gyroscope bias (x,y,z) - [3] 1 if detected at rest, else 0 - [4] 1 if no magnetic disturbance, else 0 - [5] mag_ref_norm - [6] mag_candidate_norm - [7] mag_ref_dip - [8] mag_candidate_dip
      Returns:
      0 OK, 1 ERROR
    • getQuat6D

      public Quaternion getQuat6D()
      Gets the 6-axis quaternion (no magnetometer).
      Returns:
      Quaternion {w, x, y, z}, or (1,0,0,0) if the call fails.
    • getQuat9D

      public Quaternion getQuat9D()
      Gets the 9-axis quaternion (with magnetometer).
      Returns:
      Quaternion {w, x, y, z}, or (1,0,0,0) if the call fails.
    • getRotation2d

      public Rotation2d getRotation2d()
      Gets the robot heading as a Rotation2d based on yaw.
      Returns:
      Heading as Rotation2d.
    • getRotation3d

      public Rotation3d getRotation3d()
      Gets a Rotation3d constructed from the navx quaternion.
      Returns:
      Rotation3d, or (1,0,0,0) if the quaternion fetch fails.
    • getAngularVel

      public AngularVelocity[] getAngularVel()
      Get angular velocity measurements from the gyroscope when not at rest
      Returns:
      WPILib Units Angular Velocity array {x, y, z} in degrees per second, or (0,0,0) on error
    • getLinearAccel

      public LinearAcceleration[] getLinearAccel()
      Get linear acceleration measurements from the accelerometer when not at rest
      Returns:
      WPILib Units LinearAcceleration Array {x, y, z} in m/s^2, or (0,0,0) on error
    • getCompass

      public int getCompass(float[] mag)
      Get raw, yaw offsetted magnetic field values from the magnetometer
      Parameters:
      mag - [0] x component. (mT)
      mag - [1] y component. (mT)
      mag - [2] z component. (mT)
      mag - [3] norm. (mT)
      Returns:
      0 OK, 1 ERROR
    • selfTest

      public int selfTest(int[] ret)
      Trigger IMU self test functionality on gyroscope and accelerometer unit
      Parameters:
      ret - Array of 8 elements: - [0] Gyroscope status. - [1..3] Gyroscope status (x,y,z). - [4] Accelerometer status. - [5..7] Accelerometer status (x,y,z).
      Returns:
      0 OK, 1 ERROR
    • resetYaw

      public int resetYaw()
      Reset IMU Yaw back to 0
      Returns:
      0 OK, 1 ERROR
    • setODRHz

      public int setODRHz(int odr_hz)
      Set the CAN and USB user data output rate, must be less than 1000Hz (IMU update rate)
      Returns:
      0 OK, 1 ERROR
    • enableOptionalMessages

      public int enableOptionalMessages(boolean yaw, boolean angle, boolean quat6d, boolean quat9d, boolean algoStates, boolean pitchRoll, boolean angularVel, boolean linearAccel, boolean compass, boolean temperature)
      Used to pick what sort of data is needed to be sent via the CAN bus
      Parameters:
      yaw - Boolean value to enable yaw messages.
      angle - Boolean value to enable angle messages.
      quat6d - Boolean value to enable 6-axis quaternion messages.
      quat9d - Boolean value to enable 9-axis quaternion messages.
      algoStates - Boolean value to enable algorithm states messages.
      pitchRoll - Boolean value to enable pitch and roll messages.
      angularVel - Boolean value to enable angular velocity messages.
      linearAccel - Boolean value to enable linear acceleration messages.
      compass - Boolean value to enable mag compass measurement messages.
      temperature - Boolean value to enable temperature messages.
      Returns:
      0 OK, 1 ERROR
    • getSensorUUID

      public int getSensorUUID(int[] uuid)
      Get internal sensor UUID
      Parameters:
      uuid - Retrieved 96-bit UUID
      Returns:
      0 OK, 1 ERROR
    • getTemperature

      public Temperature getTemperature()
      Get the gyroscope chip temperature
      Returns:
      The temperature in WPILib units Celsius.
    • enable9DYaw

      public int enable9DYaw(boolean enable)
      Enable Yaw to use 9D instead of 6D
      Parameters:
      enable - turns on 9D
      Returns:
      0 OK, 1 ERROR