WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
OnboardIMU.hpp
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
9#include "wpi/units/acceleration.hpp"
10#include "wpi/units/angle.hpp"
11#include "wpi/units/angular_velocity.hpp"
12
13namespace wpi {
14
15/**
16 * Systemcore onboard IMU
17 */
19 public:
20 /**
21 * A mount orientation of Systemcore
22 */
24 /** Flat (mounted parallel to the ground). */
26 /** Landscape (vertically mounted with long edge of Systemcore parallel to
27 the ground). */
29 /** Portrait (vertically mounted with the short edge of Systemcore parallel
30 to the ground). */
32 };
33
34 /**
35 * Constructs a handle to the Systemcore onboard IMU.
36 * @param mountOrientation the mount orientation of Systemcore to determine
37 * yaw.
38 */
39 explicit OnboardIMU(MountOrientation mountOrientation);
40
41 /**
42 * Get the yaw value
43 * @return yaw value
44 */
45 wpi::units::radian_t GetYaw();
46
47 /**
48 * Reset the current yaw value to 0. Future reads of the yaw value will be
49 * relative to the current orientation.
50 */
51 void ResetYaw();
52
53 /**
54 * Get the yaw as a wpi::math::Rotation2d.
55 * @return yaw
56 */
58
59 /**
60 * Get the 3D orientation as a wpi::math::Rotation3d.
61 * @return 3D orientation
62 */
64
65 /**
66 * Get the 3D orientation as a wpi::math::Quaternion.
67 * @return 3D orientation
68 */
70
71 /**
72 * Get the angle about the X axis of the IMU.
73 * @return angle about the X axis
74 */
75 wpi::units::radian_t GetAngleX();
76
77 /**
78 * Get the angle about the Y axis of the IMU.
79 * @return angle about the Y axis
80 */
81 wpi::units::radian_t GetAngleY();
82
83 /**
84 * Get the angle about the Z axis of the IMU.
85 * @return angle about the Z axis
86 */
87 wpi::units::radian_t GetAngleZ();
88
89 /**
90 * Get the angular rate about the X axis of the IMU.
91 * @return angular rate about the X axis
92 */
93 wpi::units::radians_per_second_t GetGyroRateX();
94
95 /**
96 * Get the angular rate about the Y axis of the IMU.
97 * @return angular rate about the Y axis
98 */
99 wpi::units::radians_per_second_t GetGyroRateY();
100
101 /**
102 * Get the angular rate about the Z axis of the IMU.
103 * @return angular rate about the Z axis
104 */
105 wpi::units::radians_per_second_t GetGyroRateZ();
106
107 /**
108 * Get the acceleration along the X axis of the IMU.
109 * @return acceleration along the X axis
110 */
111 wpi::units::meters_per_second_squared_t GetAccelX();
112
113 /**
114 * Get the acceleration along the Z axis of the IMU.
115 * @return acceleration along the Z axis
116 */
117 wpi::units::meters_per_second_squared_t GetAccelY();
118
119 /**
120 * Get the acceleration along the Z axis of the IMU.
121 * @return acceleration along the Z axis
122 */
123 wpi::units::meters_per_second_squared_t GetAccelZ();
124
125 private:
126 wpi::units::radian_t GetYawNoOffset();
127 MountOrientation m_mountOrientation;
128 wpi::units::radian_t m_yawOffset{0};
129};
130} // namespace wpi
wpi::units::radian_t GetYaw()
Get the yaw value.
void ResetYaw()
Reset the current yaw value to 0.
wpi::math::Quaternion GetQuaternion()
Get the 3D orientation as a wpi::math::Quaternion.
OnboardIMU(MountOrientation mountOrientation)
Constructs a handle to the Systemcore onboard IMU.
wpi::units::radians_per_second_t GetGyroRateX()
Get the angular rate about the X axis of the IMU.
wpi::units::radian_t GetAngleZ()
Get the angle about the Z axis of the IMU.
MountOrientation
A mount orientation of Systemcore.
Definition OnboardIMU.hpp:23
@ kPortrait
Portrait (vertically mounted with the short edge of Systemcore parallel to the ground).
Definition OnboardIMU.hpp:31
@ kFlat
Flat (mounted parallel to the ground).
Definition OnboardIMU.hpp:25
@ kLandscape
Landscape (vertically mounted with long edge of Systemcore parallel to the ground).
Definition OnboardIMU.hpp:28
wpi::units::radian_t GetAngleY()
Get the angle about the Y axis of the IMU.
wpi::units::meters_per_second_squared_t GetAccelY()
Get the acceleration along the Z axis of the IMU.
wpi::math::Rotation2d GetRotation2d()
Get the yaw as a wpi::math::Rotation2d.
wpi::units::radian_t GetAngleX()
Get the angle about the X 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::radians_per_second_t GetGyroRateY()
Get the angular rate about the Y axis of the IMU.
wpi::units::meters_per_second_squared_t GetAccelZ()
Get the acceleration along the Z axis of the IMU.
wpi::math::Rotation3d GetRotation3d()
Get the 3D orientation as a wpi::math::Rotation3d.
Represents a quaternion.
Definition Quaternion.hpp:20
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
Definition CvSource.hpp:15