Package edu.wpi.first.hal
Class IMUJNI
java.lang.Object
edu.wpi.first.hal.JNIWrapper
edu.wpi.first.hal.IMUJNI
IMU Functions.
- See Also:
-
- "hal/IMU.h"
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.hal.JNIWrapper
JNIWrapper.Helper
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionstatic void
getIMUAcceleration
(double[] accel) Get the acceleration along the axes of the IMU in meters per second squared.static void
getIMUEulerAnglesFlat
(double[] angles) Get the angle, in radians, about the axes of the IMU in the "flat" orientation.static void
getIMUEulerAnglesLandscape
(double[] angles) Get the angle, in radians, about the axes of the IMU in the "landscape" orientation.static void
getIMUEulerAnglesPortrait
(double[] angles) Get the angle, in radians, about the axes of the IMU in the "portrait" orientation.static void
getIMUGyroRates
(double[] rates) Get the angular rate about the axes of the IMU in radians per second.static void
getIMUQuaternion
(double[] quat) Get the orientation of the IMU as a quaternion.static double
Get the yaw value, in radians, of the IMU in the "flat" orientation.static double
Get the yaw value, in radians, of the IMU in the "landscape" orientation.static double
Get the yaw value, in radians, of the IMU in the "portrait" orientation.Methods inherited from class edu.wpi.first.hal.JNIWrapper
forceLoad, suppressUnused
-
Constructor Details
-
IMUJNI
public IMUJNI()
-
-
Method Details
-
getIMUAcceleration
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
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
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
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
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
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
Get the yaw value, in radians, of the IMU in the "flat" orientation.- Returns:
- flat orientation yaw
-
getIMUYawLandscape
Get the yaw value, in radians, of the IMU in the "landscape" orientation.- Returns:
- landscape orientation yaw
-
getIMUYawPortrait
Get the yaw value, in radians, of the IMU in the "portrait" orientation.- Returns:
- portrait orientation yaw
-