Skip to content

Commit e48835a

Browse files
committed
elims buttons, algae score bug, tighter algae hold
1 parent bc46fb1 commit e48835a

File tree

7 files changed

+12
-4
lines changed

7 files changed

+12
-4
lines changed

src/main/java/frc/robot/RobotContainer.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -838,8 +838,8 @@ public void updateCanivoreStatus() {
838838
}
839839

840840
public void updateCANErrorCount() {
841-
rCanErrors = RobotController.getCANStatus().receiveErrorCount;
842-
tCanErrors = RobotController.getCANStatus().transmitErrorCount;
841+
rCanErrors += RobotController.getCANStatus().receiveErrorCount;
842+
tCanErrors += RobotController.getCANStatus().transmitErrorCount;
843843
}
844844

845845
public void disableNoMotionCal() {

src/main/java/frc/robot/commands/robotState/ForceBargeCommand.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ public ForceBargeCommand(
2828

2929
@Override
3030
public void initialize() {
31+
hasEjectedToBarge = false;
3132
startState = robotStateSubsystem.getState();
3233
startingElevatorFinished = elevatorSubsystem.isFinished();
3334
robotStateSubsystem.setAlgaeHeight(AlgaeHeight.HIGH);

src/main/java/frc/robot/commands/robotState/ForceProcessorCommand.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ public ForceProcessorCommand(
2828

2929
@Override
3030
public void initialize() {
31+
hasEjectedToBarge = false;
3132
startState = robotStateSubsystem.getState();
3233
startingElevatorFinished = elevatorSubsystem.isFinished();
3334
robotStateSubsystem.setAlgaeHeight(AlgaeHeight.LOW);

src/main/java/frc/robot/commands/robotState/ScoreAlgaeCommand.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@ public ScoreAlgaeCommand(
2626

2727
@Override
2828
public void initialize() {
29+
hasEjectedToBarge = false;
2930
startState = robotStateSubsystem.getState();
3031
startingElevatorFinished = elevatorSubsystem.isFinished();
3132
if (startState == RobotStates.PROCESSOR_ALGAE || startState == RobotStates.BARGE_ALGAE) {

src/main/java/frc/robot/subsystems/algae/AlgaeIO.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ public interface AlgaeIO {
77
@AutoLog
88
public static class AlgaeIOInputs {
99
public double velocity;
10+
public double statorCurrent;
1011
public boolean isBeamBroken;
1112
public boolean isCoralBeamBroken;
1213
}

src/main/java/frc/robot/subsystems/algae/AlgaeIOFX.java

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
import com.ctre.phoenix6.signals.ForwardLimitValue;
1111
import com.ctre.phoenix6.signals.ReverseLimitValue;
1212
import edu.wpi.first.units.measure.AngularVelocity;
13+
import edu.wpi.first.units.measure.Current;
1314
import frc.robot.constants.AlgaeConstants;
1415
import org.slf4j.Logger;
1516
import org.slf4j.LoggerFactory;
@@ -37,6 +38,7 @@ public class AlgaeIOFX implements AlgaeIO, Checkable {
3738
private StatusSignal<ReverseLimitValue> revLimitSwitch;
3839
private VelocityVoltage speedRequest = new VelocityVoltage(0).withEnableFOC(false).withSlot(0);
3940
private DutyCycleOut dutyCycleRequest = new DutyCycleOut(0).withEnableFOC(false);
41+
private StatusSignal<Current> statorCurrent;
4042

4143
public AlgaeIOFX() {
4244
logger = LoggerFactory.getLogger(this.getClass());
@@ -49,14 +51,16 @@ public AlgaeIOFX() {
4951
fwdLimitSwitch = talonFXS.getForwardLimit();
5052
revLimitSwitch = talonFXS.getReverseLimit();
5153
curVelocity = talonFXS.getVelocity();
54+
statorCurrent = talonFXS.getStatorCurrent();
5255
}
5356

5457
@Override
5558
public void updateInputs(AlgaeIOInputs inputs) {
56-
BaseStatusSignal.refreshAll(curVelocity, fwdLimitSwitch, revLimitSwitch);
59+
BaseStatusSignal.refreshAll(curVelocity, fwdLimitSwitch, revLimitSwitch, statorCurrent);
5760
inputs.velocity = curVelocity.getValueAsDouble();
5861
inputs.isBeamBroken = fwdLimitSwitch.getValue().value == 0;
5962
inputs.isCoralBeamBroken = revLimitSwitch.getValue().value == 1;
63+
inputs.statorCurrent = statorCurrent.getValueAsDouble();
6064
}
6165

6266
@Override

src/main/java/frc/robot/subsystems/algae/AlgaeSubsystem.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ public void scoreCoral() {
6363

6464
public void holdAlgae() {
6565
// setSpeed(AlgaeConstants.kHoldSpeed);
66-
setPct(0.06);
66+
setPct(0.08);
6767
}
6868

6969
public void holdCoral() {

0 commit comments

Comments
 (0)