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

Post-BATB Tuning #123

Draft
wants to merge 7 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
57 changes: 54 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
import java.util.Optional;
import java.util.function.Supplier;

import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.Slot1Configs;
import com.ctre.phoenix6.signals.GravityTypeValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
Expand Down Expand Up @@ -250,6 +252,54 @@ public static class constShooter {
public static final NeutralModeValue PIVOT_NEUTRAL_MODE = NeutralModeValue.Brake;
public static final GravityTypeValue PIVOT_GRAVITY_TYPE = GravityTypeValue.Arm_Cosine;

// - PID -
public static Slot0Configs LEFT_PID_SLOT_0_FAST = new Slot0Configs();
public static Slot1Configs LEFT_PID_SLOT_1_SLOW = new Slot1Configs();
public static Slot0Configs RIGHT_PID_SLOT_0_FAST = new Slot0Configs();
public static Slot1Configs RIGHT_PID_SLOT_1_SLOW = new Slot1Configs();
public static Slot0Configs PIVOT_PID = new Slot0Configs();
static {
// Left 0
LEFT_PID_SLOT_0_FAST.kS = 0.13419;
LEFT_PID_SLOT_0_FAST.kV = 0.12443;
LEFT_PID_SLOT_0_FAST.kA = 0.035067;
LEFT_PID_SLOT_0_FAST.kP = 1;
LEFT_PID_SLOT_0_FAST.kI = 0;
LEFT_PID_SLOT_0_FAST.kD = 0;

// Left 1
LEFT_PID_SLOT_1_SLOW.kS = 0.13419;
LEFT_PID_SLOT_1_SLOW.kV = 0.12443;
LEFT_PID_SLOT_1_SLOW.kA = 0.035067;
LEFT_PID_SLOT_1_SLOW.kP = 0.5;
LEFT_PID_SLOT_1_SLOW.kI = 0;
LEFT_PID_SLOT_1_SLOW.kD = 0;

// Right 0
RIGHT_PID_SLOT_0_FAST.kS = 0.36;
RIGHT_PID_SLOT_0_FAST.kV = 0.115;
RIGHT_PID_SLOT_0_FAST.kA = 0;
RIGHT_PID_SLOT_0_FAST.kP = 0.7;
RIGHT_PID_SLOT_0_FAST.kI = 0;
RIGHT_PID_SLOT_0_FAST.kD = 0;
// Right 1
RIGHT_PID_SLOT_1_SLOW.kS = 0.36;
RIGHT_PID_SLOT_1_SLOW.kV = 0.112;
RIGHT_PID_SLOT_1_SLOW.kA = 0;
RIGHT_PID_SLOT_1_SLOW.kP = 0.5;
RIGHT_PID_SLOT_1_SLOW.kI = 0;
RIGHT_PID_SLOT_1_SLOW.kD = 0;
// Pivot
PIVOT_PID.kS = 0.4;
PIVOT_PID.kV = 0;
PIVOT_PID.kG = 0.53;
PIVOT_PID.kA = 0;
PIVOT_PID.kP = 90;
PIVOT_PID.kD = 0;
}
public static final Measure<Velocity<Angle>> RIGHT_SLOT_1_THRESH = Units.RotationsPerSecond.of(40);
public static final Measure<Velocity<Angle>> LEFT_SLOT_1_THRESH = Units.RotationsPerSecond.of(40);

// - Angles -
public static final Measure<Angle> PIVOT_FORWARD_LIMIT = Units.Degrees.of(155);
public static final Measure<Angle> PIVOT_BACKWARD_LIMIT = Units.Degrees.of(0);
Expand Down Expand Up @@ -473,7 +523,7 @@ public static class constElevator {
public static final double MOTOR_ROTATION_TO_METERS = 1 / 0.0456842368;

public static final Measure<Distance> AMP_POSITION = Units.Meters.of(0.38);
public static final Measure<Distance> SHOOTER_ABLE_TO_MOVE_LIMIT = Units.Meters.of(0.37);
public static final Measure<Distance> SHOOTER_ABLE_TO_MOVE_LIMIT = Units.Meters.of(0.35);

public static final Measure<Distance> AT_POSITION_TOLERANCE = Units.Meters.of(0.05);

Expand Down Expand Up @@ -528,6 +578,7 @@ public static class constIntake {
public static final Measure<Dimensionless> INTAKING_SPEED = Units.Percent.of(1);
public static final Measure<Dimensionless> EJECTING_SPEED = Units.Percent.of(-1);
public static final InvertedValue MOTOR_INVERT = InvertedValue.Clockwise_Positive;
public static final boolean NOTE_SENSOR_INVERT = true;

// -- Current Limiting --
public static final boolean ENABLE_CURRENT_LIMITING = true;
Expand All @@ -541,9 +592,9 @@ public static class constTransfer {
public static final InvertedValue MOTOR_INVERT = InvertedValue.Clockwise_Positive;
public static final NeutralModeValue FEEDER_NEUTRAL_MODE = NeutralModeValue.Brake;

public static final double INTAKING_SPEED = 0.3;
public static final double INTAKING_SPEED = 0.4;
public static final double INTAKE_SOURCE_SPEED = -0.2;
public static final double EJECTING_SPEED = -0.3;
public static final double EJECTING_SPEED = -0.4;

public static final double PREP_TO_AMP_SPEED = 0.2;

Expand Down
62 changes: 19 additions & 43 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

import java.util.function.DoubleSupplier;

import com.ctre.phoenix6.SignalLogger;
import com.frcteam3255.joystick.SN_XboxController;
import com.pathplanner.lib.auto.NamedCommands;

Expand All @@ -19,6 +20,7 @@
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.Constants.constClimber;
import frc.robot.Constants.constControllers;
import frc.robot.Constants.constElevator;
Expand Down Expand Up @@ -69,10 +71,10 @@ public class RobotContainer {
private final static Transfer subTransfer = new Transfer();
private final static Limelight subLimelight = new Limelight();

private final Trigger gamePieceTrigger = new Trigger(() -> subTransfer.getGamePieceCollected());
private final Trigger gamePieceTrigger = new Trigger(() -> subTransfer.getGamePieceStored());
private final Trigger readyToShoot = new Trigger(() -> subDrivetrain.isDrivetrainFacingSpeaker()
&& subShooter.readyToShoot() && subStateMachine.isCurrentStateTargetState()
&& subTransfer.getGamePieceCollected());
&& subTransfer.getGamePieceStored());
private final IntakeSource comIntakeSource = new IntakeSource(subStateMachine, subShooter, subTransfer);

SendableChooser<Command> autoChooser = new SendableChooser<>();
Expand Down Expand Up @@ -130,21 +132,6 @@ private void configureDriverBindings(SN_XboxController controller) {
controller.btn_North.onTrue(
Commands.runOnce(() -> subDrivetrain.resetPoseToPose(constField.getFieldPositions().get()[6].toPose2d())));

// Climb up
controller.btn_RightTrigger.onTrue(
Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_AMP)))
.onTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.CLIMBING, subStateMachine,
subClimber, subDrivetrain, subElevator,
subIntake, subTransfer, subShooter)))
.whileTrue(Commands.runOnce(() -> subClimber.setClimberSpeed(controller.getRightTriggerAxis())))
.onFalse(Commands.runOnce(() -> subClimber.setClimberSpeed(0)));

