Class IMUJNI


public class IMUJNI extends JNIWrapper
IMU Functions.
See Also:
  • "wpi/hal/IMU.h"
  • Constructor Details

  • Method Details

    • getIMUAcceleration

      public static void getIMUAcceleration(double[] accel)
      Get the acceleration along the axes of the IMU in meters per second squared.
      Parameters:
      accel - array of size >= 3 to place the acceleration data in. The data will be in the form [x, y, z].
    • getIMUGyroRates

      public static void getIMUGyroRates(double[] rates)
      Get the angular rate about the axes of the IMU in radians per second.
      Parameters:
      rates - array of size >= 3 to place the angular rate data in. The data will be in the form [x, y, z].
    • getIMUEulerAnglesFlat

      public static void getIMUEulerAnglesFlat(double[] angles)
      Get the angle, in radians, about the axes of the IMU in the "flat" orientation.
      Parameters:
      angles - array of size >= 3 to place the angle data in. The data will be in the form [x, y, z].
    • getIMUEulerAnglesLandscape

      public static void getIMUEulerAnglesLandscape(double[] angles)
      Get the angle, in radians, about the axes of the IMU in the "landscape" orientation.
      Parameters:
      angles - array of size >= 3 to place the angle data in. The data will be in the form [x, y, z].
    • getIMUEulerAnglesPortrait

      public static void getIMUEulerAnglesPortrait(double[] angles)
      Get the angle, in radians, about the axes of the IMU in the "portrait" orientation.
      Parameters:
      angles - array of size >= 3 to place the angle data in. The data will be in the form [x, y, z].
    • getIMUQuaternion

      public static void getIMUQuaternion(double[] quat)
      Get the orientation of the IMU as a quaternion.
      Parameters:
      quat - array of size >= 4 to place the quaternion data in. The data will be in the form [w, x, y, z].
    • getIMUYawFlat

      public static double getIMUYawFlat()
      Get the yaw value, in radians, of the IMU in the "flat" orientation.
      Returns:
      flat orientation yaw
    • getIMUYawLandscape

      public static double getIMUYawLandscape()
      Get the yaw value, in radians, of the IMU in the "landscape" orientation.
      Returns:
      landscape orientation yaw
    • getIMUYawPortrait

      public static double getIMUYawPortrait()
      Get the yaw value, in radians, of the IMU in the "portrait" orientation.
      Returns:
      portrait orientation yaw