diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index ed37e62..d7cc270 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -169,9 +169,11 @@ public static final class constShooter { } public static final class constTransfer { - public static final boolean ENTRANCE_WHEEL_INVERTED = true; + public static final boolean BOTTOM_LIMIT_SWITCH_INVERT = true; + public static final boolean TOP_LIMIT_SWITCH_INVERT = true; + } public static final class constTurret { diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index b3da438..ad38576 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.cameraserver.CameraServer; @@ -60,6 +61,8 @@ public void robotPeriodic() { // robot's periodic // block in order for anything in the Command-based framework to work. CommandScheduler.getInstance().run(); + + SmartDashboard.putString("Cargo State", RobotContainer.cargoState.toString()); } /** This function is called once each time the robot enters Disabled mode. */ diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index d35a11d..7645c29 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -70,7 +70,7 @@ public RobotContainer() { subDrivetrain.setDefaultCommand( new RunCommand( () -> subDrivetrain.arcadeDrive( - driveSlewRateLimiter.calculate(conDriver.getArcadeMove()), conDriver.getArcadeRotate()), + driveSlewRateLimiter.calculate(conDriver.getArcadeMove()), -conDriver.getArcadeRotate()), subDrivetrain)); subClimber.setDefaultCommand(comMoveClimber); @@ -123,7 +123,7 @@ private void configureButtonBindings() { conOperator.btn_RTrig .whileTrue(comShootCargo); - conOperator.btn_RBump.onTrue(new RunCommand(() -> subShooter.setMotorSpeedToGoalSpeed(), subShooter)); + conOperator.btn_RBump.onTrue(new RunCommand(() -> subShooter.setMotorSpeed(1), subShooter)); conOperator.btn_Start.onTrue(new InstantCommand(() -> subShooter.neutralOutput(), subShooter)); // Turret @@ -133,22 +133,32 @@ private void configureButtonBindings() { conOperator.btn_RStick .onTrue(Commands.runOnce(() -> subTurret.setAngle(prefTurret.turretFacingAwayFromIntakeDegrees))); - // Intake + // Hood + conOperator.btn_A.whileTrue(Commands.runOnce(() -> subHood.setSpeed(0.15))) + .onFalse(Commands.runOnce(() -> subHood.setSpeed(0))) + .onFalse(Commands.runOnce(() -> subHood.setAngle(subHood.getAngleDegrees()))); + conOperator.btn_Y.whileTrue(Commands.runOnce(() -> subHood.setSpeed(-0.15))) + .onFalse(Commands.runOnce(() -> subHood.setSpeed(0))) + .onFalse(Commands.runOnce(() -> subHood.setAngle(subHood.getAngleDegrees()))); + // Intake conOperator.btn_LTrig.whileTrue(comCollectCargo); conOperator.btn_B.whileTrue(comDiscardCargo); // Presets conOperator.POV_North - .onTrue(Commands.runOnce(() -> subShooter.setGoalSpeed(prefPreset.presetFenderShooterSpeed))) + // .onTrue(Commands.runOnce(() -> + // subShooter.setGoalSpeed(prefPreset.presetFenderShooterSpeed))) .onTrue(Commands.runOnce(() -> subHood.setAngle(prefPreset.presetFenderHoodDegrees))); conOperator.POV_South - .onTrue(Commands.runOnce(() -> subShooter.setGoalSpeed(prefPreset.presetLaunchpadShooterSpeed))) + // .onTrue(Commands.runOnce(() -> + // subShooter.setGoalSpeed(prefPreset.presetLaunchpadShooterSpeed))) .onTrue(Commands.runOnce(() -> subHood.setAngle(prefPreset.presetLaunchpadHoodDegrees))); conOperator.POV_West - .onTrue(Commands.runOnce(() -> subShooter.setGoalSpeed(prefPreset.presetTarmacShooterSpeed))) + // .onTrue(Commands.runOnce(() -> + // subShooter.setGoalSpeed(prefPreset.presetTarmacShooterSpeed))) .onTrue(Commands.runOnce(() -> subHood.setAngle(prefPreset.presetTarmacHoodDegrees))); } diff --git a/src/main/java/frc/robot/RobotMap.java b/src/main/java/frc/robot/RobotMap.java index fdc875a..0b7cab0 100644 --- a/src/main/java/frc/robot/RobotMap.java +++ b/src/main/java/frc/robot/RobotMap.java @@ -10,8 +10,8 @@ public static final class mapClimber { public static final int CLIMBER_MOTOR_CAN = 10; public static final int CLIMBER_MINIMUM_SWITCH_DIO = 6; - public static final int CLIMBER_MAXIMUM_SWITCH_DIO = 0; - + public static final int CLIMBER_MAXIMUM_SWITCH_DIO = 9; + // TODO: Physically Plug in Climber Limit Switch } public static final class mapControllers { @@ -34,7 +34,7 @@ public static final class mapHood { public static final int HOOD_MOTOR_CAN = 25; - public static final int HOOD_BOTTOM_SWITCH_DIO = 5; + public static final int HOOD_BOTTOM_SWITCH_DIO = 1; } @@ -57,10 +57,8 @@ public static final class mapTransfer { public static final int BOTTOM_MOTOR_CAN = 51; public static final int TOP_MOTOR_CAN = 52; - public static final int TOP_LEFT_SWITCH_DIO = 4; - public static final int TOP_RIGHT_SWITCH_DIO = 1; - public static final int BOTTOM_RIGHT_SWITCH_DIO = 2; - public static final int BOTTOM_LEFT_SWITCH_DIO = 3; + public static final int TOP_SWITCH_DIO = 2; + public static final int BOTTOM_SWITCH_DIO = 0; } diff --git a/src/main/java/frc/robot/RobotPreferences.java b/src/main/java/frc/robot/RobotPreferences.java index 10d9a95..4766850 100644 --- a/src/main/java/frc/robot/RobotPreferences.java +++ b/src/main/java/frc/robot/RobotPreferences.java @@ -73,19 +73,10 @@ public static final class prefDrivetrain { } public static final class prefHood { - - public static final SN_DoublePreference hoodArbitraryFeedForward = new SN_DoublePreference( - "hoodArbitraryFeedForward", 0.040078); - - public static final SN_DoublePreference hoodP = new SN_DoublePreference("hoodP", 0.09); + public static final SN_DoublePreference hoodP = new SN_DoublePreference("hoodP", 0.05); public static final SN_DoublePreference hoodI = new SN_DoublePreference("hoodI", 0); public static final SN_DoublePreference hoodD = new SN_DoublePreference("hoodD", 0); - public static final SN_DoublePreference hoodAllowableClosedLoopErrorDegrees = new SN_DoublePreference( - "hoodAllowableClosedLoopErrorDegrees", 0.0001); - public static final SN_DoublePreference hoodClosedLoopPeakOutput = new SN_DoublePreference( - "hoodClosedLoopPeakOutput", .25); - public static final SN_DoublePreference hoodMinDegrees = new SN_DoublePreference("hoodMinDegrees", 4.89); public static final SN_DoublePreference hoodMaxDegrees = new SN_DoublePreference("hoodMaxDegrees", 37); @@ -94,9 +85,8 @@ public static final class prefHood { } public static final class prefIntake { - public static final SN_DoublePreference intakeRollerSpeed = new SN_DoublePreference("intakeRollerSpeed", 0.8); - + public static final SN_DoublePreference intakeSpitSpeed = new SN_DoublePreference("intakeSpitSpeed", -0.8); } public static final class prefPreset { @@ -119,17 +109,10 @@ public static final class prefPreset { } public static final class prefShooter { - - public static final SN_DoublePreference shooterF = new SN_DoublePreference("shooterF", 0.04609); - public static final SN_DoublePreference shooterP = new SN_DoublePreference("shooterP", 0.21); - public static final SN_DoublePreference shooterI = new SN_DoublePreference("shooterI", 0.006); - public static final SN_DoublePreference shooterD = new SN_DoublePreference("shooterD", 10); - - public static final SN_DoublePreference shooterIZone = new SN_DoublePreference("shooterIZone", 200); - - public static final SN_DoublePreference shooterClosedLoopRamp = new SN_DoublePreference( - "shooterClosedLoopRamp", 0.2); - + public static final SN_DoublePreference shooterF = new SN_DoublePreference("shooterF", 0); + public static final SN_DoublePreference shooterP = new SN_DoublePreference("shooterP", 1); + public static final SN_DoublePreference shooterI = new SN_DoublePreference("shooterI", 0); + public static final SN_DoublePreference shooterD = new SN_DoublePreference("shooterD", 0); } public static final class prefTransfer { @@ -142,7 +125,6 @@ public static final class prefTransfer { "transferBeltSpeed", 0.5); public static final SN_DoublePreference transferBeltReverseSpeed = new SN_DoublePreference( "transferBeltReverseSpeed", -0.5); - } public static final class prefTurret { @@ -150,9 +132,9 @@ public static final class prefTurret { public static final SN_DoublePreference turretArbitraryFeedForward = new SN_DoublePreference( "turretArbitraryFeedForward", 0.01); - public static final SN_DoublePreference turretP = new SN_DoublePreference("turretP", 0.2); + public static final SN_DoublePreference turretP = new SN_DoublePreference("turretP", 1); public static final SN_DoublePreference turretI = new SN_DoublePreference("turretI", 0); - public static final SN_DoublePreference turretD = new SN_DoublePreference("turretD", 3.4); + public static final SN_DoublePreference turretD = new SN_DoublePreference("turretD", 0); public static final SN_DoublePreference turretAllowableClosedloopErrorDegrees = new SN_DoublePreference( "turretAllowableClosedloopErrorDegrees", 0.5); @@ -161,15 +143,16 @@ public static final class prefTurret { public static final SN_DoublePreference turretOpenLoopSpeed = new SN_DoublePreference("turretOpenLoopSpeed", 0.3); - public static final SN_DoublePreference turretMinDegrees = new SN_DoublePreference("turretMinDegrees", -270); - public static final SN_DoublePreference turretMaxDegrees = new SN_DoublePreference("turretMaxDegrees", 110); + public static final SN_DoublePreference turretMinDegrees = new SN_DoublePreference("turretMinDegrees", 0); + public static final SN_DoublePreference turretMaxDegrees = new SN_DoublePreference("turretMaxDegrees", 360); public static final SN_DoublePreference turretFacingTowardsIntakeDegrees = new SN_DoublePreference( - "turretFacingTowardsIntakeDegrees", -90); + "turretFacingTowardsIntakeDegrees", 270); public static final SN_DoublePreference turretFacingAwayFromIntakeDegrees = new SN_DoublePreference( "turretFacingAwayFromIntakeDegrees", 90); public static final SN_DoublePreference turretClimberThreshold = new SN_DoublePreference( "turretClimberThreshold", -269); + // TODO: Update if we want climber functionality public static final SN_DoublePreference turretDeadzoneSmall = new SN_DoublePreference("turretDeadzoneMin", -205); public static final SN_DoublePreference turretDeadzoneLarge = new SN_DoublePreference("turretDeadzoneMax", 25); diff --git a/src/main/java/frc/robot/commands/Cargo/CollectCargo.java b/src/main/java/frc/robot/commands/Cargo/CollectCargo.java index d71647f..8042b8b 100644 --- a/src/main/java/frc/robot/commands/Cargo/CollectCargo.java +++ b/src/main/java/frc/robot/commands/Cargo/CollectCargo.java @@ -92,13 +92,9 @@ public void execute() { subTransfer.setEntranceWheelSpeed(outputEntrance); subTransfer.setBottomBeltSpeed(outputBottom); subTransfer.setTopBeltSpeed(outputTop); - + subIntake.setRollerSpeed(outputIntake); } - // intake doesn't affect other commands so it gets set regardless of this - // command taking precedence - subIntake.setRollerSpeed(outputIntake); - } @Override diff --git a/src/main/java/frc/robot/commands/Cargo/DiscardCargo.java b/src/main/java/frc/robot/commands/Cargo/DiscardCargo.java index 936c45f..8055521 100644 --- a/src/main/java/frc/robot/commands/Cargo/DiscardCargo.java +++ b/src/main/java/frc/robot/commands/Cargo/DiscardCargo.java @@ -8,6 +8,7 @@ import frc.robot.RobotContainer; import frc.robot.RobotPreferences; import frc.robot.Constants.CargoState; +import frc.robot.RobotPreferences.prefIntake; import frc.robot.RobotPreferences.prefTransfer; import frc.robot.subsystems.Intake; import frc.robot.subsystems.Transfer; @@ -60,12 +61,13 @@ public void execute() { subTransfer.setTopBeltSpeed(prefTransfer.transferBeltReverseSpeed); subTransfer.setBottomBeltSpeed(prefTransfer.transferBeltReverseSpeed); subTransfer.setEntranceWheelSpeed(prefTransfer.transferEntranceReverseSpeed); - + subIntake.setRollerSpeed(prefIntake.intakeSpitSpeed); } } @Override public void end(boolean interrupted) { + subIntake.setRollerSpeed(RobotPreferences.zeroDoublePref); if (precedence) { diff --git a/src/main/java/frc/robot/subsystems/Climber.java b/src/main/java/frc/robot/subsystems/Climber.java index a97a6ab..c48b480 100644 --- a/src/main/java/frc/robot/subsystems/Climber.java +++ b/src/main/java/frc/robot/subsystems/Climber.java @@ -52,7 +52,9 @@ public void setClimberSpeed(double speed) { if ((isMinSwitch() && speed < 0) || (isMaxSwitch() && speed > 0)) { speed = 0; } - climberMotor.set(speed); + // climberMotor.set(speed); + // TODO: Climber Functionality + climberMotor.set(0); } public double getClimberEncoderCounts() { diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java index b9b6d72..95f98a5 100644 --- a/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -223,7 +223,6 @@ public void periodic() { SmartDashboard.putNumber("Drivetrain Right Meters", getRightMeters()); SmartDashboard.putNumber("Drivetrain Heading Degrees", navx.getRotation2d().getDegrees()); - } } } diff --git a/src/main/java/frc/robot/subsystems/Hood.java b/src/main/java/frc/robot/subsystems/Hood.java index 18587ed..fa0c1a0 100644 --- a/src/main/java/frc/robot/subsystems/Hood.java +++ b/src/main/java/frc/robot/subsystems/Hood.java @@ -27,8 +27,9 @@ public class Hood extends SubsystemBase { boolean displayOnDashboard; - public Hood() { + double desiredAngle; + public Hood() { hoodMotor = new CANSparkMax(mapHood.HOOD_MOTOR_CAN, MotorType.kBrushless); bottomSwitch = new DigitalInput(mapHood.HOOD_BOTTOM_SWITCH_DIO); hoodPIDController = hoodMotor.getPIDController(); @@ -48,19 +49,21 @@ public void configure() { hoodMotor.setInverted(constHood.INVERTED); hoodMotor.setIdleMode(IdleMode.kBrake); + hoodMotor.getEncoder().setPositionConversionFactor(360 / constHood.GEAR_RATIO); + hoodMotor.enableSoftLimit(SoftLimitDirection.kForward, true); hoodMotor.setSoftLimit(SoftLimitDirection.kForward, - (float) ((prefHood.hoodMaxDegrees.getValue() / 360) * constHood.GEAR_RATIO)); + (float) prefHood.hoodMaxDegrees.getValue()); hoodMotor.enableSoftLimit(SoftLimitDirection.kReverse, true); hoodMotor.setSoftLimit(SoftLimitDirection.kReverse, - (float) ((prefHood.hoodMinDegrees.getValue() / 360) * constHood.GEAR_RATIO)); + (float) prefHood.hoodMinDegrees.getValue()); resetAngleToBottom(); } public double getAngleDegrees() { - return (hoodMotor.getEncoder().getPosition()) * 360; + return (hoodMotor.getEncoder().getPosition()); } public double getRawAngle() { @@ -70,20 +73,24 @@ public double getRawAngle() { public void setAngle(double a_degrees) { double degrees = MathUtil.clamp(a_degrees, prefHood.hoodMinDegrees.getValue(), prefHood.hoodMaxDegrees.getValue()); - - hoodPIDController.setReference((degrees / 360), CANSparkMax.ControlType.kPosition); + desiredAngle = degrees; + hoodPIDController.setReference(degrees, CANSparkMax.ControlType.kPosition); } public void setAngle(SN_DoublePreference degrees) { setAngle(degrees.getValue()); } + public void setSpeed(double speed) { + hoodMotor.set(speed); + } + public boolean isBottomSwitch() { return !bottomSwitch.get(); } public void resetAngleToBottom() { - hoodMotor.getEncoder().setPosition((prefHood.hoodMinDegrees.getValue()) / 360); + hoodMotor.getEncoder().setPosition(prefHood.hoodMinDegrees.getValue()); } public void neutralOutput() { @@ -104,8 +111,11 @@ public void periodic() { if (displayOnDashboard) { SmartDashboard.putNumber("Hood Angle Degrees", getAngleDegrees()); - SmartDashboard.putNumber("Hood Raw Angle", getRawAngle()); - SmartDashboard.putBoolean("Hood Is Bottom Switch", isBottomSwitch()); + + // SmartDashboard.putNumber("Hood Desired Angle Degrees", desiredAngle); + + // SmartDashboard.putNumber("Hood Raw Angle", getRawAngle()); + // SmartDashboard.putBoolean("Hood Is Bottom Switch", isBottomSwitch()); } diff --git a/src/main/java/frc/robot/subsystems/Intake.java b/src/main/java/frc/robot/subsystems/Intake.java index 282d9ff..f8bc88a 100644 --- a/src/main/java/frc/robot/subsystems/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake.java @@ -16,8 +16,8 @@ public class Intake extends SubsystemBase { TalonSRX roller; - boolean displayOnDashboard; + double desiredPercentOutput = 0; public Intake() { @@ -32,10 +32,10 @@ public void configure() { roller.configFactoryDefault(); roller.setInverted(constIntake.ROLLER_INVERTED); - } public void setRollerSpeed(SN_DoublePreference speed) { + desiredPercentOutput = speed.getValue(); roller.set(ControlMode.PercentOutput, speed.getValue()); } @@ -49,10 +49,10 @@ public void hideValuesOnDashboard() { @Override public void periodic() { - if (displayOnDashboard) { - SmartDashboard.putNumber("Intake Roller Percent Output", roller.getMotorOutputPercent()); + SmartDashboard.putNumber("Intake Roller Desired Percent Output", desiredPercentOutput); + } } diff --git a/src/main/java/frc/robot/subsystems/Shooter.java b/src/main/java/frc/robot/subsystems/Shooter.java index d491700..c18a17b 100644 --- a/src/main/java/frc/robot/subsystems/Shooter.java +++ b/src/main/java/frc/robot/subsystems/Shooter.java @@ -41,11 +41,10 @@ public void configure() { followMotor.restoreFactoryDefaults(); leadMotor.setInverted(constShooter.LEAD_INVERTED); - followMotor.setInverted(constShooter.FOLLOW_INVERTED); leadMotor.setIdleMode(IdleMode.kCoast); - followMotor.follow(leadMotor); + followMotor.follow(leadMotor, true); } public void setMotorSpeed(double speed) { @@ -56,21 +55,21 @@ public void neutralOutput() { leadMotor.set(0); } - public void setGoalSpeed(double goalSpeed) { - this.goalSpeed = goalSpeed; - } + // public void setGoalSpeed(double goalSpeed) { + // this.goalSpeed = goalSpeed; + // } - public void setGoalSpeed(SN_DoublePreference goalSpeed) { - setGoalSpeed(goalSpeed.getValue()); - } + // public void setGoalSpeed(SN_DoublePreference goalSpeed) { + // setGoalSpeed(goalSpeed.getValue()); + // } - public double getGoalSpeed() { - return goalSpeed; - } + // public double getGoalSpeed() { + // return goalSpeed; + // } - public void setMotorSpeedToGoalSpeed() { - setMotorSpeed(getGoalSpeed()); - } + // public void setMotorSpeedToGoalSpeed() { + // setMotorSpeed(getGoalSpeed()); + // } public void displayValuesOnDashboard() { displayOnDashboard = true; @@ -86,7 +85,7 @@ public void periodic() { if (displayOnDashboard) { SmartDashboard.putNumber("Shooter Motor Percent Output", leadMotor.getAppliedOutput()); - SmartDashboard.putNumber("Shooter Goal Speed", getGoalSpeed()); + // SmartDashboard.putNumber("Shooter Goal Speed", getGoalSpeed()); } diff --git a/src/main/java/frc/robot/subsystems/Transfer.java b/src/main/java/frc/robot/subsystems/Transfer.java index 59ec4d9..fb410e3 100644 --- a/src/main/java/frc/robot/subsystems/Transfer.java +++ b/src/main/java/frc/robot/subsystems/Transfer.java @@ -8,36 +8,36 @@ import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.can.TalonSRX; import com.frcteam3255.preferences.SN_DoublePreference; +import com.revrobotics.CANSparkBase.IdleMode; +import com.revrobotics.CANSparkLowLevel.MotorType; +import com.revrobotics.CANSparkMax; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.constTransfer; import frc.robot.RobotMap.mapTransfer; +import frc.robot.RobotPreferences.prefTransfer; public class Transfer extends SubsystemBase { - TalonSRX entranceWheel; + CANSparkMax entranceWheel; TalonSRX bottomBelt; TalonSRX topBelt; - DigitalInput bottomLeftSwitch; - DigitalInput bottomRightSwitch; - DigitalInput topLeftSwitch; - DigitalInput topRightSwitch; + DigitalInput bottomSwitch; + DigitalInput topSwitch; boolean displayOnDashboard; public Transfer() { - entranceWheel = new TalonSRX(mapTransfer.ENTRANCE_MOTOR_CAN); + entranceWheel = new CANSparkMax(mapTransfer.ENTRANCE_MOTOR_CAN, MotorType.kBrushless); bottomBelt = new TalonSRX(mapTransfer.BOTTOM_MOTOR_CAN); topBelt = new TalonSRX(mapTransfer.TOP_MOTOR_CAN); - bottomLeftSwitch = new DigitalInput(mapTransfer.BOTTOM_LEFT_SWITCH_DIO); - bottomRightSwitch = new DigitalInput(mapTransfer.BOTTOM_RIGHT_SWITCH_DIO); - topLeftSwitch = new DigitalInput(mapTransfer.TOP_LEFT_SWITCH_DIO); - topRightSwitch = new DigitalInput(mapTransfer.TOP_RIGHT_SWITCH_DIO); + bottomSwitch = new DigitalInput(mapTransfer.BOTTOM_SWITCH_DIO); + topSwitch = new DigitalInput(mapTransfer.TOP_SWITCH_DIO); displayOnDashboard = true; @@ -45,11 +45,11 @@ public Transfer() { } public void configure() { - entranceWheel.configFactoryDefault(); + entranceWheel.restoreFactoryDefaults(); bottomBelt.configFactoryDefault(); topBelt.configFactoryDefault(); - entranceWheel.setNeutralMode(NeutralMode.Brake); + entranceWheel.setIdleMode(IdleMode.kBrake); bottomBelt.setNeutralMode(NeutralMode.Brake); topBelt.setNeutralMode(NeutralMode.Brake); @@ -65,15 +65,15 @@ public void setBottomBeltSpeed(SN_DoublePreference speed) { } public void setEntranceWheelSpeed(SN_DoublePreference speed) { - entranceWheel.set(ControlMode.PercentOutput, speed.getValue()); + entranceWheel.set(speed.getValue()); } public boolean isTopBallCollected() { - return !topLeftSwitch.get() || !topRightSwitch.get(); + return (constTransfer.TOP_LIMIT_SWITCH_INVERT) ? !topSwitch.get() : topSwitch.get(); } public boolean isBottomBallCollected() { - return !bottomLeftSwitch.get() || !bottomRightSwitch.get(); + return (constTransfer.BOTTOM_LIMIT_SWITCH_INVERT) ? !bottomSwitch.get() : bottomSwitch.get(); } public void displayValuesOnDashboard() { @@ -91,16 +91,13 @@ public void periodic() { SmartDashboard.putNumber("Transfer Top Belt Speed", topBelt.getMotorOutputPercent()); SmartDashboard.putNumber("Transfer Bottom Belt Speed", bottomBelt.getMotorOutputPercent()); - SmartDashboard.putNumber("Transfer Entrance Wheel Speed", entranceWheel.getMotorOutputPercent()); + SmartDashboard.putNumber("Transfer Entrance Wheel Speed", entranceWheel.getAppliedOutput()); SmartDashboard.putBoolean("Transfer Is Top Ball Collected", isTopBallCollected()); SmartDashboard.putBoolean("Transfer Is Bottom Ball Collected", isBottomBallCollected()); - SmartDashboard.putBoolean("Transfer Is Top Left Switch", topLeftSwitch.get()); - SmartDashboard.putBoolean("Transfer Is Top Right Switch", topRightSwitch.get()); - SmartDashboard.putBoolean("Transfer Is Bottom Left Switch", bottomLeftSwitch.get()); - SmartDashboard.putBoolean("Transfer Is Bottom Right Switch", bottomRightSwitch.get()); - + SmartDashboard.putBoolean("Transfer Top Switch RAW", topSwitch.get()); + SmartDashboard.putBoolean("Transfer Bottom Switch RAW", bottomSwitch.get()); } } diff --git a/src/main/java/frc/robot/subsystems/Turret.java b/src/main/java/frc/robot/subsystems/Turret.java index 85f96cb..645c433 100644 --- a/src/main/java/frc/robot/subsystems/Turret.java +++ b/src/main/java/frc/robot/subsystems/Turret.java @@ -23,6 +23,7 @@ public class Turret extends SubsystemBase { SparkPIDController turretPIDController; boolean displayOnDashboard; + final double conversionFactor = 360 / constTurret.GEAR_RATIO; public Turret() { @@ -44,13 +45,15 @@ public void configure() { turretMotor.setInverted(constTurret.INVERTED); + turretMotor.getEncoder().setPositionConversionFactor(conversionFactor); + turretMotor.enableSoftLimit(SoftLimitDirection.kForward, true); turretMotor.setSoftLimit(SoftLimitDirection.kForward, - (float) ((prefTurret.turretMaxDegrees.getValue() / 360) * constTurret.GEAR_RATIO)); + (float) prefTurret.turretMaxDegrees.getValue()); turretMotor.enableSoftLimit(SoftLimitDirection.kReverse, true); turretMotor.setSoftLimit(SoftLimitDirection.kReverse, - (float) ((prefTurret.turretMinDegrees.getValue() / 360) * constTurret.GEAR_RATIO)); + (float) prefTurret.turretMinDegrees.getValue()); turretMotor.setIdleMode(IdleMode.kBrake); } @@ -61,8 +64,7 @@ public void configure() { * @param degrees Degree count to set turret to */ public void setAngle(double degrees) { - turretPIDController.setReference(degrees / 360, CANSparkMax.ControlType.kPosition); - // TODO: I don't know if the degrees are still accurate o.O so it might explode + turretPIDController.setReference(degrees, CANSparkMax.ControlType.kPosition); } /** @@ -80,7 +82,7 @@ public void setAngle(SN_DoublePreference degrees) { * @return Turret angle in degrees */ public double getAngleDegrees() { - return (turretMotor.getEncoder().getPosition()) * 360; + return turretMotor.getEncoder().getPosition(); } public double getRawAngle() { @@ -92,7 +94,7 @@ public void setSpeed(double speed) { } public void resetEncoderCounts() { - turretMotor.getEncoder().setPosition((prefTurret.turretFacingTowardsIntakeDegrees.getValue()) / 360); + turretMotor.getEncoder().setPosition(prefTurret.turretFacingTowardsIntakeDegrees.getValue()); } public void displayValuesOnDashboard() { diff --git a/src/main/java/frc/robot/subsystems/Vision.java b/src/main/java/frc/robot/subsystems/Vision.java index 4a58041..ec20844 100644 --- a/src/main/java/frc/robot/subsystems/Vision.java +++ b/src/main/java/frc/robot/subsystems/Vision.java @@ -16,64 +16,67 @@ public class Vision extends SubsystemBase { - public SN_Limelight limelight; - - int buttonTimerLoops; - - public Vision() { - limelight = new SN_Limelight(); - } - - public void setLEDOn() { - limelight.setLEDMode(LEDMode.on); - } - - public void setLEDOff() { - limelight.setLEDMode(LEDMode.off); - } - - /** - * Get distance from hub using ty inputed to the lerp - * - * @return Distance from limelight lens to center of hub - */ - public double getDistanceFromHub() { - return constVision.tyDistanceTable.getOutput(limelight.getOffsetY()); - } - - /** - * Calculate Robot Position from Vision target. Specific to the Rapid React - * field. - *
- * Radian measures require counterclockwise rotation to be positive. - * - * @param distanceFromHub Distance from hub in meters - * @param robotAngle Robot angle in radians - * @param turretAngle Turret angle in radians - * @param offsetToTarget Angle offset to target in radians - * @return Calculated position of the robot - */ - public Pose2d calculatePoseFromVision( - double distanceFromHub, - double robotAngle, - double turretAngle, - double offsetToTarget) { - - double goalAngle = robotAngle + turretAngle + offsetToTarget; - - double calculatedRobotXPosition = constField.HUB_POSITION.getX() - (distanceFromHub * Math.cos(goalAngle)); - double calculatedRobotYPosition = constField.HUB_POSITION.getY() + (distanceFromHub * Math.sin(goalAngle)); - - return new Pose2d(calculatedRobotXPosition, calculatedRobotYPosition, new Rotation2d(-robotAngle)); - } + // public SN_Limelight limelight; + + // int buttonTimerLoops; + + // public Vision() { + // limelight = new SN_Limelight(); + // } + + // public void setLEDOn() { + // limelight.setLEDMode(LEDMode.on); + // } + + // public void setLEDOff() { + // limelight.setLEDMode(LEDMode.off); + // } + + // /** + // * Get distance from hub using ty inputed to the lerp + // * + // * @return Distance from limelight lens to center of hub + // */ + // public double getDistanceFromHub() { + // return constVision.tyDistanceTable.getOutput(limelight.getOffsetY()); + // } + + // /** + // * Calculate Robot Position from Vision target. Specific to the Rapid React + // * field. + // *
+ // * Radian measures require counterclockwise rotation to be positive. + // * + // * @param distanceFromHub Distance from hub in meters + // * @param robotAngle Robot angle in radians + // * @param turretAngle Turret angle in radians + // * @param offsetToTarget Angle offset to target in radians + // * @return Calculated position of the robot + // */ + // public Pose2d calculatePoseFromVision( + // double distanceFromHub, + // double robotAngle, + // double turretAngle, + // double offsetToTarget) { + + // double goalAngle = robotAngle + turretAngle + offsetToTarget; + + // double calculatedRobotXPosition = constField.HUB_POSITION.getX() - + // (distanceFromHub * Math.cos(goalAngle)); + // double calculatedRobotYPosition = constField.HUB_POSITION.getY() + + // (distanceFromHub * Math.sin(goalAngle)); + + // return new Pose2d(calculatedRobotXPosition, calculatedRobotYPosition, new + // Rotation2d(-robotAngle)); + // } @Override public void periodic() { - buttonTimerLoops++; - if (RobotController.getUserButton() && buttonTimerLoops > 25) { - limelight.toggleLEDs(); - buttonTimerLoops = 0; - } + // buttonTimerLoops++; + // if (RobotController.getUserButton() && buttonTimerLoops > 25) { + // limelight.toggleLEDs(); + // buttonTimerLoops = 0; + // } } }