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