Adding module zeroing constants and a few other minor changes from 2/3 build session
This commit is contained in:
@@ -12,10 +12,10 @@ public class DrivetrainConstants {
|
||||
public static final double kTrackWidth = Units.inchesToMeters(23.75);
|
||||
public static final double kWheelBase = Units.inchesToMeters(18.75);
|
||||
|
||||
public static final double kFrontLeftMagEncoderOffset = 2.98;
|
||||
public static final double kFrontRightMagEncoderOffset = 1.18;
|
||||
public static final double kRearLeftMagEncoderOffset = 3.69;
|
||||
public static final double kRearRightMagEncoderOffset = 2.54;
|
||||
public static final double kFrontLeftMagEncoderOffset = 2.965;
|
||||
public static final double kFrontRightMagEncoderOffset = 1.120;
|
||||
public static final double kRearLeftMagEncoderOffset = 3.761;
|
||||
public static final double kRearRightMagEncoderOffset = 2.573;
|
||||
|
||||
public static final int kFrontLeftDrivingCANID = 0;
|
||||
public static final int kFrontRightDrivingCANID = 3;
|
||||
|
||||
@@ -48,34 +48,34 @@ public class Drivetrain extends SubsystemBase {
|
||||
frontLeft = new SwerveModule(
|
||||
"FrontLeft",
|
||||
DrivetrainConstants.kFrontLeftDrivingCANID,
|
||||
DrivetrainConstants.kFrontLeftTurningCANID);/*,
|
||||
DrivetrainConstants.kFrontLeftTurningCANID,
|
||||
DrivetrainConstants.kFrontLeftAnalogInPort,
|
||||
DrivetrainConstants.kFrontLeftMagEncoderOffset
|
||||
); */
|
||||
);
|
||||
|
||||
frontRight = new SwerveModule(
|
||||
"FrontRight",
|
||||
DrivetrainConstants.kFrontRightDrivingCANID,
|
||||
DrivetrainConstants.kFrontRightTurningCANID);/*,
|
||||
DrivetrainConstants.kFrontRightTurningCANID,
|
||||
DrivetrainConstants.kFrontRightAnalogInPort,
|
||||
DrivetrainConstants.kFrontRightMagEncoderOffset
|
||||
);*/
|
||||
);
|
||||
|
||||
rearLeft = new SwerveModule(
|
||||
"RearLeft",
|
||||
DrivetrainConstants.kRearLeftDrivingCANID,
|
||||
DrivetrainConstants.kRearLeftTurningCANID);/*,
|
||||
DrivetrainConstants.kRearLeftTurningCANID,
|
||||
DrivetrainConstants.kRearLeftAnalogInPort,
|
||||
DrivetrainConstants.kRearLeftMagEncoderOffset
|
||||
); */
|
||||
);
|
||||
|
||||
rearRight = new SwerveModule(
|
||||
"RearRight",
|
||||
DrivetrainConstants.kRearRightDrivingCANID,
|
||||
DrivetrainConstants.kRearRightTurningCANID);/*,
|
||||
DrivetrainConstants.kRearRightTurningCANID,
|
||||
DrivetrainConstants.kRearRightAnalogInPort,
|
||||
DrivetrainConstants.kRearRightMagEncoderOffset
|
||||
); */
|
||||
);
|
||||
|
||||
gyro = new AHRS(NavXComType.kMXP_SPI);
|
||||
|
||||
|
||||
23
src/main/java/frc/robot/utilities/SparkMAXTester.java
Normal file
23
src/main/java/frc/robot/utilities/SparkMAXTester.java
Normal file
@@ -0,0 +1,23 @@
|
||||
package frc.robot.utilities;
|
||||
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class SparkMAXTester extends SubsystemBase {
|
||||
private SparkMax spark;
|
||||
|
||||
public SparkMAXTester(int deviceID) {
|
||||
spark = new SparkMax(deviceID, MotorType.kBrushless);
|
||||
}
|
||||
|
||||
public Command setSpeed(DoubleSupplier speed) {
|
||||
return run(() -> {
|
||||
spark.set(speed.getAsDouble());
|
||||
});
|
||||
}
|
||||
}
|
||||
@@ -134,6 +134,7 @@ public class SwerveModule {
|
||||
}
|
||||
|
||||
public void periodic() {
|
||||
|
||||
if(!isAbsoluteEncoderDisabled) {
|
||||
Logger.recordOutput(moduleName + "/AbsoluteEncoder/Position", turningAbsoluteEncoder.get());
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user