[wpimath] Improve SimpleMotorFeedforward argument names and deprecation message (#7489)

Also roll back SimpleMotorFeedforward unit API until 2027.
This commit is contained in:
Tyler Veness
2024-12-06 22:32:40 -08:00
committed by GitHub
parent 1921d019b7
commit 882233bede
22 changed files with 91 additions and 233 deletions

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.differentialdrivebot;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
@@ -82,10 +79,8 @@ public class Drivetrain {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(DifferentialDriveWheelSpeeds speeds) {
final double leftFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.leftMetersPerSecond)).in(Volts);
final double rightFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.rightMetersPerSecond)).in(Volts);
final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
final double leftOutput =
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.ComputerVisionUtil;
@@ -142,10 +139,8 @@ public class Drivetrain {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(DifferentialDriveWheelSpeeds speeds) {
final double leftFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.leftMetersPerSecond)).in(Volts);
final double rightFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.rightMetersPerSecond)).in(Volts);
final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
final double leftOutput =
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
@@ -99,18 +96,12 @@ public class DriveSubsystem extends SubsystemBase {
m_leftLeader.setSetpoint(
ExampleSmartMotorController.PIDMode.kPosition,
currentLeft.position,
m_feedforward
.calculate(
MetersPerSecond.of(currentLeft.velocity), MetersPerSecond.of(nextLeft.velocity))
.in(Volts)
m_feedforward.calculateWithVelocities(currentLeft.velocity, nextLeft.velocity)
/ RobotController.getBatteryVoltage());
m_rightLeader.setSetpoint(
ExampleSmartMotorController.PIDMode.kPosition,
currentRight.position,
m_feedforward
.calculate(
MetersPerSecond.of(currentLeft.velocity), MetersPerSecond.of(nextLeft.velocity))
.in(Volts)
m_feedforward.calculateWithVelocities(currentLeft.velocity, nextLeft.velocity)
/ RobotController.getBatteryVoltage());
}

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.elevatorexponentialprofile;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.ExponentialProfile;
import edu.wpi.first.wpilibj.Joystick;
@@ -48,7 +45,7 @@ public class Robot extends TimedRobot {
m_motor.setSetpoint(
ExampleSmartMotorController.PIDMode.kPosition,
m_setpoint.position,
m_feedforward.calculate(RadiansPerSecond.of(next.velocity)).in(Volts) / 12.0);
m_feedforward.calculate(next.velocity) / 12.0);
m_setpoint = next;
}

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Joystick;
@@ -48,6 +45,6 @@ public class Robot extends TimedRobot {
m_motor.setSetpoint(
ExampleSmartMotorController.PIDMode.kPosition,
m_setpoint.position,
m_feedforward.calculate(MetersPerSecond.of(m_setpoint.velocity)).in(Volts) / 12.0);
m_feedforward.calculate(m_setpoint.velocity) / 12.0);
}
}

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.eventloop;
import static edu.wpi.first.units.Units.RPM;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.Encoder;
@@ -67,7 +64,7 @@ public class Robot extends TimedRobot {
() -> {
m_shooter.setVoltage(
m_controller.calculate(m_shooterEncoder.getRate(), SHOT_VELOCITY)
+ m_ff.calculate(RPM.of(SHOT_VELOCITY)).in(Volts));
+ m_ff.calculate(SHOT_VELOCITY));
});
// if not, stop

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.flywheelbangbangcontroller;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.BangBangController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.numbers.N1;
@@ -89,8 +86,7 @@ public class Robot extends TimedRobot {
// Controls a motor with the output of the BangBang controller and a
// feedforward. The feedforward is reduced slightly to avoid overspeeding
// the shooter.
m_flywheelMotor.setVoltage(
bangOutput + 0.9 * m_feedforward.calculate(RadiansPerSecond.of(setpoint)).in(Volts));
m_flywheelMotor.setVoltage(bangOutput + 0.9 * m_feedforward.calculate(setpoint));
}
/** Update our simulation. This should be run every robot loop in simulation. */

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.mecanumbot;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Translation2d;
@@ -98,14 +95,10 @@ public class Drivetrain {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(MecanumDriveWheelSpeeds speeds) {
final double frontLeftFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.frontLeftMetersPerSecond)).in(Volts);
final double frontRightFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.frontRightMetersPerSecond)).in(Volts);
final double backLeftFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.rearLeftMetersPerSecond)).in(Volts);
final double backRightFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.rearRightMetersPerSecond)).in(Volts);
final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeftMetersPerSecond);
final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRightMetersPerSecond);
final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeftMetersPerSecond);
final double backRightFeedforward = m_feedforward.calculate(speeds.rearRightMetersPerSecond);
final double frontLeftOutput =
m_frontLeftPIDController.calculate(

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.mecanumdriveposeestimator;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
@@ -110,14 +107,10 @@ public class Drivetrain {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(MecanumDriveWheelSpeeds speeds) {
final double frontLeftFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.frontLeftMetersPerSecond)).in(Volts);
final double frontRightFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.frontRightMetersPerSecond)).in(Volts);
final double backLeftFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.rearLeftMetersPerSecond)).in(Volts);
final double backRightFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.rearRightMetersPerSecond)).in(Volts);
final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeftMetersPerSecond);
final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRightMetersPerSecond);
final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeftMetersPerSecond);
final double backRightFeedforward = m_feedforward.calculate(speeds.rearRightMetersPerSecond);
final double frontLeftOutput =
m_frontLeftPIDController.calculate(

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
import static edu.wpi.first.units.Units.DegreesPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.epilogue.Logged;
import edu.wpi.first.epilogue.NotLogged;
import edu.wpi.first.math.controller.ProfiledPIDController;
@@ -143,9 +140,7 @@ public class Drive extends SubsystemBase {
0,
m_controller.calculate(m_gyro.getRotation2d().getDegrees(), angleDeg)
// Divide feedforward voltage by battery voltage to normalize it to [-1, 1]
+ m_feedforward
.calculate(DegreesPerSecond.of(m_controller.getSetpoint().velocity))
.in(Volts)
+ m_feedforward.calculate(m_controller.getSetpoint().velocity)
/ RobotController.getBatteryVoltage()))
.until(m_controller::atGoal)
.finallyDo(() -> m_drive.arcadeDrive(0, 0));

