Skip to content

Commit ba9e05f

Browse files
committed
Checked button bindings
1 parent a887a50 commit ba9e05f

File tree

5 files changed

+51
-52
lines changed

5 files changed

+51
-52
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -135,12 +135,12 @@ public static class IntakeConstants {
135135
public static final double INTAKE_SPEED = 1;
136136
public static final double SPITAKE_SPEED = -1;
137137
public static final double DEPLOY_SPEED = 1;
138-
public static final Angle DEPLOY_POSITION = Degrees.of(70);
138+
public static final Angle DEPLOY_POSITION = Degrees.of(70);
139139
public static final Angle READY_POSITION = Degrees.of(40);
140140
public static final Angle UP_POSITION = Degrees.of(0);
141141
public static final Angle DEPLOY_TOLERANCE = Degrees.of(5);
142142

143-
public static final double kP = 1;//1.33;
143+
public static final double kP = 1; // 1.33;
144144
public static final double kI = 0;
145145
public static final double kD = 7.84;
146146
public static final double DEPLOY_RATIO = 25;

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

Lines changed: 9 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,6 @@
4040
import frc.robot.subsystems.shooter.ShooterSim;
4141
import frc.robot.subsystems.vision.Vision;
4242
import frc.robot.subsystems.vision.VisionIO;
43-
import frc.robot.subsystems.vision.VisionIOPhotonVision;
4443
import frc.robot.subsystems.vision.VisionIOPhotonVisionSim;
4544

4645
/**
@@ -98,13 +97,11 @@ public RobotContainer() {
9897
new ModuleIOTalonFX(TunerConstants.FrontRight),
9998
new ModuleIOTalonFX(TunerConstants.BackLeft),
10099
new ModuleIOTalonFX(TunerConstants.BackRight));
101-
vision =
102-
new Vision(
103-
drive::addVisionMeasurement, new VisionIO(){});
104-
// new VisionIOPhotonVision(
105-
// VisionConstants.camera0Name, VisionConstants.robotToCamera0),
106-
// new VisionIOPhotonVision(
107-
// VisionConstants.camera1Name, VisionConstants.robotToCamera1));
100+
vision = new Vision(drive::addVisionMeasurement, new VisionIO() {});
101+
// new VisionIOPhotonVision(
102+
// VisionConstants.camera0Name, VisionConstants.robotToCamera0),
103+
// new VisionIOPhotonVision(
104+
// VisionConstants.camera1Name, VisionConstants.robotToCamera1));
108105
// new VisionIOPhotonVision(
109106
// VisionConstants.camera2Name, VisionConstants.robotToCamera2),
110107
// new VisionIOPhotonVision(
@@ -279,7 +276,7 @@ private void configureButtonBindings() {
279276
() -> -controller.getRightX() * speed,
280277
() -> robotRelative));
281278

282-
// toggles between robot- and field-relative drive
279+
// toggles between robot- and field-relative drive
283280
controller
284281
.leftStick()
285282
.onTrue(
@@ -342,7 +339,7 @@ private void configureButtonBindings() {
342339
SmartDashboard.putNumber("Drive/Speed", speed);
343340
}));
344341
// reset drive commands
345-
// reset drive commands
342+
// reset drive commands
346343
operator
347344
.povUp()
348345
.onTrue(
@@ -358,7 +355,7 @@ private void configureButtonBindings() {
358355
() -> -controller.getLeftX() * speed,
359356
() -> -controller.getRightX() * speed,
360357
() -> robotRelative)));
361-
// reset gyro
358+
// reset gyro
362359
controller
363360
.povDown()
364361
.onTrue(
@@ -396,7 +393,7 @@ private void configureButtonBindings() {
396393

397394
/* SHOOTER COMMANDS */
398395

399-
// This trigger probably goes off way too much - maybe make shooter.atSpeed() lock this at true?
396+
// This trigger probably goes off way too much - maybe make shooter.atSpeed() lock this at true?
400397
DriveCommands.aligned()
401398
.and(() -> shooter.atSpeed() && false) // Armaan, turn off rumble
402399
.onTrue(

src/main/java/frc/robot/subsystems/climber/Climber.java

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -37,10 +37,7 @@ private Command runCMD(double speed) {
3737

3838
public Command raiseCMD() {
3939
return Commands.deadline(
40-
Commands.waitUntil(
41-
() ->
42-
climbEncoder.getPosition()
43-
<= ClimberConstants.POS_TOLERANCE),
40+
Commands.waitUntil(() -> climbEncoder.getPosition() <= ClimberConstants.POS_TOLERANCE),
4441
runCMD(ClimberConstants.RAISE_SPEED))
4542
.andThen(runCMD(0));
4643
}
@@ -60,7 +57,7 @@ public Command tuckCMD() {
6057
Commands.waitUntil(
6158
() ->
6259
climbEncoder.getPosition()
63-
>= ClimberConstants.DOWN_POSITION - (2*ClimberConstants.POS_TOLERANCE)),
60+
>= ClimberConstants.DOWN_POSITION - (2 * ClimberConstants.POS_TOLERANCE)),
6461
runCMD(ClimberConstants.PULL_SPEED))
6562
.andThen(runCMD(0));
6663
}

src/main/java/frc/robot/subsystems/intake/Deploy.java

Lines changed: 29 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -10,13 +10,12 @@
1010
import com.revrobotics.RelativeEncoder;
1111
import com.revrobotics.ResetMode;
1212
import com.revrobotics.spark.FeedbackSensor;
13+
import com.revrobotics.spark.SparkBase.ControlType;
1314
import com.revrobotics.spark.SparkClosedLoopController;
1415
import com.revrobotics.spark.SparkLowLevel.MotorType;
1516
import com.revrobotics.spark.SparkMax;
16-
import com.revrobotics.spark.SparkBase.ControlType;
1717
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
1818
import com.revrobotics.spark.config.SparkMaxConfig;
19-
2019
import edu.wpi.first.math.controller.ArmFeedforward;
2120
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2221
import edu.wpi.first.wpilibj2.command.Command;
@@ -32,26 +31,23 @@ public class Deploy extends SubsystemBase {
3231
RelativeEncoder deployEncoder = deployMotor.getEncoder();
3332

3433
SparkMaxConfig config = new SparkMaxConfig();
35-
ArmFeedforward feedforward =
36-
new ArmFeedforward(
37-
IntakeConstants.kS,
38-
IntakeConstants.kG,
39-
IntakeConstants.kV);
34+
ArmFeedforward feedforward =
35+
new ArmFeedforward(IntakeConstants.kS, IntakeConstants.kG, IntakeConstants.kV);
4036

4137
public Deploy() {
4238
config.smartCurrentLimit(50).idleMode(IdleMode.kBrake);
4339
config.encoder.positionConversionFactor(IntakeConstants.DEPLOY_RATIO);
4440
config
4541
.closedLoop
46-
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
47-
.p(IntakeConstants.kP)
48-
.i(IntakeConstants.kI)
49-
.d(IntakeConstants.kD)
42+
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
43+
.p(IntakeConstants.kP)
44+
.i(IntakeConstants.kI)
45+
.d(IntakeConstants.kD)
5046
.feedForward
51-
.kS(IntakeConstants.kS)
52-
.kG(IntakeConstants.kG)
53-
.kV(IntakeConstants.kV);
54-
//.kCosRatio(IntakeConstants.DEPLOY_RATIO);
47+
.kS(IntakeConstants.kS)
48+
.kG(IntakeConstants.kG)
49+
.kV(IntakeConstants.kV);
50+
// .kCosRatio(IntakeConstants.DEPLOY_RATIO);
5551
deployMotor.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
5652

5753
deployEncoder.setPosition(0);
@@ -70,9 +66,12 @@ public Deploy() {
7066
// Adds start and stop for deploying
7167
public Command deployCMD() {
7268
// Deploys fuel
73-
return Commands.runOnce(() -> {
74-
closedLoopController.setSetpoint(IntakeConstants.DEPLOY_POSITION.in(Radians), ControlType.kPosition);
75-
}).withName("Deployed");
69+
return Commands.runOnce(
70+
() -> {
71+
closedLoopController.setSetpoint(
72+
IntakeConstants.DEPLOY_POSITION.in(Radians), ControlType.kPosition);
73+
})
74+
.withName("Deployed");
7675
// return Commands.deadline(
7776
// Commands.waitUntil(
7877
// () ->
@@ -83,9 +82,12 @@ public Command deployCMD() {
8382
}
8483

8584
public Command readyCMD() {
86-
return Commands.runOnce(() -> {
87-
closedLoopController.setSetpoint(IntakeConstants.READY_POSITION.in(Radians), ControlType.kPosition);
88-
}).withName("Ready");
85+
return Commands.runOnce(
86+
() -> {
87+
closedLoopController.setSetpoint(
88+
IntakeConstants.READY_POSITION.in(Radians), ControlType.kPosition);
89+
})
90+
.withName("Ready");
8991
// return Commands.deadline(
9092
// Commands.waitUntil(
9193
// () ->
@@ -96,9 +98,12 @@ public Command readyCMD() {
9698
}
9799

98100
public Command undeployCMD() {
99-
return Commands.run(() -> {
100-
closedLoopController.setSetpoint(IntakeConstants.UP_POSITION.in(Radians), ControlType.kPosition);
101-
}).withName("Retracted");
101+
return Commands.run(
102+
() -> {
103+
closedLoopController.setSetpoint(
104+
IntakeConstants.UP_POSITION.in(Radians), ControlType.kPosition);
105+
})
106+
.withName("Retracted");
102107
// return Commands.deadline(
103108
// Commands.waitUntil(
104109
// () -> deployEncoder.getPosition() <= IntakeConstants.DEPLOY_TOLERANCE),

src/main/java/frc/robot/subsystems/shooter/Shooter.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -68,9 +68,10 @@ public Shooter() {
6868
tryUntilOk(5, () -> flywheel.getConfigurator().apply(currentLimits));
6969

7070
SmartDashboard.putNumber("Shooter/Target RPS", 0.0);
71-
SmartDashboard.putNumber("Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
72-
SmartDashboard.putNumber("Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
73-
71+
SmartDashboard.putNumber(
72+
"Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
73+
SmartDashboard.putNumber(
74+
"Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
7475
}
7576

7677
public void intake() {} // for sim
@@ -273,12 +274,11 @@ public Command stopCMD() {
273274
@Override
274275
public void periodic() {
275276
SmartDashboard.putNumber(
276-
"Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
277-
SmartDashboard.putNumber(
278-
"Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
279-
SmartDashboard.putNumber("Shooter/Target RPS", targetRPS);
280-
SmartDashboard.putNumber(
281-
"Shooter/Flywheel RPS", flywheel.getVelocity().getValueAsDouble());
277+
"Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
278+
SmartDashboard.putNumber(
279+
"Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
280+
SmartDashboard.putNumber("Shooter/Target RPS", targetRPS);
281+
SmartDashboard.putNumber("Shooter/Flywheel RPS", flywheel.getVelocity().getValueAsDouble());
282282
}
283283

284284
@Override

0 commit comments

Comments
 (0)