Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
cherriae committed Mar 14, 2024
2 parents 0141ff7 + c84f4d8 commit ced063a
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 4 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public static class CAN {

public static class Speeds {
public static final double SWERVE_DRIVE_SLOW_COEFF = .6; // Default driving speed
public static final double SWERVE_DRIVE_FAST_COEFF = .85;
public static final double SWERVE_DRIVE_FAST_COEFF = 1;

public static final double SWERVE_DRIVE_MAX_SPEED = 4; // meters per second
public static final double SWERVE_DRIVE_MAX_ANGULAR_SPEED = Math.PI * 1; // TODO: Get this value
Expand Down Expand Up @@ -149,7 +149,7 @@ public static class Ports {
// static field constants
public static class FieldConstants {
// z: 2.2456 (USE THIS)
public static final double SPEAKER_HEIGHT = 2.25;
public static final double SPEAKER_HEIGHT = 2.13;

public static final double SHOOTER_SLOW_THRESHOLD = 2;
public static final double TAG_DISTANCE_THRESHOLD = 2;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/shooter/AutonShoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public AutonShoot(
addCommands(
// Parallel command group that aims, revs, and squeezes note. ONLY APPLIES TO PRELOADED NOTE.
new ParallelRaceGroup(
new SpinShooter(shooter, ShooterState.SHOOT).withTimeout(1.5),
new SpinShooter(shooter, ShooterState.SHOOT).withTimeout(3),
new AutoAim(shooter, elevator, leds, swerve, Presets.CLOSE_SHOOTER_ANGLE, Presets.CLOSE_ELEVATOR_HEIGHT, this::headingPreset).withTimeout(2),
new FeedActuate(intake, FeedMode.INTAKE).withTimeout(4)
).onlyIf(() -> !_preloadShot).andThen(() -> _preloadShot = true),
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/utils/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,14 @@
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.Constants;
import frc.robot.Constants.PID;
import frc.robot.Constants.Physical;
import frc.robot.utils.configs.TalonFXConfig;

/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/utils/configs/TalonFXConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ public static TalonFXConfiguration configureFalcon(TalonFX falcon, boolean inver
config.SoftwareLimitSwitch.ForwardSoftLimitEnable = false;
config.SoftwareLimitSwitch.ReverseSoftLimitEnable = false;

// config.CurrentLimits.StatorCurrentLimit = 50; // TODO: Find
// config.CurrentLimits.StatorCurrentLimit = 80; // TODO: Find

falcon.getConfigurator().apply(config);
falcon.setPosition(0);
Expand Down

0 comments on commit ced063a

Please sign in to comment.