Commiting general changes to try to fix swerve issues

This commit is contained in:
2024-03-10 11:09:17 -04:00
parent c7ee873b7e
commit 3046f2d256
8 changed files with 164 additions and 7 deletions

View File

@@ -13,9 +13,9 @@ public final class AutoConstants {
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
public static final double kPXController = 5;
public static final double kPYController = 5;
public static final double kPThetaController = 0.5; // needs to be separate from heading control
public static final double kPXController = 1.05;//5;
public static final double kPYController = 1.05;//5;
public static final double kPThetaController = 0.95;//0.5; // needs to be separate from heading control
public static final double kPHeadingController = 0.02; // for heading control NOT PATHING
public static final double kDHeadingController = 0.0025;

View File

@@ -26,16 +26,18 @@ public final class DrivetrainConstants {
new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
// Angular offsets of the modules relative to the chassis in radians
/*
public static final double kFrontLeftChassisAngularOffset = Math.PI;
public static final double kFrontRightChassisAngularOffset = -Math.PI / 2;
public static final double kBackLeftChassisAngularOffset = Math.PI / 2;
public static final double kBackRightChassisAngularOffset = 0;
*/
/*
public static final double kFrontLeftChassisAngularOffset = -2*Math.PI;
public static final double kFrontRightChassisAngularOffset = -2*Math.PI;
public static final double kBackLeftChassisAngularOffset = -2*Math.PI;
public static final double kBackRightChassisAngularOffset = -2*Math.PI-(4/180.0);
*/
// SPARK MAX CAN IDs
public static final int kFrontLeftDrivingCanId = 8;

View File

@@ -16,8 +16,8 @@ public class SwerveModuleConstants {
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
public static final double kWheelDiameterMeters = 0.0762;
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
// 45 teeth on the wheel's bevel gear, 20 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
public static final double kDrivingMotorReduction = (45.0 * 20) / (kDrivingMotorPinionTeeth * 15);
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
/ kDrivingMotorReduction;

View File

@@ -299,6 +299,7 @@ public class Drivetrain extends SubsystemBase {
}
public void driveWithChassisSpeeds(ChassisSpeeds speeds) {
//speeds.omegaRadiansPerSecond = -speeds.omegaRadiansPerSecond;
SwerveModuleState[] states = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(speeds);
m_frontLeft.setDesiredState(states[0]);