ElapsedTime - OnBot Java
Introduction to ElapsedTime
Quick Links
Full Code Example
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.Blinker;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.TouchSensor;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.util.ElapsedTime;
@TeleOp
public class HelloRobot_ElapsedTime extends LinearOpMode {
private Blinker control_Hub;
private DcMotor arm;
private DcMotor leftmotor;
private DcMotor rightmotor;
private DcMotor test_motor;
private Servo test_servo;
private TouchSensor test_touch;
private ElapsedTime runtime = new ElapsedTime();
@Override
public void runOpMode() {
control_Hub = hardwareMap.get(Blinker.class, "Control Hub");
arm = hardwareMap.get(DcMotor.class, "arm");
leftmotor = hardwareMap.get(DcMotor.class, "leftmotor");
rightmotor = hardwareMap.get(DcMotor.class, "rightmotor");
test_motor = hardwareMap.get(DcMotor.class, "test_motor");
test_servo = hardwareMap.get(Servo.class, "test_servo");
test_touch = hardwareMap.get(TouchSensor.class, "test_touch");
rightmotor.setDirection(DcMotorSimple.Direction.REVERSE);
telemetry.addData("Status", "Initialized");
telemetry.update();
// Wait for the game to start (driver presses PLAY)
waitForStart();
runtime.reset();
while (opModeIsActive() && (runtime.seconds() <= 3.0)) {
leftmotor.setPower(1);
rightmotor.setPower(1);
telemetry.addData("Number of Seconds in Phase 1", runtime.seconds());
telemetry.update();
}
runtime.reset();
while (opModeIsActive() && (runtime.seconds() <= 3.0)) {
leftmotor.setPower(-1);
rightmotor.setPower(-1);
telemetry.addData("Number of Seconds in Phase 2", runtime.seconds());
telemetry.update();
}
}
}Last updated
Was this helpful?

