Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Full functional #138

Merged
merged 11 commits into from
May 11, 2024
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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. */
Expand Down
22 changes: 16 additions & 6 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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
Expand All @@ -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)));
Comment on lines 149 to 162
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove hood presets in another PR

}

Expand Down
12 changes: 5 additions & 7 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand All @@ -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;

}

Expand All @@ -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;

}

Expand Down
41 changes: 12 additions & 29 deletions src/main/java/frc/robot/RobotPreferences.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand All @@ -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 {
Expand All @@ -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);
Comment on lines +112 to +115
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are these being used anywhere?

}

public static final class prefTransfer {
Expand All @@ -142,17 +125,16 @@ 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 {

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);
Expand All @@ -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);
Expand Down
6 changes: 1 addition & 5 deletions src/main/java/frc/robot/commands/Cargo/CollectCargo.java
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/commands/Cargo/DiscardCargo.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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) {

Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/subsystems/Climber.java
Original file line number Diff line number Diff line change
Expand Up @@ -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() {
Expand Down
1 change: 0 additions & 1 deletion src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,6 @@ public void periodic() {
SmartDashboard.putNumber("Drivetrain Right Meters", getRightMeters());

SmartDashboard.putNumber("Drivetrain Heading Degrees", navx.getRotation2d().getDegrees());

}
}
}
28 changes: 19 additions & 9 deletions src/main/java/frc/robot/subsystems/Hood.java
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand All @@ -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() {
Expand All @@ -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() {
Expand All @@ -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());

}

Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
public class Intake extends SubsystemBase {

TalonSRX roller;

boolean displayOnDashboard;
double desiredPercentOutput = 0;

public Intake() {

Expand All @@ -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());
}

Expand All @@ -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);

}

}
Expand Down
Loading