Skip to content

Commit

Permalink
Small Changes, formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
ReeledWarrior14 committed Mar 8, 2024
1 parent b7f43f8 commit 1716fe7
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 30 deletions.
31 changes: 14 additions & 17 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,11 @@

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
Expand Down Expand Up @@ -56,7 +54,6 @@ public class RobotContainer {
private final XboxController m_driverController = new XboxController(IOConstants.kDriverControllerPort);
private final XboxController m_operatorController = new XboxController(IOConstants.kOperatorControllerPort);


private final SendableChooser<Command> autoChooser;

/**
Expand All @@ -65,18 +62,18 @@ public class RobotContainer {
public RobotContainer() {
NamedCommands.registerCommand("Shoot",
new SequentialCommandGroup(
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting),
new ParallelDeadlineGroup(new WaitCommand(2), new NoteOuttakeCommand(m_intakeSubsystem)),
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off)));
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting),
new ParallelDeadlineGroup(new WaitCommand(2), new NoteOuttakeCommand(m_intakeSubsystem)),
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off)));

NamedCommands.registerCommand("Intake",
new SequentialCommandGroup(
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Extended),
new NoteIntakeCommand(m_intakeSubsystem),
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted)));
new SequentialCommandGroup(
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Extended),
new NoteIntakeCommand(m_intakeSubsystem),
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted)));

NamedCommands.registerCommand("Intake in",
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted));
NamedCommands.registerCommand("Intake in",
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted));

AutoBuilder.configureHolonomic(m_robotDrive::getPose, m_robotDrive::resetOdometry,
m_robotDrive::getChassisSpeeds,
Expand Down Expand Up @@ -155,11 +152,11 @@ private void configureBindings() {
.onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off));

new JoystickButton(m_operatorController, Button.kA.value)
.onTrue(new InstantCommand(() -> m_climberSubsystem.forward(),
m_climberSubsystem));
.onTrue(new InstantCommand(() -> m_climberSubsystem.forward(),
m_climberSubsystem));
new JoystickButton(m_operatorController, Button.kB.value)
.onTrue(new InstantCommand(() -> m_climberSubsystem.reverse(),
m_climberSubsystem));
.onTrue(new InstantCommand(() -> m_climberSubsystem.reverse(),
m_climberSubsystem));

new Trigger(() -> {
return m_driverController.getLeftTriggerAxis() > 0.5;
Expand Down Expand Up @@ -199,7 +196,7 @@ public Command getAutonomousCommand() {
// var alliance = DriverStation.getAlliance();
// PathPlannerPath autonPath = path;
// if (alliance.isPresent() && alliance.get() == DriverStation.Alliance.Red) {
// autonPath = autonPath.flipPath();
// autonPath = autonPath.flipPath();
// }
// m_robotDrive.resetOdometry(autonPath.getPreviewStartingHolonomicPose());

Expand Down
5 changes: 2 additions & 3 deletions src/main/java/frc/robot/subsystems/ClimberSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,11 @@
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kOff;
import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kReverse;

import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticHub;
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.PneumaticHub;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.ClimberConstants;

Expand Down
10 changes: 0 additions & 10 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.ShooterConstants;
Expand All @@ -21,17 +20,12 @@ public class ShooterSubsystem extends SubsystemBase {
private double m_topSpeed = 0;
private double m_bottomSpeed = 0;

// SlewRateLimiter m_topLimiter = new SlewRateLimiter(0.4);
// SlewRateLimiter m_bottomLimiter = new SlewRateLimiter(0.4);

public ShooterSubsystem() {
m_bottom.setIdleMode(IdleMode.kCoast);
m_top.setIdleMode(IdleMode.kCoast);

m_bottom.setInverted(true);
m_top.setInverted(true);

//m_bottom.getEncoder().setPositionConversionFactor();
}

public void reset() {
Expand All @@ -46,15 +40,11 @@ public void setShootingSpeed(ShootSpeed speed) {
switch (speed) {
case Shooting:
m_topSpeed = ShooterConstants.kShooterSpeedTop;
// m_topSpeed = m_topLimiter.calculate(m_topSpeed);
m_bottomSpeed = ShooterConstants.kShooterSpeedBottom;
// m_bottomSpeed = m_bottomLimiter.calculate(m_topSpeed);
// System.out.println("shoot speed: " + ShooterConstants.kShooterSpeed);
break;
case Off:
m_topSpeed = 0.0;
m_bottomSpeed = 0.0;
// System.out.println("shoot speed: " + 0);
break;
}
}
Expand Down

0 comments on commit 1716fe7

Please sign in to comment.