View File

@@ -4,8 +4,6 @@
package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.wpilibj2.command.Commands.parallel;
import static edu.wpi.first.wpilibj2.command.Commands.waitUntil;
@@ -60,9 +58,7 @@ public class Shooter extends SubsystemBase {
run(
() -> {
m_shooterMotor.set(
m_shooterFeedforward
.calculate(RotationsPerSecond.of(setpointRotationsPerSecond))
.in(Volts)
m_shooterFeedforward.calculate(setpointRotationsPerSecond)
+ m_shooterFeedback.calculate(
m_shooterEncoder.getRate(), setpointRotationsPerSecond));
}),

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.simpledifferentialdrivesimulation;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
@@ -97,10 +94,8 @@ public class Drivetrain {
/** Sets speeds to the drivetrain motors. */
public void setSpeeds(DifferentialDriveWheelSpeeds speeds) {
final double leftFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.leftMetersPerSecond)).in(Volts);
final double rightFeedforward =
m_feedforward.calculate(MetersPerSecond.of(speeds.rightMetersPerSecond)).in(Volts);
final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
double leftOutput =
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
double rightOutput =

View File

@@ -4,10 +4,6 @@
package edu.wpi.first.wpilibj.examples.swervebot;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
@@ -127,10 +123,7 @@ public class SwerveModule {
final double driveOutput =
m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
final double driveFeedforward =
m_driveFeedforward
.calculate(MetersPerSecond.of(desiredState.speedMetersPerSecond))
.in(Volts);
final double driveFeedforward = m_driveFeedforward.calculate(desiredState.speedMetersPerSecond);
// Calculate the turning motor output from the turning PID controller.
final double turnOutput =
@@ -138,9 +131,7 @@ public class SwerveModule {
m_turningEncoder.getDistance(), desiredState.angle.getRadians());
final double turnFeedforward =
m_turnFeedforward
.calculate(RadiansPerSecond.of(m_turningPIDController.getSetpoint().velocity))
.in(Volts);
m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity);
m_driveMotor.setVoltage(driveOutput + driveFeedforward);
m_turningMotor.setVoltage(turnOutput + turnFeedforward);

View File

@@ -4,10 +4,6 @@
package edu.wpi.first.wpilibj.examples.swervedriveposeestimator;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
@@ -126,10 +122,7 @@ public class SwerveModule {
final double driveOutput =
m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
final double driveFeedforward =
m_driveFeedforward
.calculate(MetersPerSecond.of(desiredState.speedMetersPerSecond))
.in(Volts);
final double driveFeedforward = m_driveFeedforward.calculate(desiredState.speedMetersPerSecond);
// Calculate the turning motor output from the turning PID controller.
final double turnOutput =
@@ -137,9 +130,7 @@ public class SwerveModule {
m_turningEncoder.getDistance(), desiredState.angle.getRadians());
final double turnFeedforward =
m_turnFeedforward
.calculate(RadiansPerSecond.of(m_turningPIDController.getSetpoint().velocity))
.in(Volts);
m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity);
m_driveMotor.setVoltage(driveOutput + driveFeedforward);
m_turningMotor.setVoltage(turnOutput + turnFeedforward);

View File

@@ -95,9 +95,7 @@ public class Shooter extends SubsystemBase {
return run(() -> {
m_shooterMotor.setVoltage(
m_shooterFeedback.calculate(m_shooterEncoder.getRate(), shooterSpeed.getAsDouble())
+ m_shooterFeedforward
.calculate(RotationsPerSecond.of(shooterSpeed.getAsDouble()))
.in(Volts));
+ m_shooterFeedforward.calculate(shooterSpeed.getAsDouble()));
m_feederMotor.set(ShooterConstants.kFeederSpeed);
})
.finallyDo(