[wpilib, examples] Remove AnalogGyro (#8205)

This commit is contained in:
Ryan Blue
2025-10-10 15:44:39 -04:00
committed by GitHub
parent 35e4a18e86
commit 33f91589b4
30 changed files with 109 additions and 563 deletions

View File

@@ -15,7 +15,7 @@ Drivetrain::Drivetrain() {
// gearbox is constructed, you might have to invert the left side instead.
m_rightLeader.SetInverted(true);
m_gyro.Reset();
m_imu.ResetYaw();
// Set the distance per pulse for the drive encoders. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
@@ -84,7 +84,7 @@ frc::Pose3d Drivetrain::ObjectToRobotPose(
}
void Drivetrain::UpdateOdometry() {
m_poseEstimator.Update(m_gyro.GetRotation2d(),
m_poseEstimator.Update(m_imu.GetRotation2d(),
units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()});
@@ -125,6 +125,7 @@ void Drivetrain::SimulationPeriodic() {
m_drivetrainSimulator.GetRightPosition().value());
m_rightEncoderSim.SetRate(m_drivetrainSimulator.GetRightVelocity().value());
// m_gyroSim.SetAngle(-m_drivetrainSimulator.GetHeading().Degrees().value());
// // TODO(Ryan): fixup when sim implemented
}
void Drivetrain::Periodic() {

View File

@@ -6,9 +6,9 @@
#include <numbers>
#include <frc/AnalogGyro.h>
#include <frc/ComputerVisionUtil.h>
#include <frc/Encoder.h>
#include <frc/OnboardIMU.h>
#include <frc/RobotController.h>
#include <frc/Timer.h>
#include <frc/apriltag/AprilTagFieldLayout.h>
@@ -144,7 +144,7 @@ class Drivetrain {
frc::PIDController m_leftPIDController{1.0, 0.0, 0.0};
frc::PIDController m_rightPIDController{1.0, 0.0, 0.0};
frc::AnalogGyro m_gyro{0};
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
@@ -152,7 +152,7 @@ class Drivetrain {
// robot!
frc::DifferentialDrivePoseEstimator m_poseEstimator{
m_kinematics,
m_gyro.GetRotation2d(),
m_imu.GetRotation2d(),
units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()},
frc::Pose2d{},