Skip to content

Commit 63a2ad6

Browse files
authored
Merge pull request #2 from carrotfarm02/wyatt/launcher-prototype
added launcher prototype subsystem
2 parents 7636016 + b59c281 commit 63a2ad6

3 files changed

Lines changed: 46 additions & 2 deletions

File tree

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

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
import frc.robot.subsystems.feeder.FeederConstants;
3434
import frc.robot.subsystems.intakeAndLauncher.IntakeAndLauncher;
3535
import frc.robot.subsystems.intakeAndLauncher.IntakeAndLauncherConstants;
36+
import frc.robot.subsystems.prototype.Prototype;
3637
import frc.robot.util.CANHealthLogger;
3738

3839
/**
@@ -46,6 +47,7 @@ public class RobotContainer {
4647
private final Drive drive;
4748
private final IntakeAndLauncher intakeAndShooter;
4849
private final Feeder feederAndIndexer;
50+
private final Prototype prototype;
4951

5052
// Controller
5153
private final CommandXboxController controller = new CommandXboxController(0);
@@ -121,6 +123,7 @@ public RobotContainer() {
121123
this.feederAndIndexer = new Feeder();
122124
break;
123125
}
126+
prototype = new Prototype();
124127
this.canLogger = new CANHealthLogger();
125128

126129
// Initialize ChoreoLib AutoFactory
@@ -231,6 +234,11 @@ private void configureButtonBindings() {
231234
feederAndIndexer.voltageCmd(FeederConstants.launchVoltage.get()))))
232235
.onFalse(
233236
Commands.parallel(intakeAndShooter.voltageCmd(0.0), feederAndIndexer.voltageCmd(0.0)));
237+
// prototype controls
238+
controller
239+
.x()
240+
.whileTrue(prototype.voltageCmdPrototype(5))
241+
.whileFalse(prototype.voltageCmdPrototype(0));
234242
}
235243

236244
/**

src/main/java/frc/robot/subsystems/drive/DriveConstants.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ public final class AutoConstants {
1313
public static final LoggedTunableGains headingTrajectoryController =
1414
new LoggedTunableGains("headingTraj", new ControlGains().p(3).d(0.0));
1515
}
16-
public final static LoggedTunableNumber speedScalar =
17-
new LoggedTunableNumber("Drive/Drive Speed Scalar", 1);
16+
17+
public static final LoggedTunableNumber speedScalar =
18+
new LoggedTunableNumber("Drive/Drive Speed Scalar", 1);
1819
}
Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
package frc.robot.subsystems.prototype;
2+
3+
import com.ctre.phoenix6.controls.Follower;
4+
import com.ctre.phoenix6.hardware.TalonFX;
5+
import com.ctre.phoenix6.signals.MotorAlignmentValue;
6+
import edu.wpi.first.wpilibj2.command.Command;
7+
import edu.wpi.first.wpilibj2.command.Commands;
8+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
9+
import org.littletonrobotics.junction.Logger;
10+
11+
public class Prototype extends SubsystemBase {
12+
private TalonFX leftMotor = new TalonFX(2);
13+
private TalonFX rightMotor = new TalonFX(1);
14+
private double trackedvoltage = 0;
15+
16+
@Override
17+
public void periodic() {
18+
Logger.recordOutput("Prototype/voltage", trackedvoltage);
19+
}
20+
21+
public Prototype() {
22+
rightMotor.setControl(new Follower(leftMotor.getDeviceID(), MotorAlignmentValue.Opposed));
23+
}
24+
25+
public void setVoltagePrototype(double commandedVoltage) {
26+
leftMotor.setVoltage(commandedVoltage);
27+
trackedvoltage = commandedVoltage;
28+
}
29+
30+
public Command voltageCmdPrototype(double desiredVoltage) {
31+
return Commands.sequence(
32+
Commands.print("LaunchPrototype set to: " + desiredVoltage),
33+
Commands.runOnce(() -> this.setVoltagePrototype(desiredVoltage), this));
34+
}
35+
}

0 commit comments

Comments
 (0)