Skip to content

Commit

Permalink
yay i did stuff
Browse files Browse the repository at this point in the history
  • Loading branch information
Ishan1522 committed Oct 4, 2024
1 parent f72b871 commit 4458422
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 6 deletions.
1 change: 0 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.robot.subsystems.vision.VisionSubsystem;

/**
* The VM is configured to automatically run this class, and to call the functions corresponding to
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -118,8 +118,8 @@ private void configureButtonBindings() {
DoubleSupplier driverRightStickX = driverController::getRightX;
DoubleSupplier driverLeftStick[] =
new DoubleSupplier[] {
() -> Util.modifyAxisPolar(driverLeftStickX, driverLeftStickY, 2)[0],
() -> Util.modifyAxisPolar(driverLeftStickX, driverLeftStickY, 2)[1]
() -> Util.modifyAxisPolar(driverLeftStickX, driverLeftStickY, 3)[0],
() -> Util.modifyAxisPolar(driverLeftStickX, driverLeftStickY, 3)[1]
};

Trigger driverRightBumper = new Trigger(driverController::getRightBumper);
Expand Down Expand Up @@ -161,7 +161,7 @@ private void configureButtonBindings() {
Command driveCommand = new Drive(driveSubsystem, visionSubsystem,
driverLeftStick[1],
driverLeftStick[0],
() -> Util.modifyAxis(driverRightStickX, 2),
() -> Util.modifyAxis(driverRightStickX, 3),
() -> !driverRightBumper.getAsBoolean(),
() -> driverLeftBumper.getAsBoolean());

Expand Down
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/subsystems/swerve/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public class DriveSubsystem extends SubsystemBase {
private static final ModuleLimits currentModuleLimits =
new ModuleLimits(
DriveConstants.MAX_SPEED_METERS_PER_SECOND,
4,
10,
DriveConstants.MAX_ANGULAR_SPEED_RADIANS_PER_SECOND);
private SwerveSetpointGenerator setpointGenerator;
private SwerveSetpoint currentSetpoint;
Expand Down Expand Up @@ -222,7 +222,7 @@ private static Translation2d convertSwerveStateToVelocityVector(SwerveModuleStat
}

public double getSkidRatio() {
return getSkiddingRatio(moduleStates(), DriveConstants.DRIVE_KINEMATICS);
return getSkiddingRatio(getModuleStates(), DriveConstants.DRIVE_KINEMATICS);
}

public boolean isSkidding() {
Expand Down Expand Up @@ -469,5 +469,7 @@ public void periodic() {
SmartDashboard.putBoolean("screwed", Math.abs(pose.getX()) > 20);
SmartDashboard.putString("odometry", pose.toString());
SmartDashboard.putNumber("speakerDistance", pose.getTranslation().getDistance(SmarterDashboardRegistry.getSpeakerPos()));

SmartDashboard.putNumber("skid ratio", getSkidRatio());
}
}

0 comments on commit 4458422

Please sign in to comment.