// Climb down
controller.btn_LeftTrigger
.whileTrue(Commands.runOnce(() -> subClimber.setClimberSpeed(-controller.getLeftTriggerAxis())))
.onFalse(Commands.runOnce(() -> subClimber.setClimberSpeed(0)));

// Intake from source
controller.btn_East.whileTrue(Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.INTAKE_SOURCE,
subStateMachine, subClimber, subDrivetrain, subElevator, subIntake, subTransfer, subShooter)))
Expand Down Expand Up @@ -257,37 +244,27 @@ private void configureOperatorBindings(SN_XboxController controller) {
controller.btn_Start.whileTrue(new ManualElevator(subElevator, controller.axis_LeftY));

// Zero Elevator and Climber
controller.btn_LeftStick.onTrue(new ZeroElevator(subElevator))
.onTrue(new ZeroClimber(subClimber));
controller.btn_LeftStick.onTrue(new ZeroElevator(subElevator));

// Zero Shooter
controller.btn_RightStick.onTrue(new ZeroShooterPivot(subShooter));
}

private void configureTestBindings(SN_XboxController controller) {
controller.btn_LeftTrigger.onTrue(Commands.runOnce(() -> subStateMachine.setRobotState(RobotState.INTAKING)))
.whileTrue(new Intaking(subStateMachine, subIntake, subShooter, subTransfer))
.onFalse(new NoneState(subStateMachine, subClimber, subElevator, subIntake,
subShooter, subTransfer));

controller.btn_RightTrigger.onTrue(Commands.runOnce(() -> subStateMachine.setRobotState(RobotState.SHOOTING)))
.whileTrue(new Shooting(subStateMachine, subElevator, subShooter,
subTransfer))
.onFalse(new NoneState(subStateMachine, subClimber, subElevator, subIntake,
subShooter, subTransfer));

controller.btn_X.onTrue(Commands.runOnce(() -> subStateMachine.setRobotState(RobotState.PREP_SHUFFLE)))
.onTrue(new PrepTargetState(subElevator, subStateMachine, subShooter,
TargetState.PREP_SHUFFLE));

controller.btn_A.onTrue(Commands.runOnce(() -> subElevator.setElevatorPosition(constElevator.AMP_POSITION)));
controller.btn_Y.onTrue(Commands.runOnce(() -> subElevator.setElevatorPosition(constElevator.BACKWARD_LIMIT)));

controller.btn_West.onTrue(Commands.runOnce(() -> subStateMachine.setRobotState(RobotState.EJECTING)))
.whileTrue(new Ejecting(subStateMachine, subIntake, subElevator,
subTransfer))
.onFalse(new NoneState(subStateMachine, subClimber, subElevator, subIntake,
subShooter, subTransfer));

controller.btn_LeftBumper.onTrue(Commands.runOnce(SignalLogger::start));
controller.btn_RightBumper.onTrue(Commands.runOnce(SignalLogger::stop));

/*
* Joystick Y = quasistatic forward
* Joystick A = quasistatic reverse
* Joystick B = dynamic forward
* Joystick X = dyanmic reverse
*/
controller.btn_Y.whileTrue(subShooter.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
controller.btn_A.whileTrue(subShooter.sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
controller.btn_B.whileTrue(subShooter.sysIdDynamic(SysIdRoutine.Direction.kForward));
controller.btn_X.whileTrue(subShooter.sysIdDynamic(SysIdRoutine.Direction.kReverse));
}

private void configureAutoSelector() {
Expand Down Expand Up @@ -331,7 +308,6 @@ public Command getAutonomousCommand() {
*/
public static Command zeroSubsystems() {
Command returnedCommand = new ParallelCommandGroup(
new ZeroClimber(subClimber).withTimeout(constClimber.ZEROING_TIMEOUT.in(Units.Seconds)),
new ZeroElevator(subElevator).withTimeout(constElevator.ZEROING_TIMEOUT.in(Units.Seconds)),
new ZeroShooterPivot(subShooter).withTimeout(constShooter.ZEROING_TIMEOUT.in(Units.Seconds)))
.withInterruptBehavior(Command.InterruptionBehavior.kCancelIncoming);
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ public static class mapShooter {
// MOTORS: 20 -> 29
public static class mapIntake {
public static final int ROLLER_CAN = 20;
public static final int NOTE_SENSOR_DIO = 2;
}

// MOTORS: 30 -> 39
Expand Down
27 changes: 2 additions & 25 deletions src/main/java/frc/robot/RobotPreferences.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
package frc.robot;

import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.Slot1Configs;
import com.frcteam3255.preferences.SN_DoublePreference;

import edu.wpi.first.units.Angle;
Expand Down Expand Up @@ -79,31 +81,6 @@ public static final class prefDrivetrain {
public static final double yawSnapD = 0;
}

public static final class prefShooter {
// - PID -
public static final double leftShooterS = 0.28;
public static final double leftShooterV = 0.13;
public static final double leftShooterA = 0.0;
public static final double leftShooterP = 0.5; // 0.75 ?
public static final double leftShooterI = 0;
public static final double leftShooterD = 0.0;

public static final double rightShooterS = 0.4;
public static final double rightShooterV = 0.11;
public static final double rightShooterA = 0;
public static final double rightShooterP = 0.4; // 0.6 ?
public static final double rightShooterI = 0;
public static final double rightShooterD = 0;

public static final double pivotShooterS = 0.4;
public static final double pivotShooterV = 0.0;
public static final double pivotShooterG = 0.53;
public static final double pivotShooterA = 0.0;
public static final double pivotShooterP = 90;
public static final double pivotShooterI = 0;
public static final double pivotShooterD = 0;
}

public static final class prefElevator {
public static final double elevatorG = 0.3;
public static final double elevatorS = 0.4;
Expand Down
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/commands/Autos/Centerline.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,11 @@ public class Centerline extends SequentialCommandGroup {

BooleanSupplier readyToShoot = (() -> subDrivetrain.isDrivetrainFacingSpeaker()
&& subShooter.readyToShoot() && subStateMachine.isCurrentStateTargetState()
&& subTransfer.getGamePieceCollected());
&& subTransfer.getGamePieceStored());

// TODO: Move this into its own command so we can use it everywhere :)
SequentialCommandGroup shootSequence = new SequentialCommandGroup(
Commands.waitUntil(() -> subTransfer.getGamePieceCollected()),
Commands.waitUntil(() -> subTransfer.getGamePieceStored()),
Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_VISION)),

Commands.parallel(
Expand All @@ -64,7 +64,7 @@ public class Centerline extends SequentialCommandGroup {
.tryState(RobotState.SHOOTING, subStateMachine, subClimber, subDrivetrain, subElevator, subIntake,
subTransfer,
subShooter)
.until(() -> !subTransfer.getGamePieceCollected())),
.until(() -> !subTransfer.getGamePieceStored())),

// Reset subsystems to chill
Commands.deferredProxy(() -> subStateMachine
Expand All @@ -89,7 +89,7 @@ public Centerline(StateMachine subStateMachine, Climber subClimber, Drivetrain s
// -- PRELOAD --
Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.INTAKING, subStateMachine, subClimber,
subDrivetrain, subElevator, subIntake, subTransfer, subShooter))
.until(() -> subTransfer.getGamePieceCollected()),
.until(() -> subTransfer.getGamePieceStored()),

Commands.deferredProxy(() -> shootSequence),

Expand All @@ -109,7 +109,7 @@ public Centerline(StateMachine subStateMachine, Climber subClimber, Drivetrain s

// It wasnt there :<
new PathPlannerAuto(determineHopPathName() + ".1"),
() -> subTransfer.getGamePieceCollected()),
() -> subTransfer.getGamePieceStored()),

// -- CURRENTLY AT C4 --
Commands.waitSeconds(0.5),
Expand All @@ -125,7 +125,7 @@ public Centerline(StateMachine subStateMachine, Climber subClimber, Drivetrain s

// It wasnt there :<
new PathPlannerAuto(determineHopPathName() + ".2"),
() -> subTransfer.getGamePieceCollected()),
() -> subTransfer.getGamePieceStored()),

// -- CURRENTLY AT C3
Commands.waitSeconds(0.5),
Expand All @@ -141,7 +141,7 @@ public Centerline(StateMachine subStateMachine, Climber subClimber, Drivetrain s

// It wasnt there :<
new PathPlannerAuto(determineHopPathName() + ".3"),
() -> subTransfer.getGamePieceCollected()),
() -> subTransfer.getGamePieceStored()),

// -- CURRENTLY AT C2
Commands.waitSeconds(0.5),
Expand All @@ -157,7 +157,7 @@ public Centerline(StateMachine subStateMachine, Climber subClimber, Drivetrain s

// It wasnt there :<
new PathPlannerAuto(determineHopPathName() + ".4"),
() -> subTransfer.getGamePieceCollected()),
() -> subTransfer.getGamePieceStored()),

// -- CURRENTLY AT C1
Commands.waitSeconds(0.5),
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/commands/Autos/PreloadOnly.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ public PreloadOnly(StateMachine subStateMachine, Climber subClimber, Drivetrain

Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.INTAKING, subStateMachine, subClimber,
subDrivetrain, subElevator, subIntake, subTransfer, subShooter))
.until(() -> subTransfer.getGamePieceCollected()),
.until(() -> subTransfer.getGamePieceStored()),

Commands.waitUntil(() -> subShooter.readyToShoot()),

Expand All @@ -85,7 +85,7 @@ public PreloadOnly(StateMachine subStateMachine, Climber subClimber, Drivetrain
.tryState(RobotState.SHOOTING, subStateMachine, subClimber, subDrivetrain, subElevator, subIntake,
subTransfer,
subShooter)
.until(() -> !subTransfer.getGamePieceCollected())),
.until(() -> !subTransfer.getGamePieceStored())),

