Skip to content

Commit

Permalink
with event marker
Browse files Browse the repository at this point in the history
  • Loading branch information
JediScoy committed Mar 31, 2024
1 parent 4d007ca commit 77e6ce4
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 8 deletions.
6 changes: 6 additions & 0 deletions src/main/deploy/pathplanner/autos/Start1.0-3 Quick.auto
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,12 @@
]
}
},
{
"type": "named",
"data": {
"name": "ShootFromStage"
}
},
{
"type": "path",
"data": {
Expand Down
6 changes: 2 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -127,11 +127,9 @@ public RobotContainer() {

/* Pathplanner Named Commands */
NamedCommands.registerCommand("ShootClose", new ShootClose(arm, index, intake, shooter));
NamedCommands.registerCommand("ShootClose2", shootWhenReadyAuton);
NamedCommands.registerCommand("ShootFromStage", shootFromStage);
NamedCommands.registerCommand("Intake", new IntakeIndex(index, intake));
NamedCommands.registerCommand("AutoShootWhenReady", shootWhenReadyAuton); // Autonomous
NamedCommands.registerCommand("ShootWhenReady", shootWhenReadyAuton); // Autonomous
NamedCommands.registerCommand("SetFlywheelToIdle", setShooterIdle);
// Constants.ArmConstants.ARM_MID_POSE));

Expand Down Expand Up @@ -207,10 +205,10 @@ private void configureBindings() {
// m_driverController.rightTrigger().whileTrue(setShooterVelocity);

// TODO Testing "autonShootWhenReady" Remove later
// m_driverController.rightTrigger().whileTrue(autonShootWhenReady);
m_driverController.leftTrigger().whileTrue(shootWhenReadyAuton);

// TODO Test MotionMagicVelocityVoltage" only, then remove
m_driverController.leftTrigger().whileTrue(new InstantCommand(() -> shooter2.setFlywheelVelocityMM(shooter2.FLYWHEEL_VELOCITY)));
// m_driverController.leftTrigger().whileTrue(new InstantCommand(() -> shooter2.setFlywheelVelocityMM(shooter2.FLYWHEEL_VELOCITY)));

// TODO Remove comment out after testing the MotionMagic Velocity Voltage
// m_driverController.leftTrigger().whileTrue(new SetIndex(index, -0.75));
Expand Down
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/commands/ShootFromStage.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,8 @@ public ShootFromStage(ArmSubsystem arm, IndexSubsystem index, IntakeSubsystem in
addCommands(
// Set the arm to the middle position for shooting from the closest Stage leg
new SetArmPosition(arm, Constants.ArmConstants.ARM_MID_POSE),

// Check target velocity and index the game piece forward
new ShootWhenReady(shooter2, index, notesensor),
new ShootWhenReady(shooter2, index, notesensor).withTimeout(.75),

// Set arm back to home position
new SetArmPosition(arm, Constants.ArmConstants.ARM_HOME_POSE)
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/util/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,8 @@ public static class IndexConstants {
}

public static class IntakeConstants {
public static final double INTAKE_POWER = 0.75; // 0.75
public static final double INTAKE_POWER_REV = -0.75;
public static final double INTAKE_POWER = -0.75; // 0.75
public static final double INTAKE_POWER_REV = 0.75;

}

Expand Down

0 comments on commit 77e6ce4

Please sign in to comment.