OnboardIMU

class wpilib.OnboardIMU(mountOrientation: wpilib._wpilib.OnboardIMU.MountOrientation)

Bases: pybind11_object

Systemcore onboard IMU

Constructs a handle to the Systemcore onboard IMU.

Parameters:

mountOrientation – the mount orientation of Systemcore to determine yaw.

class MountOrientation(value: SupportsInt | SupportsIndex)

Bases: pybind11_object

A mount orientation of Systemcore

Members:

FLAT : Flat (mounted parallel to the ground).

LANDSCAPE : Landscape (vertically mounted with long edge of Systemcore parallel to

the ground).

PORTRAIT : Portrait (vertically mounted with the short edge of Systemcore parallel

to the ground).

FLAT = <MountOrientation.FLAT: 0>
LANDSCAPE = <MountOrientation.LANDSCAPE: 1>
PORTRAIT = <MountOrientation.PORTRAIT: 2>
OnboardIMU.MountOrientation.name -> str
property value
getAccelX() wpimath.units.meters_per_second_squared

Get the acceleration along the X axis of the IMU.

Returns:

acceleration along the X axis

getAccelY() wpimath.units.meters_per_second_squared

Get the acceleration along the Z axis of the IMU.

Returns:

acceleration along the Z axis

getAccelZ() wpimath.units.meters_per_second_squared

Get the acceleration along the Z axis of the IMU.

Returns:

acceleration along the Z axis

getAngleX() wpimath.units.radians

Get the angle about the X axis of the IMU.

Returns:

angle about the X axis

getAngleY() wpimath.units.radians

Get the angle about the Y axis of the IMU.

Returns:

angle about the Y axis

getAngleZ() wpimath.units.radians

Get the angle about the Z axis of the IMU.

Returns:

angle about the Z axis

getGyroRateX() wpimath.units.radians_per_second

Get the angular rate about the X axis of the IMU.

Returns:

angular rate about the X axis

getGyroRateY() wpimath.units.radians_per_second

Get the angular rate about the Y axis of the IMU.

Returns:

angular rate about the Y axis

getGyroRateZ() wpimath.units.radians_per_second

Get the angular rate about the Z axis of the IMU.

Returns:

angular rate about the Z axis

getQuaternion() wpimath._wpimath.Quaternion

Get the 3D orientation as a wpi::math::Quaternion.

Returns:

3D orientation

getRotation2d() wpimath._wpimath.Rotation2d

Get the yaw as a wpi::math::Rotation2d.

Returns:

yaw

getRotation3d() wpimath._wpimath.Rotation3d

Get the 3D orientation as a wpi::math::Rotation3d.

Returns:

3D orientation

getYaw() wpimath.units.radians

Get the yaw value

Returns:

yaw value

resetYaw() None

Reset the current yaw value to 0. Future reads of the yaw value will be relative to the current orientation.