Class TrackingWheelLateralDistanceTuner

java.lang.Object
com.qualcomm.robotcore.eventloop.opmode.OpMode
com.qualcomm.robotcore.eventloop.opmode.LinearOpMode
org.firstinspires.ftc.teamcode.subsystems.roadrunner.drive.opmode.TrackingWheelLateralDistanceTuner

@TeleOp(group="drive") public class TrackingWheelLateralDistanceTuner extends com.qualcomm.robotcore.eventloop.opmode.LinearOpMode
Opmode designed to assist the user in tuning the `StandardTrackingWheelLocalizer`'s LATERAL_DISTANCE value. The LATERAL_DISTANCE is the center-to-center distance of the parallel wheels.

Tuning Routine:

1. Set the LATERAL_DISTANCE value in StandardTrackingWheelLocalizer.java to the physical measured value. This need only be an estimated value as you will be tuning it anyways.

2. Make a mark on the bot (with a piece of tape or sharpie or however you wish) and make an similar mark right below the indicator on your bot. This will be your reference point to ensure you've turned exactly 360°.

3. Although not entirely necessary, having the bot's pose being drawn in dashbooard does help identify discrepancies in the LATERAL_DISTANCE value. To access the dashboard, connect your computer to the RC's WiFi network. In your browser, navigate to https://192.168.49.1:8080/dash if you're using the RC phone or https://192.168.43.1:8080/dash if you are using the Control Hub. Ensure the field is showing (select the field view in top right of the page).

4. Press play to begin the tuning routine.

5. Use the right joystick on gamepad 1 to turn the bot counterclockwise.

6. Spin the bot 10 times, counterclockwise. Make sure to keep track of these turns.

7. Once the bot has finished spinning 10 times, press A to finishing the routine. The indicators on the bot and on the ground you created earlier should be lined up.

8. Your effective LATERAL_DISTANCE will be given. Stick this value into your StandardTrackingWheelLocalizer.java class.

9. If this value is incorrect, run the routine again while adjusting the LATERAL_DISTANCE value yourself. Read the heading output and follow the advice stated in the note below to manually nudge the values yourself.

Note: It helps to pay attention to how the pose on the field is drawn in dashboard. A blue circle with a line from the circumference to the center should be present, representing the bot. The line indicates forward. If your LATERAL_DISTANCE value is tuned currently, the pose drawn in dashboard should keep track with the pose of your actual bot. If the drawn bot turns slower than the actual bot, the LATERAL_DISTANCE should be decreased. If the drawn bot turns faster than the actual bot, the LATERAL_DISTANCE should be increased.

If your drawn bot oscillates around a point in dashboard, don't worry. This is because the position of the perpendicular wheel isn't perfectly set and causes a discrepancy in the effective center of rotation. You can ignore this effect. The center of rotation will be offset slightly but your heading will still be fine. This does not affect your overall tracking precision. The heading should still line up.

  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    com.qualcomm.robotcore.hardware.Gamepad
     
    com.qualcomm.robotcore.hardware.Gamepad
     
    com.qualcomm.robotcore.hardware.HardwareMap
     
    static final int
     
    int
    Deprecated.
    static int
     
    org.firstinspires.ftc.robotcore.external.Telemetry
     

    Fields inherited from class com.qualcomm.robotcore.eventloop.opmode.OpMode

    msStuckDetectInit, msStuckDetectInitLoop, msStuckDetectLoop, msStuckDetectStart, time
  • Constructor Summary

    Constructors
    Constructor
    Description
     
  • Method Summary

    Modifier and Type
    Method
    Description
    final void
     
    void
     

    Methods inherited from class com.qualcomm.robotcore.eventloop.opmode.LinearOpMode

    idle, init, init_loop, isStarted, isStopRequested, loop, opModeInInit, opModeIsActive, sleep, start, stop, waitForStart

    Methods inherited from class com.qualcomm.robotcore.eventloop.opmode.OpMode

    getRuntime, internalPostInitLoop, internalPostLoop, internalPreInit, internalUpdateTelemetryNow, resetRuntime, terminateOpModeNow, updateTelemetry

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • NUM_TURNS

      public static int NUM_TURNS
    • MS_BEFORE_FORCE_STOP_AFTER_STOP_REQUESTED

      public static final int MS_BEFORE_FORCE_STOP_AFTER_STOP_REQUESTED
      See Also:
    • gamepad1

      public volatile com.qualcomm.robotcore.hardware.Gamepad gamepad1
    • gamepad2

      public volatile com.qualcomm.robotcore.hardware.Gamepad gamepad2
    • telemetry

      public org.firstinspires.ftc.robotcore.external.Telemetry telemetry
    • hardwareMap

      public volatile com.qualcomm.robotcore.hardware.HardwareMap hardwareMap
    • msStuckDetectStop

      @Deprecated public int msStuckDetectStop
      Deprecated.
  • Constructor Details

    • TrackingWheelLateralDistanceTuner

      public TrackingWheelLateralDistanceTuner()
  • Method Details

    • runOpMode

      public void runOpMode() throws InterruptedException
      Specified by:
      runOpMode in class com.qualcomm.robotcore.eventloop.opmode.LinearOpMode
      Throws:
      InterruptedException
    • requestOpModeStop

      public final void requestOpModeStop()