acmerobotics/road-runner-quickstart

lateralInPerTick is not the correct value

ftc19853 opened this issue · 3 comments

RR FTC Version

0.1.8

Observed Behavior

The robot was tested multiple times on LateralPushTest, sometimes even averaging out the lateralInPerTick that we got. However, we consistently got a value ~0.02, which with some simple testing and calculations, the robot was moving ~48 inches when supplied with ~2350 ticks, while lateralPushTest was showing -1000(Yes, negative) ticks for 24 inches. Should we go with the "wrong" value or is their an issue? Our encoders do seemed to be reversed in the same way as our motors as well when we did it here:

public DriveLocalizer() {
    leftFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftFront));
    leftBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftBack));
    rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack));
    rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));

    leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
    leftBack.setDirection(DcMotorSimple.Direction.REVERSE);

    lastLeftFrontPos = leftFront.getPositionAndVelocity().position;
    lastLeftBackPos = leftBack.getPositionAndVelocity().position;
    lastRightBackPos = rightBack.getPositionAndVelocity().position;
    lastRightFrontPos = rightFront.getPositionAndVelocity().position;

    lastHeading = Rotation2d.exp(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS));
}

and in

public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
   this.pose = pose;

   LynxFirmware.throwIfModulesAreOutdated(hardwareMap);

   for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
       module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
   }

   leftFront = hardwareMap.get(DcMotorEx.class, "Forward_Left");
   leftBack = hardwareMap.get(DcMotorEx.class, "Backward_Left");
   rightBack = hardwareMap.get(DcMotorEx.class, "Backward_Right");
   rightFront = hardwareMap.get(DcMotorEx.class, "Forward_Right");

   leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
   leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
   rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
   rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);

   leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
   leftBack.setDirection(DcMotorSimple.Direction.REVERSE);


   imu = hardwareMap.get(IMU.class, "imu");
   IMU.Parameters parameters = new IMU.Parameters(new RevHubOrientationOnRobot(
           RevHubOrientationOnRobot.LogoFacingDirection.UP,
           RevHubOrientationOnRobot.UsbFacingDirection.LEFT));
   imu.initialize(parameters);

   voltageSensor = hardwareMap.voltageSensor.iterator().next();

   localizer = new DriveLocalizer();

   FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}

as well

Tuning Files

No response

Robot Logs

No response

My bad, the instructions online should say leftward instead of rightward (this matches the coordinate system). I've since corrected them.

This still does not explain why it is ~300 ticks off. (its not 1000 ticks off as said in the issue) I don't think that all of that is lost from physical forces, because when calibrated it only moved around 18 inches when it was supposed to move 24. Here is the code:

public void runOpMode() {
        // Put initialization blocks here.
        MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
        waitForStart();
        
        
        if (opModeIsActive()) {
          Actions.runBlocking(
              drive.actionBuilder(drive.pose)
                   .strafeTo(new Vector2d(0,24))
                   .build());
}

Continuing in #326