Swerve diagnosing
This commit is contained in:
parent
0e308e2986
commit
3fec792691
@ -10,9 +10,9 @@ public final class DrivetrainConstants {
|
|||||||
public static final double kMaxSpeedMetersPerSecond = 4.1;
|
public static final double kMaxSpeedMetersPerSecond = 4.1;
|
||||||
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
|
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
|
||||||
|
|
||||||
public static final double kDirectionSlewRate = 2.4; // radians per second
|
public static final double kDirectionSlewRate = 4.8; // radians per second
|
||||||
public static final double kMagnitudeSlewRate = 3.2; // percent per second (1 = 100%)
|
public static final double kMagnitudeSlewRate = 6.4; // percent per second (1 = 100%)
|
||||||
public static final double kRotationalSlewRate = 4.0; // percent per second (1 = 100%)
|
public static final double kRotationalSlewRate = 8.0; // percent per second (1 = 100%)
|
||||||
|
|
||||||
// Chassis configuration
|
// Chassis configuration
|
||||||
public static final double kTrackWidth = Units.inchesToMeters(28-1.75*2);
|
public static final double kTrackWidth = Units.inchesToMeters(28-1.75*2);
|
||||||
@ -26,10 +26,10 @@ public final class DrivetrainConstants {
|
|||||||
new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
|
new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
|
||||||
|
|
||||||
// Angular offsets of the modules relative to the chassis in radians
|
// Angular offsets of the modules relative to the chassis in radians
|
||||||
public static final double kFrontLeftChassisAngularOffset = -Math.PI / 2;
|
public static final double kFrontLeftChassisAngularOffset = Math.PI;
|
||||||
public static final double kFrontRightChassisAngularOffset = 0;
|
public static final double kFrontRightChassisAngularOffset = -Math.PI / 2;
|
||||||
public static final double kBackLeftChassisAngularOffset = Math.PI;
|
public static final double kBackLeftChassisAngularOffset = Math.PI / 2;
|
||||||
public static final double kBackRightChassisAngularOffset = Math.PI / 2;
|
public static final double kBackRightChassisAngularOffset = 0;
|
||||||
|
|
||||||
// SPARK MAX CAN IDs
|
// SPARK MAX CAN IDs
|
||||||
public static final int kFrontLeftDrivingCanId = 8;
|
public static final int kFrontLeftDrivingCanId = 8;
|
||||||
|
@ -301,7 +301,7 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
-MathUtil.applyDeadband(ySpeed.getAsDouble(), deadband),
|
-MathUtil.applyDeadband(ySpeed.getAsDouble(), deadband),
|
||||||
-MathUtil.applyDeadband(rotation.getAsDouble(), deadband),
|
-MathUtil.applyDeadband(rotation.getAsDouble(), deadband),
|
||||||
() -> fieldRelativeControl,
|
() -> fieldRelativeControl,
|
||||||
false
|
true
|
||||||
);
|
);
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user