Add encoder reverse directions to dead wheel localizers
Direction doesn't matter for position regression, but it does matter for `inPerTick`, `lateralInPerTick`. And everything makes more sense if the directions are correct.
This commit is contained in:
@ -11,6 +11,7 @@ import com.acmerobotics.roadrunner.ftc.OverflowEncoder;
|
||||
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
|
||||
@ -37,6 +38,9 @@ public final class ThreeDeadWheelLocalizer implements Localizer {
|
||||
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;
|
||||
|
@ -12,6 +12,7 @@ import com.acmerobotics.roadrunner.ftc.OverflowEncoder;
|
||||
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;
|
||||
|
||||
@ -42,6 +43,10 @@ public final class TwoDeadWheelLocalizer implements Localizer {
|
||||
// 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;
|
||||
|
Reference in New Issue
Block a user