From a96cd7a3e2189695446895be06591a63b9097ffb Mon Sep 17 00:00:00 2001 From: aarav18 Date: Mon, 20 Jan 2020 08:59:20 -0800 Subject: [PATCH] Finished up Velocity Control PID Shooter PID --- .../java/frc4388/robot/RobotContainer.java | 6 ++- .../commands/ShooterVelocityControlPID.java | 47 +++++++++++++++++++ .../frc4388/robot/subsystems/Shooter.java | 3 +- 3 files changed, 54 insertions(+), 2 deletions(-) create mode 100644 src/main/java/frc4388/robot/commands/ShooterVelocityControlPID.java diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index abdfb35..d4902b2 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -20,6 +20,7 @@ import frc4388.robot.commands.DriveAtVelocityPID; import frc4388.robot.commands.DriveToDistanceMM; import frc4388.robot.commands.DriveToDistancePID; import frc4388.robot.commands.RunIntakeWithTriggers; +import frc4388.robot.commands.ShooterVelocityControlPID; import frc4388.robot.subsystems.Drive; import frc4388.robot.subsystems.Elevator; import frc4388.robot.subsystems.Intake; @@ -99,13 +100,16 @@ public class RobotContainer { new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) .whenPressed(new DriveAtVelocityPID(m_robotDrive, 2000)); + new JoystickButton(getOperatorJoystick(), XboxController.X_BUTTON) + .whileHeld(new ShooterVelocityControlPID(m_robotShooter, 2000)); + new JoystickButton(getOperatorJoystick(), XboxController.LEFT_BUMPER_BUTTON) .whenPressed(new DistanceElevatorPID(m_robotElevator, 20000)); new JoystickButton(getDriverJoystick(), XboxController.LEFT_JOYSTICK_BUTTON) .whenPressed(new InstantCommand(null, m_robotDrive)); - new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON) + new JoystickButton(getOperatorJoystick(), XboxController.B_BUTTON) .whileHeld(() -> m_robotShooter.runDrumShooter(1), m_robotShooter); } diff --git a/src/main/java/frc4388/robot/commands/ShooterVelocityControlPID.java b/src/main/java/frc4388/robot/commands/ShooterVelocityControlPID.java new file mode 100644 index 0000000..dcc0fb3 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/ShooterVelocityControlPID.java @@ -0,0 +1,47 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package frc4388.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc4388.robot.subsystems.Shooter; + +public class ShooterVelocityControlPID extends CommandBase { + Shooter m_shooter; + double m_targetVel; + /** + * Creates a new ShooterVelocityControlPID. + */ + public ShooterVelocityControlPID(Shooter subsystem, double targetVel) { + // Use addRequirements() here to declare subsystem dependencies. + m_shooter = subsystem; + m_targetVel = targetVel; + addRequirements(m_shooter); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + m_shooter.runDrumShooterVelocityPID(m_shooter.m_shooterFalcon, m_targetVel); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc4388/robot/subsystems/Shooter.java b/src/main/java/frc4388/robot/subsystems/Shooter.java index 934cbae..8e7cd9c 100644 --- a/src/main/java/frc4388/robot/subsystems/Shooter.java +++ b/src/main/java/frc4388/robot/subsystems/Shooter.java @@ -8,6 +8,7 @@ package frc4388.robot.subsystems; import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.TalonFXControlMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -16,7 +17,7 @@ import frc4388.robot.Constants.ShooterConstants; public class Shooter extends SubsystemBase { - WPI_TalonFX m_shooterFalcon = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_ID); + public WPI_TalonFX m_shooterFalcon = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_ID); public static Gains m_shooterGains = ShooterConstants.SHOOTER_GAINS;