FINALLY FIXED SWERVE
This commit is contained in:
@@ -50,10 +50,14 @@ public class RobotContainer {
|
|||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
driver.x().whileTrue(drivetrain.runFrontLeft());
|
driver.start().and(driver.x()).whileTrue(drivetrain.runFrontLeft(1, 0));
|
||||||
driver.y().whileTrue(drivetrain.runFrontRight());
|
driver.start().and(driver.y()).whileTrue(drivetrain.runFrontRight(1, 0));
|
||||||
driver.a().whileTrue(drivetrain.runRearLeft());
|
driver.start().and(driver.a()).whileTrue(drivetrain.runRearLeft(1, 0));
|
||||||
driver.b().whileTrue(drivetrain.runRearRight());
|
driver.start().and(driver.b()).whileTrue(drivetrain.runRearRight(1, 0));
|
||||||
|
driver.start().negate().and(driver.x()).whileTrue(drivetrain.runFrontLeft(0, 45));
|
||||||
|
driver.start().negate().and(driver.y()).whileTrue(drivetrain.runFrontRight(0, 45));
|
||||||
|
driver.start().negate().and(driver.a()).whileTrue(drivetrain.runRearLeft(0, 45));
|
||||||
|
driver.start().negate().and(driver.b()).whileTrue(drivetrain.runRearRight(0, 45));
|
||||||
driver.rightBumper().whileTrue(drivetrain.setX());
|
driver.rightBumper().whileTrue(drivetrain.setX());
|
||||||
|
|
||||||
//drivetrain.setDefaultCommand(drivetrain.disableOutputs());
|
//drivetrain.setDefaultCommand(drivetrain.disableOutputs());
|
||||||
|
|||||||
@@ -90,7 +90,8 @@ public class ModuleConstants {
|
|||||||
|
|
||||||
turningConfig
|
turningConfig
|
||||||
.idleMode(kTurnIdleMode)
|
.idleMode(kTurnIdleMode)
|
||||||
.smartCurrentLimit(kTurnMotorCurrentLimit);
|
.smartCurrentLimit(kTurnMotorCurrentLimit)
|
||||||
|
.inverted(true);
|
||||||
turningConfig.encoder
|
turningConfig.encoder
|
||||||
//.inverted(true)
|
//.inverted(true)
|
||||||
.positionConversionFactor(kTurningFactor)
|
.positionConversionFactor(kTurningFactor)
|
||||||
@@ -101,5 +102,6 @@ public class ModuleConstants {
|
|||||||
.outputRange(-1, 1)
|
.outputRange(-1, 1)
|
||||||
.positionWrappingEnabled(true)
|
.positionWrappingEnabled(true)
|
||||||
.positionWrappingInputRange(0, 2 * Math.PI);
|
.positionWrappingInputRange(0, 2 * Math.PI);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -134,32 +134,32 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
Logger.recordOutput("Drivetrain/Heading", getHeading());
|
Logger.recordOutput("Drivetrain/Heading", getHeading());
|
||||||
}
|
}
|
||||||
|
|
||||||
public Command runFrontLeft() {
|
public Command runFrontLeft(double staticSpeed, double staticAngleDegrees) {
|
||||||
return run(() -> {
|
return run(() -> {
|
||||||
frontLeft.setDesiredState(new SwerveModuleState(
|
frontLeft.setDesiredState(new SwerveModuleState(
|
||||||
1,
|
staticSpeed,
|
||||||
new Rotation2d()));
|
Rotation2d.fromDegrees(staticAngleDegrees)));
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
public Command runFrontRight() {
|
public Command runFrontRight(double staticSpeed, double staticAngleDegrees) {
|
||||||
return run(() -> {
|
return run(() -> {
|
||||||
frontRight.setDesiredState(new SwerveModuleState(
|
frontRight.setDesiredState(new SwerveModuleState(
|
||||||
1,
|
staticSpeed,
|
||||||
new Rotation2d()));
|
Rotation2d.fromDegrees(staticAngleDegrees)));
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
public Command runRearLeft() {
|
public Command runRearLeft(double staticSpeed, double staticAngleDegrees) {
|
||||||
return run(() -> {
|
return run(() -> {
|
||||||
rearLeft.setDesiredState(new SwerveModuleState(
|
rearLeft.setDesiredState(new SwerveModuleState(
|
||||||
1,
|
staticSpeed,
|
||||||
new Rotation2d()));
|
Rotation2d.fromDegrees(staticAngleDegrees)));
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
public Command runRearRight() {
|
public Command runRearRight(double staticSpeed, double staticAngleDegrees) {
|
||||||
return run(() -> {
|
return run(() -> {
|
||||||
rearRight.setDesiredState(new SwerveModuleState(
|
rearRight.setDesiredState(new SwerveModuleState(
|
||||||
1,
|
staticSpeed,
|
||||||
new Rotation2d()));
|
Rotation2d.fromDegrees(staticAngleDegrees)));
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user