![]() |
WPILibC++ 2027.0.0-alpha-4
|
Systemcore onboard IMU. More...
#include <wpi/hardware/imu/OnboardIMU.hpp>
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. | |
| wpi::units::radian_t | GetYaw () |
| Get the yaw value. | |
| void | ResetYaw () |
| Reset the current yaw value to 0. | |
| wpi::math::Rotation2d | GetRotation2d () |
| Get the yaw as a wpi::math::Rotation2d. | |
| wpi::math::Rotation3d | GetRotation3d () |
| Get the 3D orientation as a wpi::math::Rotation3d. | |
| wpi::math::Quaternion | GetQuaternion () |
| Get the 3D orientation as a wpi::math::Quaternion. | |
| wpi::units::radian_t | GetAngleX () |
| Get the angle about the X axis of the IMU. | |
| wpi::units::radian_t | GetAngleY () |
| Get the angle about the Y axis of the IMU. | |
| wpi::units::radian_t | GetAngleZ () |
| Get the angle about the Z axis of the IMU. | |
| wpi::units::radians_per_second_t | GetGyroRateX () |
| Get the angular rate about the X axis of the IMU. | |
| wpi::units::radians_per_second_t | GetGyroRateY () |
| Get the angular rate about the Y axis of the IMU. | |
| wpi::units::radians_per_second_t | GetGyroRateZ () |
| Get the angular rate about the Z axis of the IMU. | |
| wpi::units::meters_per_second_squared_t | GetAccelX () |
| Get the acceleration along the X axis of the IMU. | |
| wpi::units::meters_per_second_squared_t | GetAccelY () |
| Get the acceleration along the Z axis of the IMU. | |
| wpi::units::meters_per_second_squared_t | GetAccelZ () |
| Get the acceleration along the Z axis of the IMU. | |
Systemcore onboard IMU.
|
explicit |
Constructs a handle to the Systemcore onboard IMU.
| mountOrientation | the mount orientation of Systemcore to determine yaw. |
| wpi::units::meters_per_second_squared_t wpi::OnboardIMU::GetAccelX | ( | ) |
Get the acceleration along the X axis of the IMU.
| wpi::units::meters_per_second_squared_t wpi::OnboardIMU::GetAccelY | ( | ) |
Get the acceleration along the Z axis of the IMU.
| wpi::units::meters_per_second_squared_t wpi::OnboardIMU::GetAccelZ | ( | ) |
Get the acceleration along the Z axis of the IMU.
| wpi::units::radian_t wpi::OnboardIMU::GetAngleX | ( | ) |
Get the angle about the X axis of the IMU.
| wpi::units::radian_t wpi::OnboardIMU::GetAngleY | ( | ) |
Get the angle about the Y axis of the IMU.
| wpi::units::radian_t wpi::OnboardIMU::GetAngleZ | ( | ) |
Get the angle about the Z axis of the IMU.
| wpi::units::radians_per_second_t wpi::OnboardIMU::GetGyroRateX | ( | ) |
Get the angular rate about the X axis of the IMU.
| wpi::units::radians_per_second_t wpi::OnboardIMU::GetGyroRateY | ( | ) |
Get the angular rate about the Y axis of the IMU.
| wpi::units::radians_per_second_t wpi::OnboardIMU::GetGyroRateZ | ( | ) |
Get the angular rate about the Z axis of the IMU.
| wpi::math::Quaternion wpi::OnboardIMU::GetQuaternion | ( | ) |
Get the 3D orientation as a wpi::math::Quaternion.
| wpi::math::Rotation2d wpi::OnboardIMU::GetRotation2d | ( | ) |
Get the yaw as a wpi::math::Rotation2d.
| wpi::math::Rotation3d wpi::OnboardIMU::GetRotation3d | ( | ) |
Get the 3D orientation as a wpi::math::Rotation3d.
| wpi::units::radian_t wpi::OnboardIMU::GetYaw | ( | ) |
Get the yaw value.
| void wpi::OnboardIMU::ResetYaw | ( | ) |
Reset the current yaw value to 0.
Future reads of the yaw value will be relative to the current orientation.