Skip to content

Commit

Permalink
after drive prac
Browse files Browse the repository at this point in the history
  • Loading branch information
KPatel008 committed Feb 4, 2024
1 parent 7cdfd19 commit 00fe13d
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 13 deletions.
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -149,11 +149,13 @@ public Robot() {
// }));

// ____________________driverController_______________________\\
m_driverController.rightTrigger().onTrue(m_shooter.Feeder());
m_driverController
.rightTrigger()
.onTrue(new ParallelRaceGroup(m_intake.intake(), m_shooter.Feeder()));

m_driverController
.rightBumper()
.whileTrue(new ParallelRaceGroup(m_intake.Spit(), m_shooter.Feeder()));
.whileTrue(new ParallelRaceGroup(m_intake.Spit(), m_shooter.FeederOut()));

m_driverController.button(7).onTrue(m_drivetrain.zeroGyro());

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/drivetrain/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public class Drivetrain extends SubsystemBase {
Math.hypot(kTrackwidthMeters / 2.0, kWheelbaseMeters / 2.0);
private final double kMaxLinearSpeedMetersPerSecond = Units.feetToMeters(16.5);
private final double kMaxAngularSpeedRadPerSec = 2 * Math.PI;
private final double kDeadband = 0.05;
private final double kDeadband = 0.07;
private final boolean kUseVisionCorrection = true;

public static final Lock odometryLock = new ReentrantLock();
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ public class ModuleIOTalonFX implements ModuleIO {
private final double kDrivekV = 0.1;
private final double kSteerkP = 100.0;
private final double kSteerkD = 0.2;
private final double kSlipCurrent = 400.0;
private final double kSlipCurrent = 80;
private final String kCanBusName = "CANivore1";

private final TalonFX m_driveMotor, m_steerMotor;
Expand Down
17 changes: 8 additions & 9 deletions src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,6 @@ public void periodic() {}
public Command Shoot() {
return new InstantCommand(
() -> {
SmartDashboard.putNumber("ShooterSpeed", OutSpeed);

shooterTop.set(OutSpeed);
shooterBottom.set(OutSpeed);
},
Expand All @@ -56,14 +54,15 @@ public Command Shoot() {

public Command Stop() {
return new InstantCommand(
() -> {
SmartDashboard.putNumber("ShooterSpeed", StopSpeed);
() -> {
SmartDashboard.putNumber("ShooterSpeed", StopSpeed);

shooterTop.set(StopSpeed);
shooterBottom.set(StopSpeed);
feeder.set(StopSpeed);
},
this);
shooterTop.set(StopSpeed);
shooterBottom.set(StopSpeed);
feeder.set(StopSpeed);
},
this)
.repeatedly();
}

public Command Intake() {
Expand Down

0 comments on commit 00fe13d

Please sign in to comment.