Class OnboardIMU

java.lang.Object
edu.wpi.first.wpilibj.OnboardIMU

public class OnboardIMU extends Object
SystemCore onboard IMU.
  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Class
    Description
    static enum 
    A mount orientation of SystemCore.
  • Constructor Summary

    Constructors
    Constructor
    Description
    Constructs a handle to the SystemCore onboard IMU.
  • Method Summary

    Modifier and Type
    Method
    Description
    double
    Get the acceleration along the X axis of the IMU in meters per second squared.
    double
    Get the acceleration along the X axis of the IMU in meters per second squared.
    double
    Get the acceleration along the X axis of the IMU in meters per second squared.
    double
    Get the angle about the X axis of the IMU in radians.
    double
    Get the angle about the Y axis of the IMU in radians.
    double
    Get the angle about the Z axis of the IMU in radians.
    double
    Get the angular rate about the X axis of the IMU in radians per second.
    double
    Get the angular rate about the Y axis of the IMU in radians per second.
    double
    Get the angular rate about the Z axis of the IMU in radians per second.
    Get the 3D orientation as a Quaternion.
    Get the yaw as a Rotation2d.
    Get the 3D orientation as a Rotation3d.
    double
    Get the yaw value in radians.
    void
    Reset the current yaw value to 0.

    Methods inherited from class java.lang.Object

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

    • OnboardIMU

      public OnboardIMU(OnboardIMU.MountOrientation mountOrientation)
      Constructs a handle to the SystemCore onboard IMU.
      Parameters:
      mountOrientation - the mount orientation of SystemCore to determine yaw.
  • Method Details

    • getYawRadians

      public double getYawRadians()
      Get the yaw value in radians.
      Returns:
      yaw value in radians
    • resetYaw

      public void resetYaw()
      Reset the current yaw value to 0. Future reads of the yaw value will be relative to the current orientation.
    • getRotation2d

      Get the yaw as a Rotation2d.
      Returns:
      yaw
    • getRotation3d

      Get the 3D orientation as a Rotation3d.
      Returns:
      3D orientation
    • getQuaternion

      Get the 3D orientation as a Quaternion.
      Returns:
      3D orientation
    • getAngleX

      public double getAngleX()
      Get the angle about the X axis of the IMU in radians.
      Returns:
      angle about the X axis in radians
    • getAngleY

      public double getAngleY()
      Get the angle about the Y axis of the IMU in radians.
      Returns:
      angle about the Y axis in radians
    • getAngleZ

      public double getAngleZ()
      Get the angle about the Z axis of the IMU in radians.
      Returns:
      angle about the Z axis in radians
    • getGyroRateX

      public double getGyroRateX()
      Get the angular rate about the X axis of the IMU in radians per second.
      Returns:
      angular rate about the X axis in radians per second
    • getGyroRateY

      public double getGyroRateY()
      Get the angular rate about the Y axis of the IMU in radians per second.
      Returns:
      angular rate about the Y axis in radians per second
    • getGyroRateZ

      public double getGyroRateZ()
      Get the angular rate about the Z axis of the IMU in radians per second.
      Returns:
      angular rate about the Z axis in radians per second
    • getAccelX

      public double getAccelX()
      Get the acceleration along the X axis of the IMU in meters per second squared.
      Returns:
      acceleration along the X axis in meters per second squared
    • getAccelY

      public double getAccelY()
      Get the acceleration along the X axis of the IMU in meters per second squared.
      Returns:
      acceleration along the X axis in meters per second squared
    • getAccelZ

      public double getAccelZ()
      Get the acceleration along the X axis of the IMU in meters per second squared.
      Returns:
      acceleration along the X axis in meters per second squared