mirror of
https://github.com/Team4388/Swerve-Drive.git
synced 2026-06-09 08:48:06 -06:00
Left Back
This commit is contained in:
@@ -31,6 +31,7 @@ public final class Constants {
|
||||
|
||||
public static final class SwerveDriveConstants {
|
||||
public static final double ROTATION_SPEED = 0.1;
|
||||
public static final double WHEEL_SPEED = 0.1;
|
||||
public static final double WIDTH = 0;
|
||||
public static final double HEIGHT = 0;
|
||||
public static final int LEFT_FRONT_STEER_CAN_ID = 0;
|
||||
|
||||
@@ -79,7 +79,12 @@ public class SwerveDrive
|
||||
|
||||
// Back right module state
|
||||
SwerveModuleState rightBack = SwerveModuleState.optimize(moduleStates[3], new Rotation2d(m_rightBackEncoder.getPosition()));
|
||||
|
||||
|
||||
m_leftFrontWheelMotor.set(m_leftFrontSteerMotor.get() + leftFront.speedMetersPerSecond * SwerveDriveConstants.WHEEL_SPEED);
|
||||
m_rightFrontWheelMotor.set(m_rightFrontSteerMotor.get() + rightFront.speedMetersPerSecond * SwerveDriveConstants.WHEEL_SPEED);
|
||||
m_leftBackWheelMotor.set(m_leftBackSteerMotor.get() + lefBack.speedMetersPerSecond * SwerveDriveConstants.WHEEL_SPEED);
|
||||
m_rightBackWheelMotor.set(m_rightBackSteerMotor.get() + rightBack.speedMetersPerSecond * SwerveDriveConstants.WHEEL_SPEED);
|
||||
|
||||
}
|
||||
|
||||
// public void driveFieldRelative(double awayFromStation, double towardLeftBoundary, double rotate)
|
||||
|
||||
Reference in New Issue
Block a user