[hal, wpilib] Remove analog accumulator and analog gyro (#7697)

The 2 high level classes were temporarily kept to keep the examples compiling. We will remove those when we have the interface into the built in IMU.
This commit is contained in:
Thad House
2025-01-17 12:58:31 -08:00
committed by GitHub
parent 92f0a3c961
commit f80874dd4b
76 changed files with 33 additions and 3886 deletions

View File

@@ -32,7 +32,6 @@ import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.AnalogGyroSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
@@ -91,7 +90,6 @@ public class Drivetrain {
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
// Simulation classes
private final AnalogGyroSim m_gyroSim = new AnalogGyroSim(m_gyro);
private final EncoderSim m_leftEncoderSim = new EncoderSim(m_leftEncoder);
private final EncoderSim m_rightEncoderSim = new EncoderSim(m_rightEncoder);
private final LinearSystem<N2, N2, N2> m_drivetrainSystem =
@@ -257,7 +255,7 @@ public class Drivetrain {
m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocityMetersPerSecond());
m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPositionMeters());
m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocityMetersPerSecond());
m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
// m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
}
/** This function is called periodically, no matter the mode. */

View File

@@ -19,7 +19,6 @@ import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.AnalogGyroSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
@@ -59,7 +58,6 @@ public class Drivetrain {
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
// Simulation classes help us simulate our robot
private final AnalogGyroSim m_gyroSim = new AnalogGyroSim(m_gyro);
private final EncoderSim m_leftEncoderSim = new EncoderSim(m_leftEncoder);
private final EncoderSim m_rightEncoderSim = new EncoderSim(m_rightEncoder);
private final Field2d m_fieldSim = new Field2d();
@@ -148,7 +146,7 @@ public class Drivetrain {
m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocityMetersPerSecond());
m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPositionMeters());
m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocityMetersPerSecond());
m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
// m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
}
/** Update odometry - this should be run every robot loop. */