[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

@@ -10,8 +10,8 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** Represents a differential drive style drivetrain. */
@@ -31,7 +31,7 @@ public class Drivetrain {
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final PIDController m_leftPIDController = new PIDController(1, 0, 0);
private final PIDController m_rightPIDController = new PIDController(1, 0, 0);
@@ -49,7 +49,7 @@ public class Drivetrain {
* gyro.
*/
public Drivetrain() {
m_gyro.reset();
m_imu.resetYaw();
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
@@ -70,7 +70,7 @@ public class Drivetrain {
m_odometry =
new DifferentialDriveOdometry(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
m_imu.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
}
/**
@@ -103,6 +103,6 @@ public class Drivetrain {
/** Updates the field-relative position. */
public void updateOdometry() {
m_odometry.update(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
m_imu.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
}
}

View File

@@ -27,8 +27,8 @@ import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.networktables.DoubleArrayEntry;
import edu.wpi.first.networktables.DoubleArrayTopic;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
@@ -54,7 +54,7 @@ public class Drivetrain {
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final PIDController m_leftPIDController = new PIDController(1, 0, 0);
private final PIDController m_rightPIDController = new PIDController(1, 0, 0);
@@ -79,7 +79,7 @@ public class Drivetrain {
private final DifferentialDrivePoseEstimator m_poseEstimator =
new DifferentialDrivePoseEstimator(
m_kinematics,
m_gyro.getRotation2d(),
m_imu.getRotation2d(),
m_leftEncoder.getDistance(),
m_rightEncoder.getDistance(),
Pose2d.kZero,
@@ -103,7 +103,7 @@ public class Drivetrain {
* gyro.
*/
public Drivetrain(DoubleArrayTopic cameraToObjectTopic) {
m_gyro.reset();
m_imu.resetYaw();
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
@@ -220,7 +220,7 @@ public class Drivetrain {
/** Updates the field-relative position. */
public void updateOdometry() {
m_poseEstimator.update(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
m_imu.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
// Publish cameraToObject transformation to networktables --this would normally be handled by
// the
@@ -254,7 +254,8 @@ public class Drivetrain {
m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocity());
m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPosition());
m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocity());
// m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
// m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees()); // TODO(Ryan): fixup
// when sim implemented
}
/** This function is called periodically, no matter the mode. */

View File

@@ -5,8 +5,8 @@
package edu.wpi.first.wpilibj.examples.gyro;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
@@ -20,20 +20,17 @@ public class Robot extends TimedRobot {
private static final double kAngleSetpoint = 0.0;
private static final double kP = 0.005; // proportional turning constant
// gyro calibration constant, may need to be adjusted;
// gyro value of 360 is set to correspond to one full revolution
private static final double kVoltsPerDegreePerSecond = 0.0128;
private static final int kLeftMotorPort = 0;
private static final int kRightMotorPort = 1;
private static final int kGyroPort = 0;
private static final OnboardIMU.MountOrientation kIMUMountOrientation =
OnboardIMU.MountOrientation.kFlat;
private static final int kJoystickPort = 0;
private final PWMSparkMax m_leftDrive = new PWMSparkMax(kLeftMotorPort);
private final PWMSparkMax m_rightDrive = new PWMSparkMax(kRightMotorPort);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
private final OnboardIMU m_imu = new OnboardIMU(kIMUMountOrientation);
private final Joystick m_joystick = new Joystick(kJoystickPort);
/** Called once at the beginning of the robot program. */
@@ -41,7 +38,6 @@ public class Robot extends TimedRobot {
SendableRegistry.addChild(m_robotDrive, m_leftDrive);
SendableRegistry.addChild(m_robotDrive, m_rightDrive);
m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
@@ -54,7 +50,7 @@ public class Robot extends TimedRobot {
*/
@Override
public void teleopPeriodic() {
double turningValue = (kAngleSetpoint - m_gyro.getAngle()) * kP;
double turningValue = (kAngleSetpoint - m_imu.getRotation2d().getDegrees()) * kP;
m_robotDrive.arcadeDrive(-m_joystick.getY(), -turningValue);
}
}

View File

@@ -5,8 +5,8 @@
package edu.wpi.first.wpilibj.examples.gyromecanum;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.MecanumDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
@@ -16,19 +16,16 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
* in relation to the starting orientation of the robot (field-oriented controls).
*/
public class Robot extends TimedRobot {
// gyro calibration constant, may need to be adjusted;
// gyro value of 360 is set to correspond to one full revolution
private static final double kVoltsPerDegreePerSecond = 0.0128;
private static final int kFrontLeftChannel = 0;
private static final int kRearLeftChannel = 1;
private static final int kFrontRightChannel = 2;
private static final int kRearRightChannel = 3;
private static final int kGyroPort = 0;
private static final OnboardIMU.MountOrientation kIMUMountOrientation =
OnboardIMU.MountOrientation.kFlat;
private static final int kJoystickPort = 0;
private final MecanumDrive m_robotDrive;
private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
private final OnboardIMU m_imu = new OnboardIMU(kIMUMountOrientation);
private final Joystick m_joystick = new Joystick(kJoystickPort);
/** Called once at the beginning of the robot program. */
@@ -45,8 +42,6 @@ public class Robot extends TimedRobot {
m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set);
m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);
SendableRegistry.addChild(m_robotDrive, frontRight);
@@ -57,6 +52,6 @@ public class Robot extends TimedRobot {
@Override
public void teleopPeriodic() {
m_robotDrive.driveCartesian(
-m_joystick.getY(), -m_joystick.getX(), -m_joystick.getZ(), m_gyro.getRotation2d());
-m_joystick.getY(), -m_joystick.getX(), -m_joystick.getZ(), m_imu.getRotation2d());
}
}

View File

@@ -12,8 +12,8 @@ import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** Represents a mecanum drive style drivetrain. */
@@ -41,21 +41,21 @@ public class Drivetrain {
private final PIDController m_backLeftPIDController = new PIDController(1, 0, 0);
private final PIDController m_backRightPIDController = new PIDController(1, 0, 0);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final MecanumDriveKinematics m_kinematics =
new MecanumDriveKinematics(
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation);
private final MecanumDriveOdometry m_odometry =
new MecanumDriveOdometry(m_kinematics, m_gyro.getRotation2d(), getCurrentDistances());
new MecanumDriveOdometry(m_kinematics, m_imu.getRotation2d(), getCurrentDistances());
// Gains are for example purposes only - must be determined for your own robot!
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
/** Constructs a MecanumDrive and resets the gyro. */
public Drivetrain() {
m_gyro.reset();
m_imu.resetYaw();
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
@@ -127,13 +127,13 @@ public class Drivetrain {
double xSpeed, double ySpeed, double rot, boolean fieldRelative, double period) {
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
if (fieldRelative) {
chassisSpeeds = chassisSpeeds.toRobotRelative(m_gyro.getRotation2d());
chassisSpeeds = chassisSpeeds.toRobotRelative(m_imu.getRotation2d());
}
setSpeeds(m_kinematics.toWheelSpeeds(chassisSpeeds.discretize(period)).desaturate(kMaxSpeed));
}
/** Updates the field relative position of the robot. */
public void updateOdometry() {
m_odometry.update(m_gyro.getRotation2d(), getCurrentDistances());
m_odometry.update(m_imu.getRotation2d(), getCurrentDistances());
}
}

View File

@@ -15,8 +15,8 @@ import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
@@ -45,7 +45,7 @@ public class Drivetrain {
private final PIDController m_backLeftPIDController = new PIDController(1, 0, 0);
private final PIDController m_backRightPIDController = new PIDController(1, 0, 0);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final MecanumDriveKinematics m_kinematics =
new MecanumDriveKinematics(
@@ -56,7 +56,7 @@ public class Drivetrain {
private final MecanumDrivePoseEstimator m_poseEstimator =
new MecanumDrivePoseEstimator(
m_kinematics,
m_gyro.getRotation2d(),
m_imu.getRotation2d(),
getCurrentDistances(),
Pose2d.kZero,
VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)),
@@ -67,7 +67,7 @@ public class Drivetrain {
/** Constructs a MecanumDrive and resets the gyro. */
public Drivetrain() {
m_gyro.reset();
m_imu.resetYaw();
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
@@ -147,7 +147,7 @@ public class Drivetrain {
/** Updates the field relative position of the robot. */
public void updateOdometry() {
m_poseEstimator.update(m_gyro.getRotation2d(), getCurrentDistances());
m_poseEstimator.update(m_imu.getRotation2d(), getCurrentDistances());
// Also apply vision measurements. We use 0.3 seconds in the past as an example -- on
// a real robot, this must be calculated based either on latency or timestamps.

View File

@@ -10,8 +10,8 @@ import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConstants;
@@ -49,7 +49,7 @@ public class Drive extends SubsystemBase {
DriveConstants.kRightEncoderPorts[1],
DriveConstants.kRightEncoderReversed);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final ProfiledPIDController m_controller =
new ProfiledPIDController(
DriveConstants.kTurnP,
@@ -129,11 +129,11 @@ public class Drive extends SubsystemBase {
*/
public Command turnToAngleCommand(double angleDeg) {
return startRun(
() -> m_controller.reset(m_gyro.getRotation2d().getDegrees()),
() -> m_controller.reset(m_imu.getRotation2d().getDegrees()),
() ->
m_drive.arcadeDrive(
0,
m_controller.calculate(m_gyro.getRotation2d().getDegrees(), angleDeg)
m_controller.calculate(m_imu.getRotation2d().getDegrees(), angleDeg)
// Divide feedforward voltage by battery voltage to normalize it to [-1, 1]
+ m_feedforward.calculate(m_controller.getSetpoint().velocity)
/ RobotController.getBatteryVoltage()))

View File

@@ -15,8 +15,8 @@ import edu.wpi.first.math.numbers.N2;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
@@ -45,13 +45,13 @@ public class Drivetrain {
private final PIDController m_leftPIDController = new PIDController(8.5, 0, 0);
private final PIDController m_rightPIDController = new PIDController(8.5, 0, 0);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final DifferentialDriveKinematics m_kinematics =
new DifferentialDriveKinematics(kTrackwidth);
private final DifferentialDriveOdometry m_odometry =
new DifferentialDriveOdometry(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
m_imu.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
// Gains are for example purposes only - must be determined for your own
// robot!
@@ -114,14 +114,14 @@ public class Drivetrain {
/** Update robot odometry. */
public void updateOdometry() {
m_odometry.update(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
m_imu.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
}
/** Resets robot odometry. */
public void resetOdometry(Pose2d pose) {
m_drivetrainSimulator.setPose(pose);
m_odometry.resetPosition(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), pose);
m_imu.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), pose);
}
/** Check the current robot pose. */

View File

@@ -9,7 +9,7 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.OnboardIMU;
/** Represents a swerve drive style drivetrain. */
public class Drivetrain {
@@ -26,7 +26,7 @@ public class Drivetrain {
private final SwerveModule m_backLeft = new SwerveModule(5, 6, 8, 9, 10, 11);
private final SwerveModule m_backRight = new SwerveModule(7, 8, 12, 13, 14, 15);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final SwerveDriveKinematics m_kinematics =
new SwerveDriveKinematics(
@@ -35,7 +35,7 @@ public class Drivetrain {
private final SwerveDriveOdometry m_odometry =
new SwerveDriveOdometry(
m_kinematics,
m_gyro.getRotation2d(),
m_imu.getRotation2d(),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
@@ -44,7 +44,7 @@ public class Drivetrain {
});
public Drivetrain() {
m_gyro.reset();
m_imu.resetYaw();
}
/**
@@ -59,7 +59,7 @@ public class Drivetrain {
double xSpeed, double ySpeed, double rot, boolean fieldRelative, double period) {
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
if (fieldRelative) {
chassisSpeeds = chassisSpeeds.toRobotRelative(m_gyro.getRotation2d());
chassisSpeeds = chassisSpeeds.toRobotRelative(m_imu.getRotation2d());
}
chassisSpeeds = chassisSpeeds.discretize(period);
@@ -75,7 +75,7 @@ public class Drivetrain {
/** Updates the field relative position of the robot. */
public void updateOdometry() {
m_odometry.update(
m_gyro.getRotation2d(),
m_imu.getRotation2d(),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),

View File

@@ -12,7 +12,7 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.OnboardIMU;
import edu.wpi.first.wpilibj.Timer;
/** Represents a swerve drive style drivetrain. */
@@ -30,7 +30,7 @@ public class Drivetrain {
private final SwerveModule m_backLeft = new SwerveModule(5, 6, 8, 9, 10, 11);
private final SwerveModule m_backRight = new SwerveModule(7, 8, 12, 13, 14, 15);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final OnboardIMU m_imu = new OnboardIMU(OnboardIMU.MountOrientation.kFlat);
private final SwerveDriveKinematics m_kinematics =
new SwerveDriveKinematics(
@@ -41,7 +41,7 @@ public class Drivetrain {
private final SwerveDrivePoseEstimator m_poseEstimator =
new SwerveDrivePoseEstimator(
m_kinematics,
m_gyro.getRotation2d(),
m_imu.getRotation2d(),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
@@ -53,7 +53,7 @@ public class Drivetrain {
VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));
public Drivetrain() {
m_gyro.reset();
m_imu.resetYaw();
}
/**
@@ -86,7 +86,7 @@ public class Drivetrain {
/** Updates the field relative position of the robot. */
public void updateOdometry() {
m_poseEstimator.update(
m_gyro.getRotation2d(),
m_imu.getRotation2d(),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),