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

206 sim subsystems #208

Merged
merged 9 commits into from
Feb 20, 2025
Merged
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
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ public Robot() {
Logger.addDataReceiver(new WPILOGWriter("/home/lvuser/logs"));
Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
PowerDistribution distribution =
new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging
new PowerDistribution(
33, ModuleType.kRev); // Enables power distribution logging
} else {
setUseTiming(true); // Run as fast as possible
Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
Expand Down
70 changes: 45 additions & 25 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,8 @@
import frc.robot.subsystems.chute.ChuteIONeo550;
import frc.robot.subsystems.chute.ChuteIOSim;
import frc.robot.subsystems.chute.ChuteSubsystem;
import frc.robot.subsystems.climber.ClimberHeadIONeo550;
import frc.robot.subsystems.climber.ClimberHeadIOSim;
import frc.robot.subsystems.climber.ClimberIOSim;
import frc.robot.subsystems.climber.ClimberIOTalonFX;
import frc.robot.subsystems.climber.ClimberSubsystem;
import frc.robot.subsystems.elevator.ElevatorIOSim;
import frc.robot.subsystems.elevator.ElevatorIOTalonFX;
Expand All @@ -54,8 +52,8 @@
import frc.robot.subsystems.intake.IntakeSubsystem;
import frc.robot.subsystems.lights.LightsSubsystem;
import frc.robot.subsystems.swerve.CommandSwerveDrivetrain;
import frc.robot.subsystems.vision.DummyPhotonCamera;
import frc.robot.subsystems.vision.Vision;
import frc.robot.subsystems.vision.VisionIOLimelight;
import frc.robot.subsystems.vision.VisionIOPhotonVisionSim;
import frc.robot.subsystems.vision.VisionIOPhotonVisionSimML;
import frc.robot.subsystems.wrist.WristIONeo550;
Expand Down Expand Up @@ -99,23 +97,31 @@ public RobotContainer() {
vision =
new Vision(
drivetrain::addVisionMeasurement,
new VisionIOLimelight(
VisionConstants.camera0Name,
() -> drivetrain.getRobotPose().getRotation()),
new VisionIOLimelight(
VisionConstants.camera1Name,
() -> drivetrain.getRobotPose().getRotation()),
new VisionIOLimelight(
VisionConstants.camera2Name,
() -> drivetrain.getRobotPose().getRotation()));
gripperSubsystem = new GripperSubsystem(new GripperIOFalcon());
elevatorSubsystem = new ElevatorSubsystem(new ElevatorIOTalonFX());
new DummyPhotonCamera(),
new DummyPhotonCamera(),
new DummyPhotonCamera());
// new VisionIOLimelight(
// VisionConstants.camera0Name,
// () -> drivetrain.getRobotPose().getRotation()),
// new VisionIOLimelight(
// VisionConstants.camera1Name,
// () -> drivetrain.getRobotPose().getRotation()),
// new VisionIOLimelight(
// VisionConstants.camera2Name,
// () -> drivetrain.getRobotPose().getRotation()));
gripperSubsystem =
new GripperSubsystem(new GripperIOFalcon()); // new GripperIOFalcon());
elevatorSubsystem =
new ElevatorSubsystem(new ElevatorIOTalonFX()); // new ElevatorIOTalonFX());
armSubsystem = new ArmSubsystem(new ArmPivotIOTalonFX());
wristSubsystem = new WristSubsystem(new WristIONeo550());
wristSubsystem = new WristSubsystem(new WristIONeo550()); // new WristIONeo550());
climberSubsystem =
new ClimberSubsystem(new ClimberIOTalonFX(), new ClimberHeadIONeo550());
new ClimberSubsystem(
new ClimberIOSim(),
new ClimberHeadIOSim()); // new ClimberIOTalonFX(), new
// ClimberHeadIONeo550());
lights = new LightsSubsystem();
chuteSubsystem = new ChuteSubsystem(new ChuteIONeo550());
chuteSubsystem = new ChuteSubsystem(new ChuteIONeo550()); // new ChuteIONeo550());

intakeSubsystem = new IntakeSubsystem(new IntakeRollerIOSim(), new FlipperIOSim());
} else {
Expand Down Expand Up @@ -150,6 +156,10 @@ public RobotContainer() {
elevatorSubsystem, armSubsystem, wristSubsystem, chuteSubsystem);

auto = new Auto(drivetrain, this);

wristSubsystem.elevatorHeight = () -> elevatorSubsystem.getPosition();
wristSubsystem.armHeight = () -> armSubsystem.getPosition();

configureBindings();
// Establish the "Trajectory Field" Field2d into the dashboard
}
Expand Down Expand Up @@ -368,7 +378,9 @@ private void configureBindings() {
ARMWRIST.and(operatorController.getX()).whileTrue(wristSubsystem.turnWristLeft());
ARMWRIST.and(operatorController.getB()).whileTrue(wristSubsystem.turnWristRight());

CORAL.and(operatorController.getY()).onTrue(stateManager.moveToPosition(Position.L4));
CORAL.and(operatorController.getY())
.onTrue(stateManager.moveToPosition(Position.L4Prep))
.onFalse(stateManager.moveToPosition(Position.L4));
CORAL.and(operatorController.getX()).onTrue(stateManager.moveToPosition(Position.L3));
CORAL.and(operatorController.getB()).onTrue(stateManager.moveToPosition(Position.L2));
CORAL.and(operatorController.getA()).onTrue(stateManager.moveToPosition(Position.L1));
Expand All @@ -378,7 +390,8 @@ private void configureBindings() {
CORAL.and(operatorController.getDPadDown())
.onTrue(stateManager.moveToPosition(Position.Home));
CORAL.and(operatorController.getDPadUp())
.onTrue(stateManager.moveToPosition(Position.Handoff));
.onTrue(stateManager.moveToPosition(Position.HandoffPrep))
.onFalse(stateManager.moveToPosition(Position.Handoff));
CORAL.and(operatorController.getDPadLeft()).onTrue(chuteSubsystem.moveChuteUp());
CORAL.and(operatorController.getDPadRight()).onTrue(chuteSubsystem.moveChuteDown());

Expand Down Expand Up @@ -417,11 +430,10 @@ private void configureBindings() {
// rightDriveController.getRightThumb().whileTrue(intakeSubsystem.openAndEject());

CORAL.and(rightDriveController.getBottomThumb())
.whileTrue(gripperSubsystem.intakeSpinCoral());
.whileTrue(gripperSubsystem.intakeSpinCoral().until(gripperSubsystem.HAS_PIECE));
CORAL.and(rightDriveController.getTrigger()).whileTrue(gripperSubsystem.ejectSpinCoral());

ALGAE.and(rightDriveController.getBottomThumb())
.whileTrue(gripperSubsystem.intakeSpinAlgae());
ALGAE.and(rightDriveController.getBottomThumb()).onTrue(gripperSubsystem.intakeSpinAlgae());
ALGAE.and(rightDriveController.getTrigger()).whileTrue(gripperSubsystem.ejectSpinAlgae());

leftDriveController
Expand Down Expand Up @@ -450,19 +462,27 @@ private void configureBindings() {
// Technical Bindings

leftDriveController.getLeftBottomMiddle().onTrue(climberSubsystem.zeroClimberCommand());
rightDriveController
.getLeftBottomMiddle()
.onTrue(stateManager.moveToPosition(Position.Start));
leftDriveController.getLeftTopMiddle().whileTrue(climberSubsystem.climberTuneable());

rightDriveController
.getLeftTopLeft()
.onTrue(Commands.runOnce(() -> drivetrain.seedFieldCentric()));

leftDriveController.getLeftBottomLeft().whileTrue(intakeSubsystem.rollerTuneable());
leftDriveController.getLeftTopRight().whileTrue(intakeSubsystem.flipperTuneable());
// leftDriveController.getLeftBottomLeft().whileTrue(wristSubsystem.tunablePose());
// leftDriveController.getLeftTopRight().whileTrue(wristSubsystem.tuneableVoltage());

// leftDriveController.getLeftBottomLeft().whileTrue(intakeSubsystem.rollerTuneable());
// leftDriveController.getLeftTopRight().whileTrue(intakeSubsystem.flipperTuneable());

leftDriveController.getLeftBottomLeft().whileTrue(chuteSubsystem.moveChuteUp());
leftDriveController.getLeftTopRight().whileTrue(chuteSubsystem.moveChuteDown());

leftDriveController.getLeftBottomRight().onTrue(intakeSubsystem.zeroflipper());

leftDriveController.getLeftTopLeft().whileTrue(gripperSubsystem.gripperTuneable());

{
var tunableCommand =
Commands.runOnce(
Expand Down
15 changes: 7 additions & 8 deletions src/main/java/frc/robot/constants/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@

public class ArmConstants {

public static final int ARM_PIVOT_MOTOR_ID = 10; // not correct motor ID
public static final String ARM_PIVOT_CANBUS = "CANivore";
public static final int ARM_PIVOT_MOTOR_ID = 10;
public static final String ARM_PIVOT_CANBUS = "rio";

public static final int ARM_THROUGHBORE_ENCODER_ID = 0;
public static final int ARM_THROUGHBORE_ENCODER_ID = 1;

// public static final Slot0Configs slot0Configs =
// new Slot0Configs()
Expand All @@ -27,13 +27,12 @@ public class ArmConstants {
// .withMotionMagicJerk(4);

public static final CurrentLimitsConfigs currentLimitConfigs = new CurrentLimitsConfigs();

public static final double ARM_KP = 5;
public static final double ARM_KP = 3.5;
public static final double ARM_KD = 0;
public static final double ARM_KI = 0;
public static final double ARM_KI = 0.25;

public static final double ARM_TOLERANCE = 0.01;

public static final double upperLimit = 100;
public static final double lowerLimit = 0;
public static final double upperLimit = 2.15;
public static final double lowerLimit = -0.6;
}
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/ChuteConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@ public class ChuteConstants {

public static final double CHUTE_TOLERANCE = 0.01;

public static final double ChuteCurrent = 30;
public static final double ChuteCurrent = 40;

public static final double upperLimit = 100;
public static final double upperLimit = 10;
public static final double lowerLimit = 0;

public static final double ChuteCurrentTrigger = 15;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/constants/ClimberConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ public class ClimberConstants {

public static final int CLIMBER_ID = 16;

public static final int CLIMBER_HEAD_ID = 0; // or 40? the electrical manual wasn't clear
public static final int CLIMBER_HEAD_ID = 40;

public static final String CANbus = "CANivore";

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/ElevatorConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ public class ElevatorConstants {
.withKD(0)
.withKG(0)
.withKI(0)
.withKP(0)
.withKP(2)
.withKS(0)
.withKV(0)
.withGravityType(GravityTypeValue.Elevator_Static);
Expand All @@ -32,5 +32,5 @@ public class ElevatorConstants {
public static final CurrentLimitsConfigs currentLimit = new CurrentLimitsConfigs();

public static final double lowerLimit = 0;
public static final double upperLimit = 100;
public static final double upperLimit = 298.5;
}
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/GripperConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ public class GripperConstants {
public static final CurrentLimitsConfigs currentLimit =
new CurrentLimitsConfigs().withStatorCurrentLimit(50);

public static final String canbus = "CANivore";
public static final String canbus = "rio";

public static final int gripperSensorChannel = 60;
public static final int gripperSensorChannel = 0;
}
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/VisionConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ public class VisionConstants {
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);

// Camera names, must match names configured on coprocessor
public static String camera0Name = "limelight-april";
public static String camera1Name = "limelight-april-right";
public static String camera0Name = "limelight-left";
public static String camera1Name = "limelight-right";
public static String camera2Name = "limelight-intake";
// public static String camera1Name = "camera_1";

Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/constants/WristConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,16 @@ public class WristConstants {
public static final int WRIST_MOTOR_ID = 11;
public static final String WRIST_CANBUS = "CANivore";

public static final int WRIST_THROUGHBORE_ENCODER_ID = 1;
public static final int WRIST_THROUGHBORE_ENCODER_ID = 0;

public static final double WRIST_KP = 5;
public static final double WRIST_KP = 8;
public static final double WRIST_KD = 0;
public static final double WRIST_KI = 0;

public static final double WRIST_TOLERANCE = 0.01;

public static final double WristCurrent = 0;

public static final double upperLimit = 100;
public static final double lowerLimit = 0;
public static final double upperLimit = 1.59;
public static final double lowerLimit = -1.58;
}
Loading
Loading