Skip to content
This repository has been archived by the owner on Jan 6, 2024. It is now read-only.

Commit

Permalink
tune robot at Bellarmine
Browse files Browse the repository at this point in the history
  • Loading branch information
saikiranra committed Nov 8, 2023
1 parent d29c0b8 commit 0c426d4
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 10 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ private void configureButtonBindings() {
// driveController.leftStick();
// driveController.rightStick();
driveController.leftTrigger(0.3).onTrue(superstructure.getIntakeFloorCommand());
driveController.leftBumper().onTrue(superstructure.getIntakeShelfCommand());
// driveController.leftBumper().onTrue(superstructure.getIntakeShelfCommand());
driveController.rightTrigger(0.3).onTrue(superstructure.getScoreFinishCommand());
driveController.rightBumper().onTrue(superstructure.getIntakeSingleSubstationCommand());
driveController.back().onTrue(imu.getZeroCommand());
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/config/Config.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ public class Config {
public static final boolean SWERVE_MOTOR_LIMITS_ENABLED = true;
public static final PIDConstants SWERVE_TRANSLATION_PID = new PIDConstants(2.5, 0, 0);
public static final PIDConstants SWERVE_ROTATION_PID = new PIDConstants(4.5, 0, 0.1);
public static final PIDConstants SWERVE_ROTATION_SNAP_PID = new PIDConstants(7.5, 0, 0.5);
public static final PIDConstants SWERVE_ROTATION_SNAP_PID = new PIDConstants(7.5, 0, 1);
public static final boolean SWERVE_USE_FOC = true;

public static final int SWERVE_FL_DRIVE_MOTOR_ID = 2;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,16 +29,16 @@ public class Positions {
public static final SuperstructurePosition INTAKING_CONE_SHELF =
new SuperstructurePosition(Rotation2d.fromDegrees(90), Rotation2d.fromDegrees(180));
public static final SuperstructurePosition INTAKING_CONE_SINGLE_SUBSTATION =
new SuperstructurePosition(Rotation2d.fromDegrees(0), Rotation2d.fromDegrees(30));
new SuperstructurePosition(Rotation2d.fromDegrees(0), Rotation2d.fromDegrees(42));

public static final SuperstructurePosition CONE_NODE_LOW_FRONT =
new SuperstructurePosition(Rotation2d.fromDegrees(-19), Rotation2d.fromDegrees(-118.6));
public static final SuperstructurePosition CONE_NODE_LOW_BACK =
new SuperstructurePosition(Rotation2d.fromDegrees(0), Rotation2d.fromDegrees(89));
public static final SuperstructurePosition CONE_NODE_MID =
new SuperstructurePosition(Rotation2d.fromDegrees(125), Rotation2d.fromDegrees(-92));
new SuperstructurePosition(Rotation2d.fromDegrees(125), Rotation2d.fromDegrees(-90));
public static final SuperstructurePosition CONE_NODE_HIGH =
new SuperstructurePosition(Rotation2d.fromDegrees(110), Rotation2d.fromDegrees(145));
new SuperstructurePosition(Rotation2d.fromDegrees(130), Rotation2d.fromDegrees(-132));
public static final SuperstructurePosition YEET_CONE =
new SuperstructurePosition(Rotation2d.fromDegrees(50), Rotation2d.fromDegrees(135));

Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,9 @@ public SwerveModule(
driveMotorConfigs.Voltage.PeakForwardVoltage = 12;
driveMotorConfigs.Voltage.PeakReverseVoltage = -12;

CurrentLimitsConfigs currentLimits = new CurrentLimitsConfigs();
currentLimits.SupplyCurrentLimit = 35;
currentLimits.SupplyCurrentLimitEnable = true;
driveMotorConfigs.CurrentLimits.SupplyCurrentLimit = 15;
driveMotorConfigs.CurrentLimits.SupplyCurrentLimitEnable = true;
driveMotorConfigs.CurrentLimits.StatorCurrentLimitEnable = false;

if (constants.driveInversion) {
driveMotorConfigs.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
Expand Down Expand Up @@ -121,7 +121,7 @@ public SwerveModule(
steerMotorPID.setPositionPIDWrappingMinInput(0.0);
steerMotorPID.setPositionPIDWrappingMaxInput(1.0);

steerMotor.setSmartCurrentLimit(35);
steerMotor.setSmartCurrentLimit(15);

steerMotor.setInverted(constants.angleInversion);

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/swerve/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ public class SwerveSubsystem extends LifecycleSubsystem {
FRONT_LEFT_LOCATION, FRONT_RIGHT_LOCATION, BACK_LEFT_LOCATION, BACK_RIGHT_LOCATION);
public static final double MAX_VELOCITY =
((6080.0 / 60.0) / Config.SWERVE_DRIVE_GEARING_REDUCTION) * (Config.WHEEL_DIAMETER * Math.PI);
public static final double MAX_ANGULAR_VELOCITY = 20;
public static final double MAX_ANGULAR_VELOCITY = 15;

private final ImuSubsystem imu;
private final SwerveModule frontRight;
Expand Down

0 comments on commit 0c426d4

Please sign in to comment.