Move drive encoder reversal before first get
Changing the direction of an encoder after reading it the first time will create a potentially massive delta in the first odometry update.
This commit is contained in:
@ -133,15 +133,15 @@ public final class MecanumDrive {
|
|||||||
rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack));
|
rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack));
|
||||||
rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));
|
rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));
|
||||||
|
|
||||||
|
// TODO: reverse encoders if needed
|
||||||
|
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
lastLeftFrontPos = leftFront.getPositionAndVelocity().position;
|
lastLeftFrontPos = leftFront.getPositionAndVelocity().position;
|
||||||
lastLeftBackPos = leftBack.getPositionAndVelocity().position;
|
lastLeftBackPos = leftBack.getPositionAndVelocity().position;
|
||||||
lastRightBackPos = rightBack.getPositionAndVelocity().position;
|
lastRightBackPos = rightBack.getPositionAndVelocity().position;
|
||||||
lastRightFrontPos = rightFront.getPositionAndVelocity().position;
|
lastRightFrontPos = rightFront.getPositionAndVelocity().position;
|
||||||
|
|
||||||
lastHeading = Rotation2d.exp(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS));
|
lastHeading = Rotation2d.exp(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS));
|
||||||
|
|
||||||
// TODO: reverse encoders if needed
|
|
||||||
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
|
@ -136,9 +136,7 @@ public final class TankDrive {
|
|||||||
for (DcMotorEx m : leftMotors) {
|
for (DcMotorEx m : leftMotors) {
|
||||||
Encoder e = new OverflowEncoder(new RawEncoder(m));
|
Encoder e = new OverflowEncoder(new RawEncoder(m));
|
||||||
leftEncs.add(e);
|
leftEncs.add(e);
|
||||||
lastLeftPos += e.getPositionAndVelocity().position;
|
|
||||||
}
|
}
|
||||||
lastLeftPos /= leftEncs.size();
|
|
||||||
this.leftEncs = Collections.unmodifiableList(leftEncs);
|
this.leftEncs = Collections.unmodifiableList(leftEncs);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -147,14 +145,22 @@ public final class TankDrive {
|
|||||||
for (DcMotorEx m : rightMotors) {
|
for (DcMotorEx m : rightMotors) {
|
||||||
Encoder e = new OverflowEncoder(new RawEncoder(m));
|
Encoder e = new OverflowEncoder(new RawEncoder(m));
|
||||||
rightEncs.add(e);
|
rightEncs.add(e);
|
||||||
lastRightPos += e.getPositionAndVelocity().position;
|
|
||||||
}
|
}
|
||||||
lastRightPos /= rightEncs.size();
|
|
||||||
this.rightEncs = Collections.unmodifiableList(rightEncs);
|
this.rightEncs = Collections.unmodifiableList(rightEncs);
|
||||||
}
|
}
|
||||||
|
|
||||||
// TODO: reverse encoder directions if needed
|
// TODO: reverse encoder directions if needed
|
||||||
// leftEncs.get(0).setDirection(DcMotorSimple.Direction.REVERSE);
|
// leftEncs.get(0).setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
|
for (Encoder e : leftEncs) {
|
||||||
|
lastLeftPos += e.getPositionAndVelocity().position;
|
||||||
|
}
|
||||||
|
lastLeftPos /= leftEncs.size();
|
||||||
|
|
||||||
|
for (Encoder e : rightEncs) {
|
||||||
|
lastRightPos += e.getPositionAndVelocity().position;
|
||||||
|
}
|
||||||
|
lastRightPos /= rightEncs.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
|
Reference in New Issue
Block a user