Skip to content
Open
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
1 change: 1 addition & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
[submodule "src/main/java/frc/trigon/lib"]
path = src/main/java/frc/trigon/lib
url = https://github.com/Programming-TRIGON/TRIGONLib
branch = subsystem-wrapper
20 changes: 15 additions & 5 deletions src/main/java/frc/trigon/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,10 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.trigon.lib.subsystems.MotorSubsystem;
import frc.trigon.lib.subsystems.flywheel.SimpleMotorSubsystem;
import frc.trigon.lib.subsystems.flywheel.SimpleMotorSubsystemCommands;
import frc.trigon.lib.utilities.flippable.Flippable;
import frc.trigon.robot.commands.CommandConstants;
import frc.trigon.robot.commands.commandfactories.GeneralCommands;
import frc.trigon.robot.constants.AutonomousConstants;
import frc.trigon.robot.constants.CameraConstants;
Expand All @@ -19,7 +21,8 @@
import frc.trigon.robot.misc.objectdetectioncamera.ObjectPoseEstimator;
import frc.trigon.robot.misc.simulatedfield.SimulatedGamePieceConstants;
import frc.trigon.robot.poseestimation.poseestimator.PoseEstimator;
import frc.trigon.robot.subsystems.MotorSubsystem;
import frc.trigon.robot.subsystems.flyWheel.FlyWheel;
import frc.trigon.robot.subsystems.flyWheel.FlyWheelConstants;
Comment on lines +24 to +25
Copy link

Choose a reason for hiding this comment

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

🧹 Nitpick | 🔵 Trivial

Package name flyWheel should be lowercase.

Java package naming convention uses all lowercase. Consider renaming to flywheel for consistency.

import frc.trigon.robot.subsystems.swerve.Swerve;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

Expand All @@ -32,6 +35,9 @@ public class RobotContainer {
CameraConstants.OBJECT_DETECTION_CAMERA
);
public static final Swerve SWERVE = new Swerve();
// public static final ArmSubsystem ARM = new Arm();
// public static final ElevatorSubsystem ELEVATOR = new Elevator();
public static final SimpleMotorSubsystem FLY_WHEEL = new FlyWheel();
private LoggedDashboardChooser<Command> autoChooser;

