Skip to content

Commit

Permalink
Merge branch 'main' into implement-new-climber-
Browse files Browse the repository at this point in the history
  • Loading branch information
TaylerUva authored Mar 17, 2024
2 parents c33ae6e + 0a68da7 commit 336f457
Show file tree
Hide file tree
Showing 3 changed files with 25 additions and 11 deletions.
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/RobotPreferences.java
Original file line number Diff line number Diff line change
Expand Up @@ -488,12 +488,12 @@ public static final class prefShooter {
public static final SN_DoublePreference shooterUpToSpeedTolerance = new SN_DoublePreference(
"shooterUpToSpeedTolerance", 0.7);

public static final SN_DoublePreference leftShooterIntakeVelocity = new SN_DoublePreference(
"leftShooterIntakeVelocity",
-10);
public static final SN_DoublePreference rightShooterIntakeVelocity = new SN_DoublePreference(
"rightShooterIntakeVelocity",
-10);
public static final SN_DoublePreference leftShooterIntakeVoltage = new SN_DoublePreference(
"leftShooterIntakeVoltage",
-3);
public static final SN_DoublePreference rightShooterIntakeVoltage = new SN_DoublePreference(
"rightShooterIntakeVoltage",
-3);

/**
* <b>Units:</b> Meters per second
Expand Down
5 changes: 2 additions & 3 deletions src/main/java/frc/robot/commands/IntakeFromSource.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@ public IntakeFromSource(Shooter subShooter, Transfer subTransfer, Pitch subPitch
public void initialize() {
lastDesiredPitch = subPitch.getPitchAngle();

subShooter.setDesiredVelocities(prefShooter.leftShooterIntakeVelocity.getValue(),
prefShooter.rightShooterIntakeVelocity.getValue());
subShooter.setVoltage(prefShooter.leftShooterIntakeVoltage.getValue(),
prefShooter.rightShooterIntakeVoltage.getValue());

subPitch.setPitchAngle(prefPitch.pitchSourceAngle.getValue());
subTurret.setTurretAngle(prefTurret.turretIntakePos.getValue());
Expand All @@ -51,7 +51,6 @@ public void initialize() {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
subShooter.getUpToSpeed();
subTransfer.setFeederMotorSpeed(prefTransfer.feederIntakeSourceSpeed.getValue());
subTransfer.setTransferMotorSpeed(prefTransfer.transferIntakeSourceSpeed.getValue());
}
Expand Down
19 changes: 17 additions & 2 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import com.ctre.phoenix6.controls.MotionMagicVelocityVoltage;
import com.ctre.phoenix6.controls.NeutralOut;
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand All @@ -26,7 +27,7 @@ public class Shooter extends SubsystemBase implements Logged {
MotionMagicVelocityVoltage motionMagicRequest;

VelocityVoltage velocityRequest;

VoltageOut voltageRequest;
boolean leftInvert, rightInvert;

@Log.NT
Expand Down Expand Up @@ -55,7 +56,7 @@ public Shooter() {

rightInvert = (RobotContainer.isPracticeBot()) ? constShooter.pracBot.RIGHT_INVERT
: constShooter.RIGHT_INVERT;

voltageRequest = new VoltageOut(0);
velocityRequest = new VelocityVoltage(0).withSlot(0);
motionMagicRequest = new MotionMagicVelocityVoltage(0);

Expand Down Expand Up @@ -103,6 +104,15 @@ public void getUpToSpeed() {
}
}

public void setLeftShooterIntakeVoltage(double voltage) {
leftMotor.setControl(voltageRequest.withOutput(voltage));

}

public void setRightShooterIntakeVoltage(double voltage) {
rightMotor.setControl(voltageRequest.withOutput(voltage));
}

/**
* Sets all of the shooting motors to neutral.
*/
Expand Down Expand Up @@ -170,6 +180,11 @@ public void setDesiredVelocities(double desiredLeftVelocity, double desiredRight
setRightDesiredVelocity(desiredRightVelocity);
}

public void setVoltage(double leftVoltage, double rightVoltage) {
setLeftShooterIntakeVoltage(leftVoltage);
setRightShooterIntakeVoltage(rightVoltage);
}

public void setIgnoreFlywheelSpeed(boolean ignoreFlywheelSpeed) {
this.ignoreFlywheelSpeed = ignoreFlywheelSpeed;
}
Expand Down

0 comments on commit 336f457

Please sign in to comment.