Skip to content

Commit

Permalink
fixed leftover problems with absolute encoder offset
Browse files Browse the repository at this point in the history
  • Loading branch information
MrTinker64 committed Jan 10, 2024
1 parent 0dab4fc commit 1f43f14
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 13 deletions.
11 changes: 0 additions & 11 deletions src/main/java/frc/robot/subsystems/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,6 @@ public class SwerveSubsystem extends SubsystemBase implements AutoCloseable {

private double[] desiredModuleStates = { 0, 0, 0, 0, 0, 0, 0, 0 };
private double[] currentStates = { 0, 0, 0, 0, 0, 0, 0, 0 };
private double[] encoderOffsets = { 0, 0, 0, 0 };

private final Field2d field2d = new Field2d();
private final FieldObject2d[] modules2d = new FieldObject2d[modules.size()];
Expand All @@ -94,9 +93,6 @@ public class SwerveSubsystem extends SubsystemBase implements AutoCloseable {
private DoubleArrayTopic m_desiredStatesTopic = inst.getDoubleArrayTopic("desired module states");
private DoubleArrayPublisher m_desiredStatesPublisher = m_desiredStatesTopic.publish();

private DoubleArrayTopic m_encoderOffsetTopic = inst.getDoubleArrayTopic("encoder offsets");
private DoubleArrayPublisher m_encoderOffsetPublisher = m_encoderOffsetTopic.publish();

public SwerveSubsystem() {
/* Threads are units of code. These threads call the zeroHeading method 1 sec
after the robot starts without interfering with the rest of the code */
Expand Down Expand Up @@ -171,13 +167,6 @@ public void updatePoseEstimator(){

m_statesPublisher.set(currentStates);

encoderOffsets[0] = m_frontLeft.getAbsoluteEncoderRad();
encoderOffsets[1] = m_frontRight.getAbsoluteEncoderRad();
encoderOffsets[2] = m_backLeft.getAbsoluteEncoderRad();
encoderOffsets[3] = m_backRight.getAbsoluteEncoderRad();

m_encoderOffsetPublisher.set(encoderOffsets);

for (int i = 0; i < modules.size(); i++) {
var transform = new Transform2d(DriveConstants.kModuleOffset[i], modules.get(i).getPosition().angle);
modules2d[i].setPose(getPose().transformBy(transform));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ public SwerveModuleState getDesiredState() {
}

@Override
public double getAbsoluteEncoderRad(){
public double getAbsoluteEncoderRotations(){
return 0.0;
}

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/lib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ public static SwerveModule create(int kDriveMotorId, int kTurningMotorId, boolea

// double getTurningVelocity();

double getAbsoluteEncoderRad();
double getAbsoluteEncoderRotations();

public default void stopMotors() {}

Expand Down

0 comments on commit 1f43f14

Please sign in to comment.