diff --git a/src/main/deploy/songs/Africa.chrp b/src/main/deploy/songs/Africa.chrp new file mode 100644 index 0000000..b4c63a1 Binary files /dev/null and b/src/main/deploy/songs/Africa.chrp differ diff --git a/src/main/deploy/songs/Believer.chrp b/src/main/deploy/songs/Believer.chrp new file mode 100644 index 0000000..03c5e18 Binary files /dev/null and b/src/main/deploy/songs/Believer.chrp differ diff --git a/src/main/deploy/songs/Big Brother.chrp b/src/main/deploy/songs/Big Brother.chrp new file mode 100644 index 0000000..1129a8d Binary files /dev/null and b/src/main/deploy/songs/Big Brother.chrp differ diff --git a/src/main/deploy/songs/Bonetrousle.chrp b/src/main/deploy/songs/Bonetrousle.chrp new file mode 100644 index 0000000..d9b1951 Binary files /dev/null and b/src/main/deploy/songs/Bonetrousle.chrp differ diff --git a/src/main/deploy/songs/Cotton Eye Joe.chrp b/src/main/deploy/songs/Cotton Eye Joe.chrp new file mode 100644 index 0000000..18e8bd4 Binary files /dev/null and b/src/main/deploy/songs/Cotton Eye Joe.chrp differ diff --git a/src/main/deploy/songs/Country Roads.chrp b/src/main/deploy/songs/Country Roads.chrp new file mode 100644 index 0000000..1434c29 Binary files /dev/null and b/src/main/deploy/songs/Country Roads.chrp differ diff --git a/src/main/deploy/songs/Duel of the Fates.chrp b/src/main/deploy/songs/Duel of the Fates.chrp new file mode 100644 index 0000000..c09ee54 Binary files /dev/null and b/src/main/deploy/songs/Duel of the Fates.chrp differ diff --git a/src/main/deploy/songs/Epic Sax.chrp b/src/main/deploy/songs/Epic Sax.chrp new file mode 100644 index 0000000..440bf5d Binary files /dev/null and b/src/main/deploy/songs/Epic Sax.chrp differ diff --git a/src/main/deploy/songs/Gourmet Race.chrp b/src/main/deploy/songs/Gourmet Race.chrp new file mode 100644 index 0000000..f0740c8 Binary files /dev/null and b/src/main/deploy/songs/Gourmet Race.chrp differ diff --git a/src/main/deploy/songs/Halo.chrp b/src/main/deploy/songs/Halo.chrp new file mode 100644 index 0000000..8653ccb Binary files /dev/null and b/src/main/deploy/songs/Halo.chrp differ diff --git a/src/main/deploy/songs/Hello World.chrp b/src/main/deploy/songs/Hello World.chrp new file mode 100644 index 0000000..339e4f4 Binary files /dev/null and b/src/main/deploy/songs/Hello World.chrp differ diff --git a/src/main/deploy/songs/HesAPirate.chrp b/src/main/deploy/songs/HesAPirate.chrp new file mode 100644 index 0000000..a4b4c92 Binary files /dev/null and b/src/main/deploy/songs/HesAPirate.chrp differ diff --git a/src/main/deploy/songs/Lone Digger.chrp b/src/main/deploy/songs/Lone Digger.chrp new file mode 100644 index 0000000..f4e1eb7 Binary files /dev/null and b/src/main/deploy/songs/Lone Digger.chrp differ diff --git a/src/main/deploy/songs/MEGALOVANIA.chrp b/src/main/deploy/songs/MEGALOVANIA.chrp new file mode 100644 index 0000000..d26c9f1 Binary files /dev/null and b/src/main/deploy/songs/MEGALOVANIA.chrp differ diff --git a/src/main/deploy/songs/Mii Plaza.chrp b/src/main/deploy/songs/Mii Plaza.chrp new file mode 100644 index 0000000..186e536 Binary files /dev/null and b/src/main/deploy/songs/Mii Plaza.chrp differ diff --git a/src/main/deploy/songs/Number One.chrp b/src/main/deploy/songs/Number One.chrp new file mode 100644 index 0000000..948433c Binary files /dev/null and b/src/main/deploy/songs/Number One.chrp differ diff --git a/src/main/deploy/songs/Sweden.chrp b/src/main/deploy/songs/Sweden.chrp new file mode 100644 index 0000000..3a0b5d9 Binary files /dev/null and b/src/main/deploy/songs/Sweden.chrp differ diff --git a/src/main/deploy/songs/TJ-WNPC.chrp b/src/main/deploy/songs/TJ-WNPC.chrp new file mode 100644 index 0000000..30f78af Binary files /dev/null and b/src/main/deploy/songs/TJ-WNPC.chrp differ diff --git a/src/main/deploy/songs/Take On Me.chrp b/src/main/deploy/songs/Take On Me.chrp new file mode 100644 index 0000000..a5aaa05 Binary files /dev/null and b/src/main/deploy/songs/Take On Me.chrp differ diff --git a/src/main/deploy/songs/The Wolf.chrp b/src/main/deploy/songs/The Wolf.chrp new file mode 100644 index 0000000..3c00ae7 Binary files /dev/null and b/src/main/deploy/songs/The Wolf.chrp differ diff --git a/src/main/deploy/songs/Through the Fire and Flames.chrp b/src/main/deploy/songs/Through the Fire and Flames.chrp new file mode 100644 index 0000000..8a97919 Binary files /dev/null and b/src/main/deploy/songs/Through the Fire and Flames.chrp differ diff --git a/src/main/deploy/songs/VA Main Theme.chrp b/src/main/deploy/songs/VA Main Theme.chrp new file mode 100644 index 0000000..ca3e07b Binary files /dev/null and b/src/main/deploy/songs/VA Main Theme.chrp differ diff --git a/src/main/deploy/songs/Wet Hands.chrp b/src/main/deploy/songs/Wet Hands.chrp new file mode 100644 index 0000000..98a5837 Binary files /dev/null and b/src/main/deploy/songs/Wet Hands.chrp differ diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 1d51df2..1600ab1 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -29,11 +29,11 @@ public final class Constants { /* PID Constants Drive*/ public static final int DRIVE_TIMEOUT_MS = 30; public static final Gains DRIVE_DISTANCE_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 0.3); - public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.0, 0.0, 0.0, 0.1, 0, 1.0); - public static final Gains DRIVE_TURNING_GAINS = new Gains(0.4, 0.0, 0.0, 0.0, 0, 0.3); + public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.1, 0.0, 0.0, 0.1, 0, 1.0); + public static final Gains DRIVE_TURNING_GAINS = new Gains(0.4, 0.0, 0.0, 0.0, 0, 0.5); public static final Gains DRIVE_MOTION_MAGIC_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 1.0); - public static final int DRIVE_CRUISE_VELOCITY = 2000; - public static final int DRIVE_ACCELERATION = 1000; + public static final int DRIVE_CRUISE_VELOCITY = 20000; + public static final int DRIVE_ACCELERATION = 7000; /* Remote Sensors */ public final static int REMOTE_0 = 0; @@ -66,24 +66,30 @@ public final class Constants { } public static final class IntakeConstants { - public static final int INTAKE_SPARK_ID = 9; - public static final int EXTENDER_SPARK_ID = 10; + public static final int INTAKE_SPARK_ID = -9; + public static final int EXTENDER_SPARK_ID = -10; } public static final class ShooterConstants { + /* Motor IDs */ public static final int SHOOTER_FALCON_ID = 8; + public static final int SHOOTER_ANGLE_ADJUST_ID = 9; + public static final int SHOOTER_ROTATE_ID = 10; /* PID Constants Shooter */ public static final int SHOOTER_SLOT_IDX = 0; public static final int SHOOTER_PID_LOOP_IDX = 1; public static final int SHOOTER_TIMEOUT_MS = 30; - public static final Gains SHOOTER_GAINS = new Gains(0.4, 0.0005, 13, 0.05, 0, 1.0); - + public static final Gains DRUM_SHOOTER_GAINS = new Gains(0.4, 0.0005, 13, 0.05, 0, 1.0); + public static final Gains SHOOTER_TURRET_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 1.0); + public static final double SHOOTER_TURRET_MIN = -1.0; public static final double ENCODER_TICKS_PER_REV = 2048; + public static final double NEO_UNITS_PER_REV = 42; + public static final double DEGREES_PER_ROT = 360; } public static final class ClimberConstants { - public static final int CLIMBER_SPARK_ID = 10; + public static final int CLIMBER_SPARK_ID = -1; } public static final class LevelerConstants { @@ -91,13 +97,30 @@ public final class Constants { } public static final class StorageConstants { - public static final int STORAGE_CAN_ID = -1; + public static final int STORAGE_CAN_ID = 10; + + /* Ball Indexes */ public static final int BEAM_SENSOR_DIO_0 = 0; public static final int BEAM_SENSOR_DIO_1 = 1; public static final int BEAM_SENSOR_DIO_2 = 2; public static final int BEAM_SENSOR_DIO_3 = 3; public static final int BEAM_SENSOR_DIO_4 = 4; public static final int BEAM_SENSOR_DIO_5 = 5; + + /* PID Values */ + public static final int SLOT_DISTANCE = 0; + + /* PID Indexes */ + public static final int PID_PRIMARY = 0; + + /* PID Gains */ + public static final double storP = 0.1; + public static final double storI = 1e-4; + public static final double storD = 1.0; + public static final double storIz = 0.0; + public static final double storF = 0.0; + public static final double storkmaxOutput = 1.0; + public static final double storkminOutput = -1.0; } public static final class LEDConstants { diff --git a/src/main/java/frc4388/robot/Gains.java b/src/main/java/frc4388/robot/Gains.java index b2f1de2..7d2b3d7 100644 --- a/src/main/java/frc4388/robot/Gains.java +++ b/src/main/java/frc4388/robot/Gains.java @@ -17,6 +17,8 @@ public class Gains { public double m_kF; public int m_kIzone; public double m_kPeakOutput; + public double m_kmaxOutput; + public double m_kminOutput; /** * Creates Gains object for PIDs diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 26c9ac9..f96cc57 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -17,6 +17,9 @@ import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc4388.robot.Constants.*; import frc4388.robot.commands.DriveStraightAtVelocityPID; import frc4388.robot.commands.DriveWithJoystick; +import frc4388.robot.commands.DriveStraightToPositionMM; +import frc4388.robot.commands.DriveStraightToPositionPID; +import frc4388.robot.commands.DriveWithJoystickUsingDeadAssistPID; import frc4388.robot.commands.RunClimberWithTriggers; import frc4388.robot.commands.RunExtenderOutIn; import frc4388.robot.commands.RunIntakeWithTriggers; @@ -71,7 +74,7 @@ public class RobotContainer { /* Default Commands */ // drives the robot with a two-axis input from the driver controller - m_robotDrive.setDefaultCommand(new DriveWithJoystick(m_robotDrive, getDriverController())); + m_robotDrive.setDefaultCommand(new DriveWithJoystickUsingDeadAssistPID(m_robotDrive, getDriverController())); // drives intake with input from triggers on the opperator controller m_robotIntake.setDefaultCommand(new RunIntakeWithTriggers(m_robotIntake, getOperatorController())); // drives climber with input from triggers on the opperator controller @@ -79,11 +82,13 @@ public class RobotContainer { // continually sends updates to the Blinkin LED controller to keep the lights on m_robotLED.setDefaultCommand(new RunCommand(() -> m_robotLED.updateLED(), m_robotLED)); // runs the drum shooter in idle mode - m_robotShooter.setDefaultCommand(new RunCommand(() -> m_robotShooter.runDrumShooter(0.15), m_robotShooter)); + + + m_robotShooter.setDefaultCommand(new RunCommand(() -> m_robotShooter.runShooterWithInput(m_operatorXbox), m_robotShooter)); // drives the leveler with an axis input from the driver controller - m_robotLeveler.setDefaultCommand(new RunLevelerWithJoystick(m_robotLeveler, getDriverController())); + // m_robotLeveler.setDefaultCommand(new RunLevelerWithJoystick(m_robotLeveler, getDriverController())); // runs storage motor at 50 percent - m_robotStorage.setDefaultCommand(new RunCommand(() -> m_robotStorage.runStorage(0.0), m_robotStorage)); + // m_robotStorage.setDefaultCommand(new RunCommand(() -> m_robotStorage.runStorage(0.0), m_robotStorage)); } /** @@ -94,11 +99,8 @@ public class RobotContainer { */ private void configureButtonBindings() { /* Driver Buttons */ - // test command to spin the robot while pressing A on the driver controller new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON) - .whileHeld(() -> m_robotDrive.driveWithInput(0, 1), m_robotDrive); - //new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON) - // .whenPressed(new DriveStraightToPositionPID(m_robotDrive, 36)); + .whenPressed(new DriveStraightToPositionPID(m_robotDrive, 144)); /* Operator Buttons */ // activates "Lit Mode" @@ -114,15 +116,24 @@ public class RobotContainer { new JoystickButton(getOperatorJoystick(), XboxController.LEFT_BUMPER_BUTTON) .whenPressed(new RunExtenderOutIn(m_robotIntake)); + /* PID Test Command */ // runs velocity PID while driving straight new JoystickButton(getDriverJoystick(), XboxController.B_BUTTON) .whenPressed(new DriveStraightAtVelocityPID(m_robotDrive, 500)) .whenReleased(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive)); + + //new JoystickButton(getDriverJoystick(), XboxController.RIGHT_BUMPER_BUTTON) + // .whileHeld(new DriveWithJoystickAuxPID(m_robotDrive, getDriverController())); // resets the yaw of the pigeon new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON) - .whenPressed(new InstantCommand(() -> m_robotDrive.resetGyroYaw(), m_robotDrive)); + .whenPressed(new DriveStraightToPositionMM(m_robotDrive, 72)); + + // turn 45 degrees + new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) + .whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(45), m_robotDrive)); + // sets solenoids into high gear new JoystickButton(getDriverJoystick(), XboxController.START_BUTTON) @@ -135,6 +146,10 @@ public class RobotContainer { // interrupts any running command new JoystickButton(getDriverJoystick(), XboxController.LEFT_JOYSTICK_BUTTON) .whenPressed(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive)); + + /* Storage Neo PID Test */ + new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON) + .whileHeld(new RunCommand(() -> m_robotStorage.runStoragePositionPID(0.5, 0.2, 0.0, 0.0, 0.0, 0.0, 1, -1))); } /** diff --git a/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java b/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java new file mode 100644 index 0000000..259c571 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java @@ -0,0 +1,70 @@ +/*----------------------------------------------------------------------------*/ +/* 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.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc4388.robot.Constants.DriveConstants; +import frc4388.robot.subsystems.Drive; + +public class DriveStraightToPositionMM extends CommandBase { + Drive m_drive; + double m_targetPosIn; + double m_targetPosOut; + double m_targetGyro; + boolean isGoneFast; + + /** + * Creates a new DriveToDistancePID. + * @param subsystem drive subsystem + * @param targetPos distance to travel in inches + */ + public DriveStraightToPositionMM(Drive subsystem, double targetPos) { + // Use addRequirements() here to declare subsystem dependencies. + m_drive = subsystem; + m_targetPosIn = targetPos * DriveConstants.TICKS_PER_INCH; + addRequirements(m_drive); + //SmartDashboard.putNumber("Distance Target Inches", targetPos); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + System.err.println("PID START \n | \n |"); + m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + m_targetPosOut = m_targetPosIn + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY); + isGoneFast = false; + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + //System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); + //System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); + //System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); + m_drive.runMotionMagicPID(m_targetPosOut, m_targetGyro); + } + + // 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() { + if (Math.abs((int)m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY)) < 5 && isGoneFast){ + return true; + } else { + if (m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY) > 100) { + isGoneFast = true; + } + return false; + } + } +} diff --git a/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java b/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java index 67d78b3..0b9b998 100644 --- a/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java +++ b/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java @@ -14,8 +14,10 @@ import frc4388.robot.subsystems.Drive; public class DriveStraightToPositionPID extends CommandBase { Drive m_drive; - double m_targetPos; + double m_targetPosIn; + double m_targetPosOut; double m_targetGyro; + int i; /** * Creates a new DriveToDistancePID. @@ -25,22 +27,27 @@ public class DriveStraightToPositionPID extends CommandBase { public DriveStraightToPositionPID(Drive subsystem, double targetPos) { // Use addRequirements() here to declare subsystem dependencies. m_drive = subsystem; - m_targetPos = targetPos * DriveConstants.TICKS_PER_INCH; + m_targetPosIn = targetPos * DriveConstants.TICKS_PER_INCH; addRequirements(m_drive); - SmartDashboard.putNumber("Distance Target Inches", targetPos); + //SmartDashboard.putNumber("Distance Target Inches", targetPos); } // Called when the command is initially scheduled. @Override public void initialize() { + //System.err.println("PID START \n | \n |"); m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + m_targetPosOut = m_targetPosIn + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY); + i = 0; } // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - //System.err.println(m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); - m_drive.runDriveStraightPositionPID(m_targetPos, m_targetGyro); + //System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); + //System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); + //System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_PRIMARY)); + m_drive.runDriveStraightPositionPID(m_targetPosOut, m_targetGyro); } // Called once the command ends or is interrupted. @@ -51,9 +58,11 @@ public class DriveStraightToPositionPID extends CommandBase { // Returns true when the command should end. @Override public boolean isFinished() { - if (Math.abs(m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() - m_targetPos) < 500){ + if (Math.abs((int)m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY)) < 5 && i > 5){ return true; } else { + i++; + //System.err.println(i); return false; } } diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickAuxPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickAuxPID.java new file mode 100644 index 0000000..2531847 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickAuxPID.java @@ -0,0 +1,79 @@ +/*----------------------------------------------------------------------------*/ +/* 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 com.ctre.phoenix.motorcontrol.TalonFXControlMode; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpiutil.math.MathUtil; +import frc4388.robot.Constants.DriveConstants; +import frc4388.robot.subsystems.Drive; +import frc4388.utility.controller.IHandController; + +public class DriveWithJoystickAuxPID extends CommandBase { + Drive m_drive; + double m_targetGyro; + long lastTime; + IHandController m_controller; + + /** + * Creates a new DriveWithJoystickAuxPID. + */ + public DriveWithJoystickAuxPID(Drive subsystem, IHandController controller) { + // Use addRequirements() here to declare subsystem dependencies. + m_drive = subsystem; + m_controller = controller; + addRequirements(m_drive); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + lastTime = System.currentTimeMillis(); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + double currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + double moveInput = m_controller.getLeftYAxis(); + double steerInput = m_controller.getRightXAxis(); + double moveOutput = 0; + long deltaTime = System.currentTimeMillis() - lastTime; + lastTime = System.currentTimeMillis(); + if (moveInput >= 0){ + moveOutput = -Math.cos(1.571*moveInput)+1; + } else { + moveOutput = Math.cos(1.571*moveInput)-1; + } + + m_targetGyro += 2 * steerInput * deltaTime; + + m_targetGyro = MathUtil.clamp(m_targetGyro, + currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4), + currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/4)); + + m_drive.driveWithInputAux(moveOutput, m_targetGyro); + + System.err.println("Target: " + m_targetGyro); + System.err.println("Current: " + currentGyro); + System.err.println(); + } + + // 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/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java new file mode 100644 index 0000000..0a7938e --- /dev/null +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -0,0 +1,114 @@ +/*----------------------------------------------------------------------------*/ +/* 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 edu.wpi.first.wpiutil.math.MathUtil; +import frc4388.robot.Constants.DriveConstants; +import frc4388.robot.subsystems.Drive; +import frc4388.utility.controller.IHandController; + +public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { + Drive m_drive; + double m_targetGyro; + long lastTime; + IHandController m_controller; + boolean isAuxPIDEnabled = false; + + /** + * Creates a new DriveWithJoystickUsingDeadAssistPID to control the drivetrain with an Xbox controller. + * Applies a curved ramp to the input from the controllers to make the robot less "touchy". + * Also uses PIDs to keep the robot on course when given a "dead" or 0 input. + * @param subsystem pass the Drive subsystem from {@link frc4388.robot.RobotContainer#RobotContainer() RobotContainer} + * @param controller pass the Driver {@link frc4388.utility.controller.IHandController#getClass() IHandController} using the + * {@link frc4388.robot.RobotContainer#getDriverJoystick() getDriverJoystick()} method in + * {@link frc4388.robot.RobotContainer#RobotContainer() RobotContainer} + */ + public DriveWithJoystickUsingDeadAssistPID(Drive subsystem, IHandController controller) { + // Use addRequirements() here to declare subsystem dependencies. + m_drive = subsystem; + m_controller = controller; + addRequirements(m_drive); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + lastTime = System.currentTimeMillis(); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + double currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + double moveInput = m_controller.getLeftYAxis(); + double steerInput = m_controller.getRightXAxis(); + double moveOutput = 0; + double steerOutput = 0; + long deltaTime = System.currentTimeMillis() - lastTime; + lastTime = System.currentTimeMillis(); + + /* If AuxPID is enabled, then update using the steer input */ + if (isAuxPIDEnabled) { + m_targetGyro += 2 * steerInput * deltaTime; + + m_targetGyro = MathUtil.clamp( m_targetGyro, + currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4), + currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/4)); + } + /* Otherwise set target angle to current angle (prevents buildup of gyro error) */ + else { + m_targetGyro = currentGyro; + } + + /* If move stick is being used */ + if (moveInput != 0) { + /* Curves the moveInput to be slightly more gradual at first */ + if (moveInput >= 0) { + moveOutput = -Math.cos(1.571*moveInput)+1; + } else { + moveOutput = Math.cos(1.571*moveInput)-1; + } + + /* If steer stick is being used. */ + if (steerInput != 0) { + double cosMultiplier = .45; + double deadzone = .2; + /* Curves the steer output to be similarily gradual */ + if (steerInput > 0){ + steerOutput = -cosMultiplier*Math.cos(1.571*steerInput)+(cosMultiplier+deadzone); + } else { + steerOutput = cosMultiplier*Math.cos(1.571*steerInput)-(cosMultiplier+deadzone); + } + m_drive.driveWithInput(moveOutput, steerOutput); + isAuxPIDEnabled = false; + } + /* If only the move stick is being used */ + else { + m_drive.driveWithInputAux(moveOutput, m_targetGyro); + isAuxPIDEnabled = true; + } + } + /* If the move stick is not being used */ + else { + m_drive.runDriveStraightVelocityPID(0, m_targetGyro); + isAuxPIDEnabled = true; + } + } + + // 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/commands/PlaySongDrive.java b/src/main/java/frc4388/robot/commands/PlaySongDrive.java new file mode 100644 index 0000000..5e0e6b4 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/PlaySongDrive.java @@ -0,0 +1,52 @@ +/*----------------------------------------------------------------------------*/ +/* 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.Drive; + +public class PlaySongDrive extends CommandBase { + private Drive m_drive; + + /** + * Creates a new PlaySongDrive. + */ + public PlaySongDrive(Drive subsystem) { + // Use addRequirements() here to declare subsystem dependencies. + m_drive = subsystem; + addRequirements(m_drive); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + m_drive.m_rightFrontMotor.set(0); + m_drive.m_leftFrontMotor.set(0); + m_drive.m_rightBackMotor.set(0); + m_drive.m_leftBackMotor.set(0); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + m_drive.playSong(); + //System.err.println("Playing " + m_drive.m_orchestra.isPlaying()); + //m_drive.m_driveTrain.feedWatchdog(); + } + + // 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/Climber.java b/src/main/java/frc4388/robot/subsystems/Climber.java index 6b35036..e878d85 100644 --- a/src/main/java/frc4388/robot/subsystems/Climber.java +++ b/src/main/java/frc4388/robot/subsystems/Climber.java @@ -10,6 +10,7 @@ package frc4388.robot.subsystems; import com.revrobotics.CANDigitalInput; import com.revrobotics.CANSparkMax; import com.revrobotics.CANDigitalInput.LimitSwitchPolarity; +import com.revrobotics.CANSparkMax.IdleMode; import com.revrobotics.CANSparkMaxLowLevel.MotorType; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -17,18 +18,20 @@ import frc4388.robot.Constants.ClimberConstants; public class Climber extends SubsystemBase { CANSparkMax m_climberMotor = new CANSparkMax(ClimberConstants.CLIMBER_SPARK_ID, MotorType.kBrushless); - CANDigitalInput m_forwardLimit, m_reverseLimit; + CANDigitalInput m_climberForwardLimit, m_climberReverseLimit; /** * Creates a new Climber. */ public Climber() { m_climberMotor.restoreFactoryDefaults(); - - m_forwardLimit = m_climberMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyClosed); - m_reverseLimit = m_climberMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyClosed); - m_forwardLimit.enableLimitSwitch(false); - m_reverseLimit.enableLimitSwitch(false); + m_climberMotor.setIdleMode(IdleMode.kBrake); + m_climberMotor.setInverted(false); + + m_climberForwardLimit = m_climberMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyClosed); + m_climberReverseLimit = m_climberMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyClosed); + m_climberForwardLimit.enableLimitSwitch(false); + m_climberReverseLimit.enableLimitSwitch(false); } @Override diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 35db61c..c6fa789 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -7,6 +7,17 @@ package frc4388.robot.subsystems; +import java.io.File; +import java.io.FilenameFilter; +import java.io.IOException; +import java.nio.file.Files; +import java.nio.file.Path; +import java.nio.file.Paths; +import java.util.ArrayList; +import java.util.List; +import java.util.stream.Collectors; +import java.util.stream.Stream; +import com.ctre.phoenix.motorcontrol.ControlMode; import com.ctre.phoenix.motorcontrol.DemandType; import com.ctre.phoenix.motorcontrol.FeedbackDevice; import com.ctre.phoenix.motorcontrol.FollowerType; @@ -17,11 +28,15 @@ import com.ctre.phoenix.motorcontrol.SensorTerm; import com.ctre.phoenix.motorcontrol.StatusFrame; import com.ctre.phoenix.motorcontrol.TalonFXControlMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; +import com.ctre.phoenix.music.Orchestra; import com.ctre.phoenix.sensors.PigeonIMU; import com.ctre.phoenix.sensors.PigeonIMU_StatusFrame; +import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj.DoubleSolenoid; + import edu.wpi.first.wpilibj.drive.DifferentialDrive; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -41,6 +56,7 @@ public class Drive extends SubsystemBase { public WPI_TalonFX m_leftBackMotor = new WPI_TalonFX(DriveConstants.DRIVE_LEFT_BACK_CAN_ID); public WPI_TalonFX m_rightBackMotor = new WPI_TalonFX(DriveConstants.DRIVE_RIGHT_BACK_CAN_ID); public static PigeonIMU m_pigeon = new PigeonIMU(DriveConstants.PIGEON_ID); + public Orchestra m_orchestra = new Orchestra(); public DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor); @@ -50,6 +66,8 @@ public class Drive extends SubsystemBase { public static Gains m_gainsTurning = DriveConstants.DRIVE_TURNING_GAINS; public static Gains m_gainsMotionMagic = DriveConstants.DRIVE_MOTION_MAGIC_GAINS; + SendableChooser m_songChooser = new SendableChooser(); + public DoubleSolenoid speedShift; /** @@ -79,7 +97,7 @@ public class Drive extends SubsystemBase { /* flip input so forward becomes back, etc */ m_leftFrontMotor.setInverted(false); m_rightFrontMotor.setInverted(true); - m_driveTrain.setRightSideInverted(false); + //m_driveTrain.setRightSideInverted(false); m_leftBackMotor.setInverted(InvertType.FollowMaster); m_rightBackMotor.setInverted(InvertType.FollowMaster); @@ -104,6 +122,15 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.config_kD(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_MOTION_MAGIC, DriveConstants.PID_PRIMARY); + m_rightFrontMotor.config_kF(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.config_kP(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.config_kI(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.config_kD(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configMotionCruiseVelocity(DriveConstants.DRIVE_CRUISE_VELOCITY, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configMotionAcceleration(DriveConstants.DRIVE_ACCELERATION, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configMotionSCurveStrength(0, DriveConstants.DRIVE_TIMEOUT_MS); + /* Setup Sensors for WPI_TalonFXs */ m_leftFrontMotor.setSelectedSensorPosition(0, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.setSelectedSensorPosition(0, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS); @@ -134,8 +161,8 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.configSensorTerm(SensorTerm.Sum1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); /* Diff Signal */ - m_rightFrontMotor.configSensorTerm(SensorTerm.Diff0, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configSensorTerm(SensorTerm.Diff1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSensorTerm(SensorTerm.Diff1, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSensorTerm(SensorTerm.Diff0, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); /* Configure Sum [Sum of both QuadEncoders] to be used for Primary PID Index */ m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.SensorDifference, @@ -225,8 +252,22 @@ public class Drive extends SubsystemBase { * true means talon's local output is PID0 - PID1, and other side Talon is PID0 + PID1 */ m_rightFrontMotor.configAuxPIDPolarity(false, DriveConstants.DRIVE_TIMEOUT_MS); + + m_orchestra.addInstrument(m_leftBackMotor); + m_orchestra.addInstrument(m_rightFrontMotor); + m_orchestra.addInstrument(m_rightBackMotor); + m_orchestra.addInstrument(m_leftFrontMotor); + + File songsDir = new File(Filesystem.getDeployDirectory().getAbsolutePath() + "/songs"); + System.err.println(songsDir.getPath()); + String[] songsStrings = songsDir.list(); + for (String songString : songsStrings){ + m_songChooser.addOption(songString, songsDir.getAbsolutePath() + "/" + songString); + } + Shuffleboard.getTab("Songs").add(m_songChooser); } + String currentSong = ""; @Override public void periodic() { try { @@ -254,6 +295,11 @@ public class Drive extends SubsystemBase { SmartDashboard.putNumber("PID 0 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); SmartDashboard.putNumber("PID 1 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); + if (currentSong != m_songChooser.getSelected()){ + currentSong = m_songChooser.getSelected(); + selectSong(currentSong); + System.err.println(currentSong); + } } catch (Exception e) { System.err.println("Error in the Drive Subsystem"); //e.printStackTrace(System.err); @@ -319,14 +365,29 @@ public class Drive extends SubsystemBase { } /** - * Add your docs here. + * Runs percent output control on the moving and steering of the drive train, + * using the Differential Drive class to manage the two inputs */ public void driveWithInput(double move, double steer){ - m_driveTrain.arcadeDrive(move, steer); + //m_driveTrain.arcadeDrive(move, steer); } /** - * Runs a position PID while driving straight (has not been tested) + * Runs percent output control on the drive train while using an AUX PID for rotation + * @param targetPos The position to drive to in units + * @param targetGyro The angle to drive at in units + */ + public void driveWithInputAux(double move, double targetGyro) { + m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); + + m_rightFrontMotor.set(TalonFXControlMode.PercentOutput, move, DemandType.AuxPID, targetGyro); + m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); + + m_driveTrain.feedWatchdog(); + } + + /** + * Runs a position PID while driving straight * @param targetPos The position to drive to in units * @param targetGyro The angle to drive at in units */ @@ -334,11 +395,10 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - targetPos *= 2; m_rightFrontMotor.set(TalonFXControlMode.Position, targetPos, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); - m_driveTrain.feedWatchdog(); + //m_driveTrain.feedWatchdog(); } /** @@ -349,27 +409,26 @@ public class Drive extends SubsystemBase { public void runDriveStraightVelocityPID(double targetVel, double targetGyro) { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - - targetVel *= 2; m_rightFrontMotor.set(TalonFXControlMode.Velocity, targetVel, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); - m_driveTrain.feedWatchdog(); + //m_driveTrain.feedWatchdog(); } /** - * Runs motion magic PID while driving straight (has not been tested) + * Runs motion magic PID while driving straight * @param targetPos The position to drive to in units * @param targetGyro The angle to drive at in units */ public void runMotionMagicPID(double targetPos, double targetGyro){ m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_MOTION_MAGIC, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - - m_rightFrontMotor.set(TalonFXControlMode.MotionMagic, targetPos, DemandType.AuxPID, targetGyro); + + m_rightFrontMotor.set(ControlMode.MotionMagic, targetPos, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); - + m_driveTrain.feedWatchdog(); + } /** @@ -420,6 +479,21 @@ public class Drive extends SubsystemBase { m_pigeon.setAccumZAngle(0); } + /** + * Plays Music! + */ + public void playSong() { + m_orchestra.play(); + } + + /** + * Selects a song to play! + * @param song The name of the song to be played + */ + public void selectSong(String song) { + SmartDashboard.putString("Selected Song", song); + m_orchestra.loadMusic(song); + } /** * Set to high or low gear based on boolean state, true = high, false = low * @param state Chooses between high or low gear diff --git a/src/main/java/frc4388/robot/subsystems/Leveler.java b/src/main/java/frc4388/robot/subsystems/Leveler.java index 02df406..aa93f13 100644 --- a/src/main/java/frc4388/robot/subsystems/Leveler.java +++ b/src/main/java/frc4388/robot/subsystems/Leveler.java @@ -26,7 +26,8 @@ public class Leveler extends SubsystemBase { */ public Leveler() { m_levelerMotor.restoreFactoryDefaults(); - m_levelerMotor.setIdleMode(IdleMode.kCoast); + + m_levelerMotor.setIdleMode(IdleMode.kBrake); m_levelerMotor.setInverted(false); } diff --git a/src/main/java/frc4388/robot/subsystems/Shooter.java b/src/main/java/frc4388/robot/subsystems/Shooter.java index 169e36f..c072a8f 100644 --- a/src/main/java/frc4388/robot/subsystems/Shooter.java +++ b/src/main/java/frc4388/robot/subsystems/Shooter.java @@ -11,28 +11,56 @@ import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.TalonFXControlMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; +import com.revrobotics.CANSparkMax; +import com.revrobotics.CANSparkMax.IdleMode; +import com.revrobotics.CANEncoder; +import com.revrobotics.CANPIDController; +import com.revrobotics.ControlType; +import com.revrobotics.CANSparkMaxLowLevel.MotorType; + +import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc4388.robot.Gains; -import frc4388.robot.Constants.DriveConstants; import frc4388.robot.Constants.ShooterConstants; +import frc4388.utility.controller.IHandController; public class Shooter extends SubsystemBase { public WPI_TalonFX m_shooterFalcon = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_ID); + public CANSparkMax m_angleAdjustMotor = new CANSparkMax(ShooterConstants.SHOOTER_ANGLE_ADJUST_ID, MotorType.kBrushless); + public CANSparkMax m_shooterRotateMotor = new CANSparkMax(ShooterConstants.SHOOTER_ROTATE_ID, MotorType.kBrushless); - public static Gains m_shooterGains = ShooterConstants.SHOOTER_GAINS; + + public static Gains m_shooterTurretGains = ShooterConstants.SHOOTER_TURRET_GAINS; + public static Gains m_drumShooterGains = ShooterConstants.DRUM_SHOOTER_GAINS; + public static Shooter m_shooter; + public static IHandController m_controller; + + + // Configure PID Controllers + CANPIDController m_angleAdjustPIDController = m_angleAdjustMotor.getPIDController(); + CANPIDController m_shooterRotatePIDController = m_shooterRotateMotor.getPIDController(); + + CANEncoder m_angleEncoder = m_angleAdjustMotor.getEncoder(); + CANEncoder m_shooterRotateEncoder = m_shooterRotateMotor.getEncoder(); double velP; - /** + double input; + + /* * Creates a new Shooter subsystem. */ public Shooter() { + //Testing purposes reseting gyros + resetGyroAngleAdj(); + resetGyroShooterRotate(); + m_shooterFalcon.configFactoryDefault(); - + m_shooterRotateMotor.setIdleMode(IdleMode.kBrake); m_shooterFalcon.setNeutralMode(NeutralMode.Coast); - - m_shooterFalcon.setInverted(true); + m_shooterFalcon.setInverted(false); setShooterGains(); @@ -64,10 +92,10 @@ public class Shooter extends SubsystemBase { */ public void setShooterGains() { m_shooterFalcon.selectProfileSlot(ShooterConstants.SHOOTER_SLOT_IDX, ShooterConstants.SHOOTER_PID_LOOP_IDX); - m_shooterFalcon.config_kF(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kF, ShooterConstants.SHOOTER_TIMEOUT_MS); - m_shooterFalcon.config_kP(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kP, ShooterConstants.SHOOTER_TIMEOUT_MS); - m_shooterFalcon.config_kI(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kI, ShooterConstants.SHOOTER_TIMEOUT_MS); - m_shooterFalcon.config_kD(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kD, ShooterConstants.SHOOTER_TIMEOUT_MS); + m_shooterFalcon.config_kF(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterTurretGains.m_kF, ShooterConstants.SHOOTER_TIMEOUT_MS); + m_shooterFalcon.config_kP(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterTurretGains.m_kP, ShooterConstants.SHOOTER_TIMEOUT_MS); + m_shooterFalcon.config_kI(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterTurretGains.m_kI, ShooterConstants.SHOOTER_TIMEOUT_MS); + m_shooterFalcon.config_kD(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterTurretGains.m_kD, ShooterConstants.SHOOTER_TIMEOUT_MS); } /** * Runs drum shooter velocity PID. @@ -87,4 +115,58 @@ public class Shooter extends SubsystemBase { m_shooterFalcon.set(TalonFXControlMode.Velocity, targetVel); //Init PID } } + + + public void runShooterWithInput(IHandController controller) { + m_controller = controller; + input = m_controller.getLeftXAxis(); + System.err.println(input); + m_shooterRotateMotor.set(input); + } + + /* Angle Adjustment PID Control */ + public void runAngleAdjustPID(double targetAngle) + { + // Set PID Coefficients + m_angleAdjustPIDController.setP(m_shooterTurretGains.m_kP); + m_angleAdjustPIDController.setI(m_shooterTurretGains.m_kI); + m_angleAdjustPIDController.setD(m_shooterTurretGains.m_kD); + m_angleAdjustPIDController.setIZone(m_shooterTurretGains.m_kIzone); + m_angleAdjustPIDController.setFF(m_shooterTurretGains.m_kF); + m_angleAdjustPIDController.setOutputRange(ShooterConstants.SHOOTER_TURRET_MIN, m_shooterTurretGains.m_kPeakOutput); + + // Convert input angle in degrees to rotations of the motor + targetAngle = targetAngle/ShooterConstants.DEGREES_PER_ROT; + + m_angleAdjustPIDController.setReference(targetAngle, ControlType.kPosition); + } + + /* Rotate Shooter PID Control */ + public void runshooterRotatePID(double targetAngle) + { + // Set PID Coefficients + m_shooterRotatePIDController.setP(m_shooterTurretGains.m_kP); + m_shooterRotatePIDController.setI(m_shooterTurretGains.m_kI); + m_shooterRotatePIDController.setD(m_shooterTurretGains.m_kD); + m_shooterRotatePIDController.setFF(m_shooterTurretGains.m_kF); + m_shooterRotatePIDController.setIZone(m_shooterTurretGains.m_kIzone); + m_shooterRotatePIDController.setOutputRange(ShooterConstants.SHOOTER_TURRET_MIN, m_shooterTurretGains.m_kPeakOutput); + + // Convert input angle in degrees to rotations of the motor + targetAngle = targetAngle/ShooterConstants.DEGREES_PER_ROT; + + m_shooterRotatePIDController.setReference(targetAngle, ControlType.kPosition); + } + + /* For Testing Purposes, reseting gyro for angle adjuster */ + public void resetGyroAngleAdj() + { + m_angleEncoder.setPosition(0); + } + + /* For Testing Purposes, reseting gyro for shooter rotation */ + public void resetGyroShooterRotate() + { + m_shooterRotateEncoder.setPosition(0); + } } \ No newline at end of file diff --git a/src/main/java/frc4388/robot/subsystems/Storage.java b/src/main/java/frc4388/robot/subsystems/Storage.java index a7d1bfb..790e59e 100644 --- a/src/main/java/frc4388/robot/subsystems/Storage.java +++ b/src/main/java/frc4388/robot/subsystems/Storage.java @@ -9,11 +9,14 @@ package frc4388.robot.subsystems; import com.ctre.phoenix.motorcontrol.can.TalonSRX; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import com.revrobotics.CANEncoder; +import com.revrobotics.CANPIDController; import com.revrobotics.CANSparkMax; +import com.revrobotics.ControlType; import com.revrobotics.SparkMax; import com.revrobotics.CANSparkMaxLowLevel.MotorType; - import edu.wpi.first.wpilibj.DigitalInput; +import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc4388.robot.Constants.StorageConstants; @@ -21,10 +24,17 @@ import frc4388.robot.Constants.StorageConstants; public class Storage extends SubsystemBase { private CANSparkMax m_storageMotor = new CANSparkMax(StorageConstants.STORAGE_CAN_ID, MotorType.kBrushless); private DigitalInput[] m_beamSensors = new DigitalInput[6]; + + CANPIDController m_storagePIDController = m_storageMotor.getPIDController(); + + CANEncoder m_encoder = m_storageMotor.getEncoder(); + /** * Creates a new Storage. */ public Storage() { + resetEncoder(); + m_beamSensors[0] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_0); m_beamSensors[1] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_1); m_beamSensors[2] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_2); @@ -40,17 +50,36 @@ public class Storage extends SubsystemBase { /** * Runs storage motor + * * @param input the voltage to run motor at */ - public void runStorage(double input) { + public void runStorage(final double input) { m_storageMotor.set(input); - boolean beam_on = m_beamSensors[0].get(); + final boolean beam_on = m_beamSensors[0].get(); - if (beam_on) { - System.err.println("Beam on"); - } else { - System.err.println("Beam off"); - } - + } + + public void resetEncoder() + { + m_encoder.setPosition(0); + } + + /* Storage PID Control */ + public void runStoragePositionPID(double targetPos, double kP, double kI, double kD, double kIz, double kF, double kmaxOutput, double kminOutput) + { + // Set PID Coefficients + m_storagePIDController.setP(kP); + m_storagePIDController.setI(kI); + m_storagePIDController.setD(kD); + m_storagePIDController.setIZone(kIz); + m_storagePIDController.setFF(kF); + m_storagePIDController.setOutputRange(kminOutput, kmaxOutput); + + m_storagePIDController.setReference(targetPos, ControlType.kPosition); + } + + public void getEncoderPos() + { + m_encoder.getPosition(); } } diff --git a/vendordeps/WPILibOldCommands.json b/vendordeps/WPILibOldCommands.json new file mode 100644 index 0000000..acc8879 --- /dev/null +++ b/vendordeps/WPILibOldCommands.json @@ -0,0 +1,37 @@ +{ + "fileName": "WPILibOldCommands.json", + "name": "WPILib-Old-Commands", + "version": "2020.0.0", + "uuid": "b066afc2-5c18-43c4-b758-43381fcb275e", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibOldCommands", + "artifactId": "wpilibOldCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibOldCommands", + "artifactId": "wpilibOldCommands-cpp", + "version": "wpilib", + "libName": "wpilibOldCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxaarch64bionic", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} \ No newline at end of file