Package edu.wpi.first.wpilibj
Class OnboardIMU
java.lang.Object
edu.wpi.first.wpilibj.OnboardIMU
SystemCore onboard IMU.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic enum
A mount orientation of SystemCore. -
Constructor Summary
ConstructorsConstructorDescriptionOnboardIMU
(OnboardIMU.MountOrientation mountOrientation) Constructs a handle to the SystemCore onboard IMU. -
Method Summary
Modifier and TypeMethodDescriptiondouble
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
resetYaw()
Reset the current yaw value to 0.
-
Constructor Details
-
OnboardIMU
Constructs a handle to the SystemCore onboard IMU.- Parameters:
mountOrientation
- the mount orientation of SystemCore to determine yaw.
-
-
Method Details
-
getYawRadians
Get the yaw value in radians.- Returns:
- yaw value in radians
-
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
Get the angle about the X axis of the IMU in radians.- Returns:
- angle about the X axis in radians
-
getAngleY
Get the angle about the Y axis of the IMU in radians.- Returns:
- angle about the Y axis in radians
-
getAngleZ
Get the angle about the Z axis of the IMU in radians.- Returns:
- angle about the Z axis in radians
-
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
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
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
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
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
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
-