WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
frc::OnboardIMU Class Reference

SystemCore onboard IMU. More...

#include <frc/OnboardIMU.h>

Public Types

enum  MountOrientation { kFlat , kLandscape , kPortrait }
 A mount orientation of SystemCore. More...
 

Public Member Functions

 OnboardIMU (MountOrientation mountOrientation)
 Constructs a handle to the SystemCore onboard IMU.
 
units::radian_t GetYaw ()
 Get the yaw value.
 
void ResetYaw ()
 Reset the current yaw value to 0.
 
Rotation2d GetRotation2d ()
 Get the yaw as a Rotation2d.
 
Rotation3d GetRotation3d ()
 Get the 3D orientation as a Rotation3d.
 
Quaternion GetQuaternion ()
 Get the 3D orientation as a Quaternion.
 
units::radian_t GetAngleX ()
 Get the angle about the X axis of the IMU.
 
units::radian_t GetAngleY ()
 Get the angle about the Y axis of the IMU.
 
units::radian_t GetAngleZ ()
 Get the angle about the Z axis of the IMU.
 
units::radians_per_second_t GetGyroRateX ()
 Get the angular rate about the X axis of the IMU.
 
units::radians_per_second_t GetGyroRateY ()
 Get the angular rate about the Y axis of the IMU.
 
units::radians_per_second_t GetGyroRateZ ()
 Get the angular rate about the Z axis of the IMU.
 
units::meters_per_second_squared_t GetAccelX ()
 Get the acceleration along the X axis of the IMU.
 
units::meters_per_second_squared_t GetAccelY ()
 Get the acceleration along the Z axis of the IMU.
 
units::meters_per_second_squared_t GetAccelZ ()
 Get the acceleration along the Z axis of the IMU.
 

Detailed Description

SystemCore onboard IMU.

Member Enumeration Documentation

◆ MountOrientation

A mount orientation of SystemCore.

Enumerator
kFlat 

Flat (mounted parallel to the ground).

kLandscape 

Landscape (vertically mounted with long edge of SystemCore parallel to the ground).

kPortrait 

Portrait (vertically mounted with the short edge of SystemCore parallel to the ground).

Constructor & Destructor Documentation

◆ OnboardIMU()

frc::OnboardIMU::OnboardIMU ( MountOrientation mountOrientation)
explicit

Constructs a handle to the SystemCore onboard IMU.

Parameters
mountOrientationthe mount orientation of SystemCore to determine yaw.

Member Function Documentation

◆ GetAccelX()

units::meters_per_second_squared_t frc::OnboardIMU::GetAccelX ( )

Get the acceleration along the X axis of the IMU.

Returns
acceleration along the X axis

◆ GetAccelY()

units::meters_per_second_squared_t frc::OnboardIMU::GetAccelY ( )

Get the acceleration along the Z axis of the IMU.

Returns
acceleration along the Z axis

◆ GetAccelZ()

units::meters_per_second_squared_t frc::OnboardIMU::GetAccelZ ( )

Get the acceleration along the Z axis of the IMU.

Returns
acceleration along the Z axis

◆ GetAngleX()

units::radian_t frc::OnboardIMU::GetAngleX ( )

Get the angle about the X axis of the IMU.

Returns
angle about the X axis

◆ GetAngleY()

units::radian_t frc::OnboardIMU::GetAngleY ( )

Get the angle about the Y axis of the IMU.

Returns
angle about the Y axis

◆ GetAngleZ()

units::radian_t frc::OnboardIMU::GetAngleZ ( )

Get the angle about the Z axis of the IMU.

Returns
angle about the Z axis

◆ GetGyroRateX()

units::radians_per_second_t frc::OnboardIMU::GetGyroRateX ( )

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

Returns
angular rate about the X axis

◆ GetGyroRateY()

units::radians_per_second_t frc::OnboardIMU::GetGyroRateY ( )

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

Returns
angular rate about the Y axis

◆ GetGyroRateZ()

units::radians_per_second_t frc::OnboardIMU::GetGyroRateZ ( )

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

Returns
angular rate about the Z axis

◆ GetQuaternion()

Quaternion frc::OnboardIMU::GetQuaternion ( )

Get the 3D orientation as a Quaternion.

Returns
3D orientation

◆ GetRotation2d()

Rotation2d frc::OnboardIMU::GetRotation2d ( )

Get the yaw as a Rotation2d.

Returns
yaw

◆ GetRotation3d()

Rotation3d frc::OnboardIMU::GetRotation3d ( )

Get the 3D orientation as a Rotation3d.

Returns
3D orientation

◆ GetYaw()

units::radian_t frc::OnboardIMU::GetYaw ( )

Get the yaw value.

Returns
yaw value

◆ ResetYaw()

void frc::OnboardIMU::ResetYaw ( )

Reset the current yaw value to 0.

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


The documentation for this class was generated from the following file: