Skip to content

Commit

Permalink
Fix shooter after dhavn did bad (not tested)
Browse files Browse the repository at this point in the history
  • Loading branch information
LTeixeira4909 committed Feb 3, 2024
1 parent c8eb9d2 commit 601ce36
Show file tree
Hide file tree
Showing 4 changed files with 50 additions and 38 deletions.
2 changes: 1 addition & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,6 @@
"editor.defaultFormatter": "richardwillis.vscode-spotless-gradle"
},
"[java]": {
"editor.defaultFormatter": "richardwillis.vscode-spotless-gradle"
"editor.defaultFormatter": "redhat.java"
}
}
72 changes: 42 additions & 30 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,8 @@ public Robot() {
m_driverController.x().whileTrue(m_shooter.Stop());
m_driverController.rightTrigger().whileTrue(m_shooter.ShooterDelay());

// m_driverController.leftTrigger().whileTrue(new RepeatCommand(m_shooter.Intake()));
// m_driverController.leftTrigger().whileTrue(new
// RepeatCommand(m_shooter.Intake()));
// m_driverController.leftTrigger().whileTrue(m_intake.intake());
// m_driverController.y().whileTrue(m_intake.Spit());
m_driverController.b().whileTrue(m_intake.Stop());
Expand All @@ -117,27 +118,27 @@ public Robot() {
SmartDashboard.putNumber("StopDistance", defaultStopDistance);

// m_driverController
// .povUp()
// .onTrue(
// new SequentialCommandGroup(m_intake.intake(), m_shooter.Intake())
// .until(
// () -> {
// return mytimeofflight.getRange()
// <= SmartDashboard.getNumber("StopDistance", defaultStopDistance);
// }));
// .povUp()
// .onTrue(
// new SequentialCommandGroup(m_intake.intake(), m_shooter.Intake())
// .until(
// () -> {
// return mytimeofflight.getRange()
// <= SmartDashboard.getNumber("StopDistance", defaultStopDistance);
// }));

m_driverController
.leftTrigger()
.whileTrue(new ParallelRaceGroup(m_intake.intake(), m_shooter.Intake()).repeatedly());

// m_driverController
// .leftTrigger()
// .whileTrue(new SequentialCommandGroup(
// m_intake.intake(),
// m_shooter.Intake()).repeatedly()
// .until(

// ));
m_driverController
.leftTrigger()
.whileTrue(new ParallelRaceGroup(
m_intake.intake(),
m_shooter.Intake()).repeatedly()
.until(() -> {
return m_shooter.getCurrent() > 10;
}));

}

Expand All @@ -151,16 +152,19 @@ public Command SensorIntake() {
new RepeatCommand(m_shooter.Intake())
.until(
() -> {
return mytimeofflight.getRange()
<= SmartDashboard.getNumber("StopDistance", defaultStopDistance);
return mytimeofflight.getRange() <= SmartDashboard.getNumber("StopDistance", defaultStopDistance);
}));
}

/**
* This function is called every robot packet, no matter the mode. Use this for items like
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
* This function is called every robot packet, no matter the mode. Use this for
* items like
* diagnostics that you want ran during disabled, autonomous, teleoperated and
* test.
*
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
* <p>
* This runs after the mode specific periodic functions, but before LiveWindow
* and
* SmartDashboard integrated updating.
*/
@Override
Expand All @@ -179,28 +183,36 @@ public void autonomousInit() {
}

@Override
public void autonomousPeriodic() {}
public void autonomousPeriodic() {
}

@Override
public void teleopInit() {}
public void teleopInit() {
}

@Override
public void teleopPeriodic() {}
public void teleopPeriodic() {
}

@Override
public void disabledInit() {}
public void disabledInit() {
}

@Override
public void disabledPeriodic() {}
public void disabledPeriodic() {
}

@Override
public void testInit() {}
public void testInit() {
}

@Override
public void testPeriodic() {}
public void testPeriodic() {
}

@Override
public void simulationInit() {}
public void simulationInit() {
}

@Override
public void simulationPeriodic() {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
public class Intake extends SubsystemBase {
// private final double Speed = 1;
private final double StopSpeed = 0;
private double defaultFrontRollerSpeed = -.4;
private double defaultBackRollerSpeed = -.4;
private double defaultFrontRollerSpeed = -.5;
private double defaultBackRollerSpeed = -.5;
private double defaultFrontRollerSpeedSpit = .5;
private double defaultBackRollerSpeedSpit = .5;

Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
public class Shooter extends SubsystemBase {

private final double InSpeed = -.4;
private final double OutSpeed = .25;
private final double OutSpeed = .4;
private final double StopSpeed = 0;
private double defaultDelay = .3;

Expand Down Expand Up @@ -97,8 +97,8 @@ public Command Feeder() {
.repeatedly();
}

// public Command getCurrent(){
// feeder.getTorqueCurrent();
// return double.getTorqueCurrent();
// }
public double getCurrent(){
return feeder.getTorqueCurrent().getValue();

}
}

0 comments on commit 601ce36

Please sign in to comment.