shooter units off
This commit is contained in:
@@ -8,17 +8,23 @@ import edu.wpi.first.math.util.Units;
|
|||||||
|
|
||||||
public class ShooterConstants {
|
public class ShooterConstants {
|
||||||
public enum ShooterSpeeds {
|
public enum ShooterSpeeds {
|
||||||
kHubSpeed(0),
|
kHubSpeed(4000.0),
|
||||||
kFeedSpeed(0.35);
|
kFeedSpeed(6000.0);
|
||||||
|
|
||||||
private double speedMPS;
|
private double speedMPS;
|
||||||
|
private double speedRPM;
|
||||||
|
|
||||||
private ShooterSpeeds(double speedMPS) {
|
private ShooterSpeeds(double speedRPM) {
|
||||||
this.speedMPS = speedMPS;
|
this.speedMPS = speedRPM * kWheelDiameter*Math.PI;
|
||||||
|
this.speedRPM = speedRPM;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getSpeedMPS() {
|
public double getSpeedMPS() {
|
||||||
return speedMPS;
|
return speedMPS * kWheelDiameter*Math.PI;
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getSpeedRPM(){
|
||||||
|
return speedRPM;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -31,16 +37,16 @@ public class ShooterConstants {
|
|||||||
public static final int kRightShooterMotorCANID = 5;
|
public static final int kRightShooterMotorCANID = 5;
|
||||||
|
|
||||||
public static final boolean kLeftShooterMotorInverted = true;
|
public static final boolean kLeftShooterMotorInverted = true;
|
||||||
public static final boolean kRightShooterMotorInverted = false;
|
public static final boolean kRightShooterMotorInverted = true;
|
||||||
|
|
||||||
public static final double kLeftP = 0.1;
|
public static final double kLeftP = 0;//0.1;
|
||||||
public static final double kLeftI = 0;
|
public static final double kLeftI = 0;
|
||||||
public static final double kLeftD = 0;
|
public static final double kLeftD = 0;
|
||||||
public static final double kLeftS = 0;
|
public static final double kLeftS = 0;
|
||||||
public static final double kLeftV = 0.21;
|
public static final double kLeftV = 0.21;
|
||||||
public static final double kLeftA = 0;
|
public static final double kLeftA = 0;
|
||||||
|
|
||||||
public static final double kRightP = 0.1;
|
public static final double kRightP = 0;//0.1;
|
||||||
public static final double kRightI = 0;
|
public static final double kRightI = 0;
|
||||||
public static final double kRightD = 0;
|
public static final double kRightD = 0;
|
||||||
public static final double kRightS = 0;
|
public static final double kRightS = 0;
|
||||||
@@ -68,8 +74,8 @@ public class ShooterConstants {
|
|||||||
.smartCurrentLimit(kCurrentLimit)
|
.smartCurrentLimit(kCurrentLimit)
|
||||||
.inverted(kLeftShooterMotorInverted);
|
.inverted(kLeftShooterMotorInverted);
|
||||||
kLeftMotorConfig.absoluteEncoder
|
kLeftMotorConfig.absoluteEncoder
|
||||||
.positionConversionFactor(kWheelDiameter * Math.PI)
|
.positionConversionFactor(1)
|
||||||
.velocityConversionFactor(kWheelDiameter * Math.PI / 60);
|
.velocityConversionFactor(1);
|
||||||
kLeftMotorConfig.closedLoop
|
kLeftMotorConfig.closedLoop
|
||||||
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
|
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
|
||||||
.pid(kLeftP, kLeftI, kLeftD)
|
.pid(kLeftP, kLeftI, kLeftD)
|
||||||
@@ -82,8 +88,9 @@ public class ShooterConstants {
|
|||||||
.smartCurrentLimit(kCurrentLimit)
|
.smartCurrentLimit(kCurrentLimit)
|
||||||
.inverted(kRightShooterMotorInverted);
|
.inverted(kRightShooterMotorInverted);
|
||||||
kRightMotorConfig.absoluteEncoder
|
kRightMotorConfig.absoluteEncoder
|
||||||
.positionConversionFactor(kWheelDiameter * Math.PI)
|
.positionConversionFactor(1)
|
||||||
.velocityConversionFactor(kWheelDiameter * Math.PI / 60);
|
.velocityConversionFactor(1)
|
||||||
|
.inverted(true);
|
||||||
kRightMotorConfig.closedLoop
|
kRightMotorConfig.closedLoop
|
||||||
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
|
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
|
||||||
.pid(kRightP, kRightI, kRightD)
|
.pid(kRightP, kRightI, kRightD)
|
||||||
|
|||||||
@@ -59,12 +59,12 @@ public class Shooter extends SubsystemBase {
|
|||||||
@Override
|
@Override
|
||||||
public void periodic() {
|
public void periodic() {
|
||||||
Logger.recordOutput(
|
Logger.recordOutput(
|
||||||
"Shooter/TargetMPS",
|
"Shooter/TargetRPM",
|
||||||
targetSpeeds == null ? 0 : targetSpeeds.getSpeedMPS()
|
targetSpeeds == null ? 0 : targetSpeeds.getSpeedRPM()
|
||||||
);
|
);
|
||||||
|
|
||||||
Logger.recordOutput("Shooter/LeftRollers/CurrentMPS", leftEncoder.getVelocity());
|
Logger.recordOutput("Shooter/LeftRollers/CurrentRPM", leftEncoder.getVelocity());
|
||||||
Logger.recordOutput("Shooter/RightRollers/CurrentMPS", rightEncoder.getVelocity());
|
Logger.recordOutput("Shooter/RightRollers/CurrentRPM", rightEncoder.getVelocity());
|
||||||
|
|
||||||
// TODO How does the SparkMAX controller determine "at setpoint"? Is there any tolerance?
|
// TODO How does the SparkMAX controller determine "at setpoint"? Is there any tolerance?
|
||||||
Logger.recordOutput("Shooter/LeftRollers/AtSetpoint", leftClosedLoopController.isAtSetpoint());
|
Logger.recordOutput("Shooter/LeftRollers/AtSetpoint", leftClosedLoopController.isAtSetpoint());
|
||||||
@@ -80,12 +80,12 @@ public class Shooter extends SubsystemBase {
|
|||||||
rightMotor.disable();
|
rightMotor.disable();
|
||||||
} else {
|
} else {
|
||||||
leftClosedLoopController.setSetpoint(
|
leftClosedLoopController.setSetpoint(
|
||||||
targetSpeeds.getSpeedMPS(),
|
targetSpeeds.getSpeedRPM(),
|
||||||
ControlType.kVelocity
|
ControlType.kVelocity
|
||||||
);
|
);
|
||||||
|
|
||||||
rightClosedLoopController.setSetpoint(
|
rightClosedLoopController.setSetpoint(
|
||||||
-targetSpeeds.getSpeedMPS(),
|
-targetSpeeds.getSpeedRPM(),
|
||||||
ControlType.kVelocity
|
ControlType.kVelocity
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user