// Reset subsystems to chill
Commands.deferredProxy(() -> subStateMachine
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/commands/Autos/PreloadTaxi.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,10 @@ public class PreloadTaxi extends SequentialCommandGroup {

BooleanSupplier readyToShoot = (() -> subDrivetrain.isDrivetrainFacingSpeaker()
&& subShooter.readyToShoot() && subStateMachine.isCurrentStateTargetState()
&& subTransfer.getGamePieceCollected());
&& subTransfer.getGamePieceStored());

SequentialCommandGroup shootSequence = new SequentialCommandGroup(
Commands.waitUntil(() -> subTransfer.getGamePieceCollected()),
Commands.waitUntil(() -> subTransfer.getGamePieceStored()),
Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_VISION)),

Commands.deferredProxy(() -> subStateMachine
Expand All @@ -65,7 +65,7 @@ public class PreloadTaxi extends SequentialCommandGroup {
.tryState(RobotState.SHOOTING, subStateMachine, subClimber, subDrivetrain, subElevator, subIntake,
subTransfer,
subShooter)
.until(() -> !subTransfer.getGamePieceCollected())),
.until(() -> !subTransfer.getGamePieceStored())),

// Reset subsystems to chill
Commands.deferredProxy(() -> subStateMachine
Expand Down Expand Up @@ -95,7 +95,7 @@ public PreloadTaxi(StateMachine subStateMachine, Climber subClimber, Drivetrain
// -- PRELOAD --
Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.INTAKING, subStateMachine, subClimber,
subDrivetrain, subElevator, subIntake, subTransfer, subShooter))
.until(() -> subTransfer.getGamePieceCollected()),
.until(() -> subTransfer.getGamePieceStored()),

Commands.deferredProxy(() -> shootSequence),

Expand Down
Loading