public RobotContainer() {
Expand All @@ -54,12 +60,16 @@ private void configureBindings() {

private void bindDefaultCommands() {
SWERVE.setDefaultCommand(GeneralCommands.getFieldRelativeDriveCommand());
// ARM.setDefaultCommand(ArmSubsystemCommands.getSetTargetStateCommand(ArmConstants.ArmState.REST, ARM));
// ELEVATOR.setDefaultCommand(ElevatorSubsystemCommands.getSetTargetStateCommand(ElevatorConstants.ElevatorState.REST,ELEVATOR));
FLY_WHEEL.setDefaultCommand(SimpleMotorSubsystemCommands.getSetTargetStateCommand(FlyWheelConstants.FlyWheelState.REST, FLY_WHEEL));
}

private void bindControllerCommands() {
OperatorConstants.RESET_HEADING_TRIGGER.onTrue(CommandConstants.RESET_HEADING_COMMAND);
OperatorConstants.DRIVE_FROM_DPAD_TRIGGER.whileTrue(CommandConstants.SELF_RELATIVE_DRIVE_FROM_DPAD_COMMAND);
OperatorConstants.TOGGLE_BRAKE_TRIGGER.onTrue(GeneralCommands.getToggleBrakeCommand());
// OperatorConstants.RESET_HEADING_TRIGGER.onTrue(CommandConstants.RESET_HEADING_COMMAND);
// OperatorConstants.DRIVE_FROM_DPAD_TRIGGER.whileTrue(CommandConstants.SELF_RELATIVE_DRIVE_FROM_DPAD_COMMAND);
// OperatorConstants.TOGGLE_BRAKE_TRIGGER.onTrue(GeneralCommands.getToggleBrakeCommand());
OperatorConstants.INTAKE_TRIGGER.whileTrue(SimpleMotorSubsystemCommands.getSetTargetStateCommand(FlyWheelConstants.FlyWheelState.INTAKE, FLY_WHEEL));
}

private void configureSysIDBindings(MotorSubsystem subsystem) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
import edu.wpi.first.wpilibj2.command.*;
import frc.trigon.robot.commands.CommandConstants;
import frc.trigon.robot.constants.OperatorConstants;
import frc.trigon.robot.subsystems.MotorSubsystem;
import frc.trigon.robot.subsystems.swerve.SwerveCommands;
import frc.trigon.lib.subsystems.MotorSubsystem;

import java.util.function.BooleanSupplier;

Expand All @@ -14,7 +14,7 @@
*/
public class GeneralCommands {
public static Command getFieldRelativeDriveCommand() {
return SwerveCommands.getClosedLoopFieldRelativeDriveCommand(
return SwerveCommands.getOpenLoopFieldRelativeDriveCommand(
() -> CommandConstants.calculateDriveStickAxisValue(OperatorConstants.DRIVER_CONTROLLER.getLeftY()),
() -> CommandConstants.calculateDriveStickAxisValue(OperatorConstants.DRIVER_CONTROLLER.getLeftX()),
() -> CommandConstants.calculateDriveStickAxisValue(OperatorConstants.DRIVER_CONTROLLER.getRightX())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,13 @@
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.trigon.lib.hardware.misc.KeyboardController;
import frc.trigon.lib.hardware.misc.XboxController;
import frc.trigon.robot.commands.commandclasses.IntakeAssistCommand;
Copy link

Choose a reason for hiding this comment

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

🧹 Nitpick | 🔵 Trivial

Unused import.

IntakeAssistCommand is imported but not referenced anywhere in this file. Remove it to keep imports clean.


import java.util.function.DoubleUnaryOperator;

public class OperatorConstants {
public static final double DRIVER_CONTROLLER_DEADBAND = 0.07;
private static final int DRIVER_CONTROLLER_PORT = 0;
private static final int DRIVER_CONTROLLER_PORT = 1;
private static final int
DRIVER_CONTROLLER_RIGHT_STICK_EXPONENT = 1,
DRIVER_CONTROLLER_LEFT_STICK_EXPONENT = 2;
Expand Down Expand Up @@ -43,5 +44,6 @@ public class OperatorConstants {
FORWARD_QUASISTATIC_CHARACTERIZATION_TRIGGER = OPERATOR_CONTROLLER.right(),
BACKWARD_QUASISTATIC_CHARACTERIZATION_TRIGGER = OPERATOR_CONTROLLER.left(),
FORWARD_DYNAMIC_CHARACTERIZATION_TRIGGER = OPERATOR_CONTROLLER.up(),
BACKWARD_DYNAMIC_CHARACTERIZATION_TRIGGER = OPERATOR_CONTROLLER.down();
BACKWARD_DYNAMIC_CHARACTERIZATION_TRIGGER = OPERATOR_CONTROLLER.down(),
INTAKE_TRIGGER = DRIVER_CONTROLLER.leftTrigger();
}
171 changes: 0 additions & 171 deletions src/main/java/frc/trigon/robot/subsystems/MotorSubsystem.java

This file was deleted.

12 changes: 12 additions & 0 deletions src/main/java/frc/trigon/robot/subsystems/arm/Arm.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
package frc.trigon.robot.subsystems.arm;

import edu.wpi.first.math.geometry.Pose3d;
import frc.trigon.lib.hardware.phoenix6.talonfx.TalonFXMotor;
import frc.trigon.lib.subsystems.arm.ArmSubsystem;
import frc.trigon.lib.subsystems.arm.ArmSubsystemConfiguration;
Comment on lines +4 to +6
Copy link

Choose a reason for hiding this comment

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

🧹 Nitpick | 🔵 Trivial

Remove unused imports.

TalonFXMotor and ArmSubsystemConfiguration are not used in this file.

Suggested fix
 package frc.trigon.robot.subsystems.arm;

 import edu.wpi.first.math.geometry.Pose3d;
-import frc.trigon.lib.hardware.phoenix6.talonfx.TalonFXMotor;
 import frc.trigon.lib.subsystems.arm.ArmSubsystem;
-import frc.trigon.lib.subsystems.arm.ArmSubsystemConfiguration;

 public class Arm extends ArmSubsystem {
📝 Committable suggestion

‼️ IMPORTANT
Carefully review the code before committing. Ensure that it accurately replaces the highlighted code, contains no missing lines, and has no issues with indentation. Thoroughly test & benchmark the code to ensure it meets the requirements.

Suggested change
import frc.trigon.lib.hardware.phoenix6.talonfx.TalonFXMotor;
import frc.trigon.lib.subsystems.arm.ArmSubsystem;
import frc.trigon.lib.subsystems.arm.ArmSubsystemConfiguration;
package frc.trigon.robot.subsystems.arm;
import edu.wpi.first.math.geometry.Pose3d;
import frc.trigon.lib.subsystems.arm.ArmSubsystem;
public class Arm extends ArmSubsystem {


public class Arm extends ArmSubsystem {
public Arm() {
super(ArmConstants.MASTER_MOTOR, ArmConstants.ARM_CONFIG, new Pose3d());
}
}
Loading