Skip to content

Commit

Permalink
Add encoder reverse directions to dead wheel localizers
Browse files Browse the repository at this point in the history
Direction doesn't matter for position regression, but it does matter
for `inPerTick`, `lateralInPerTick`. And everything makes more sense
if the directions are correct.
  • Loading branch information
rbrott committed Dec 23, 2023
1 parent ce080b0 commit a890105
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ public DriveLocalizer() {
rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));

// TODO: reverse encoders if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);

lastLeftFrontPos = leftFront.getPositionAndVelocity().position;
lastLeftBackPos = leftBack.getPositionAndVelocity().position;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ public DriveLocalizer() {
}

// 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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
import com.acmerobotics.roadrunner.ftc.RawEncoder;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;

@Config
Expand All @@ -37,6 +38,9 @@ public ThreeDeadWheelLocalizer(HardwareMap hardwareMap, double inPerTick) {
par1 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par1")));
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));

// TODO: reverse encoder directions if needed
// par0.setDirection(DcMotorSimple.Direction.REVERSE);

lastPar0Pos = par0.getPositionAndVelocity().position;
lastPar1Pos = par1.getPositionAndVelocity().position;
lastPerpPos = perp.getPositionAndVelocity().position;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
import com.acmerobotics.roadrunner.ftc.RawEncoder;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.IMU;

Expand Down Expand Up @@ -42,6 +43,10 @@ public TwoDeadWheelLocalizer(HardwareMap hardwareMap, IMU imu, double inPerTick)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
par = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par")));
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));

// TODO: reverse encoder directions if needed
// par.setDirection(DcMotorSimple.Direction.REVERSE);

this.imu = imu;

lastParPos = par.getPositionAndVelocity().position;
Expand Down

0 comments on commit a890105

Please sign in to comment.