Add setVoltage method to SpeedController (#1997)

Add a voltage-compensated setVoltage method to SpeedController, which is sorely needed to help teams use feedforward-based controls effectively. Also uses correct units on the cpp side.

Also update relevant examples.
This commit is contained in:
Oblarg
2019-11-01 12:32:40 -04:00
committed by Peter Johnson
parent f6e311ef86
commit 9ebd23d61e
12 changed files with 88 additions and 39 deletions

View File

@@ -49,16 +49,17 @@ public final class Constants {
public static final double kShooterTargetRPS = 4000;
public static final double kShooterToleranceRPS = 50;
// These are not real PID gains, and will have to be tuned for your specific robot.
public static final double kP = 1;
public static final double kI = 0;
public static final double kD = 0;
// On a real robot the feedforward constants should be empirically determined; these are
// reasonable guesses.
public static final double kSFractional = .05;
public static final double kVFractional =
// Should have value 1 at free speed...
1. / kShooterFreeRPS;
public static final double kSVolts = .05;
public static final double kVVoltSecondsPerRotation =
// Should have value 12V at free speed...
12. / kShooterFreeRPS;
public static final double kFeederSpeed = .5;
}

View File

@@ -20,11 +20,11 @@ import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstan
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kFeederSpeed;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kI;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kP;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kSFractional;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kSVolts;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kShooterMotorPort;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kShooterTargetRPS;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kShooterToleranceRPS;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kVFractional;
import static edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants.kVVoltSecondsPerRotation;
public class ShooterSubsystem extends PIDSubsystem {
private final PWMVictorSPX m_shooterMotor = new PWMVictorSPX(kShooterMotorPort);
@@ -44,7 +44,7 @@ public class ShooterSubsystem extends PIDSubsystem {
@Override
public void useOutput(double output) {
// Use a feedforward of the form kS + kV * velocity
m_shooterMotor.set(output + kSFractional + kVFractional * kShooterTargetRPS);
m_shooterMotor.setVoltage(output + kSVolts + kVVoltSecondsPerRotation * kShooterTargetRPS);
}
@Override

View File

@@ -123,12 +123,12 @@ public class RobotContainer {
m_robotDrive.getRightEncoder()::getRate,
new PIDController(kPDriveVel, 0, 0),
new PIDController(kPDriveVel, 0, 0),
// RamseteCommand passes volts to the callback, so we have to rescale here
(left, right) -> m_robotDrive.tankDrive(left / 12., right / 12.),
// RamseteCommand passes volts to the callback
m_robotDrive::tankDriveVolts,
m_robotDrive
);
// Run path following command, then stop at the end.
return ramseteCommand.andThen(() -> m_robotDrive.tankDrive(0, 0));
return ramseteCommand.andThen(() -> m_robotDrive.tankDriveVolts(0, 0));
}
}

View File

@@ -107,14 +107,14 @@ public class DriveSubsystem extends SubsystemBase {
}
/**
* Drives the robot using tank controls. Does not square inputs to enable composition with
* external controllers.
* Controls the left and right sides of the drive directly with voltages.
*
* @param left the commanded left output
* @param right the commanded right output
* @param leftVolts the commanded left output
* @param rightVolts the commanded right output
*/
public void tankDrive(double left, double right) {
m_drive.tankDrive(left, right, false);
public void tankDriveVolts(double leftVolts, double rightVolts) {
m_leftMotors.setVoltage(leftVolts);
m_rightMotors.setVoltage(-rightVolts);
}
/**