Skip to content

Commit

Permalink
Changes to allow manually monitoring the position during init_loop().
Browse files Browse the repository at this point in the history
  • Loading branch information
rhsftc committed Nov 17, 2024
1 parent c169c3f commit 4a79133
Showing 1 changed file with 6 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ public class EncoderTest extends OpMode {
private ElapsedTime runtime = new ElapsedTime();
private GamepadEx gamePad;
private DcMotorEx motor;
private DcMotor.RunMode mode;
private final float ENCODER_INCREMENT = 145.1f * 50f; // 10 revolutions
private final double MAX_VELOCITY = 2900;
private double RUN_VELOCITY = MAX_VELOCITY * .7f;
Expand All @@ -67,8 +66,10 @@ public void init() {
telemetry.update();
gamePad = new GamepadEx(gamepad1);
motor = hardwareMap.get(DcMotorEx.class, "motor");
motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
motor.setDirection(DcMotorSimple.Direction.FORWARD);
// Make sure the motor is stopped and encoder is set to 0;
stopAndResetEncoder(motor);
// Use encoders to enable manual movement of the motor to deternmine position values.
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
pidfVelocityCoefficients = motor.getPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER);
pidfPositionCoefficients = motor.getPIDFCoefficients(DcMotor.RunMode.RUN_TO_POSITION);
Expand All @@ -91,6 +92,7 @@ public void init() {
public void init_loop() {
telemetry.addLine("Dpad Up and Dpad Down");
telemetry.addLine("Y - Stop and Reset");
telemetry.addLine("Position is monitored real-time.");
telemetry.addData("Position", motor.getCurrentPosition());
telemetry.update();
}
Expand Down Expand Up @@ -128,14 +130,13 @@ public void loop() {
stopAndResetEncoder(motor);
}

mode = motor.getMode();
telemetry.addData("Target", "%d", motor.getTargetPosition());
telemetry.addData("Position", "%d", motor.getCurrentPosition());
telemetry.addData("Velocity", "%6.2f", motor.getVelocity());
telemetry.addData("Power", "%6.2f", motor.getPower());
telemetry.addData("Busy", motor.isBusy());
telemetry.addData("Current (milli amps)", "%6.2f", motor.getCurrent(CurrentUnit.MILLIAMPS));
telemetry.addData("Mode", mode);
telemetry.addData("Mode", motor.getMode());
telemetry.addData("PIDF Run Using", motor.getPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER));
telemetry.addData("PIDF Run To Position", motor.getPIDFCoefficients(DcMotor.RunMode.RUN_TO_POSITION));
telemetry.update();
Expand Down

0 comments on commit 4a79133

Please sign in to comment.