-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathDriveCircleLogging.java
99 lines (70 loc) · 2.6 KB
/
DriveCircleLogging.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
// simple autonomous program that drives bot in a circle then ends.
// this code assumes it will end before the period is over but if the period ended while
// still driving, this code will just stop. Stops after 5 seconds or on touch sensor button.
// This sample shows the use of logging to a file for debugging purposes.
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.TouchSensor;
@Autonomous(name="Drive Circle Logging", group="Exercises")
//@Disabled
public class DriveCircleLogging extends LinearOpMode
{
DcMotor leftMotor;
DcMotor rightMotor;
TouchSensor touch;
// Use class constructor to initialize logging system.
public DriveCircleLogging() throws Exception
{
Logging.setup();
Logging.log("Starting Drive Circle Logging");
}
// called when init button is pressed.
@Override
public void runOpMode() throws InterruptedException
{
leftMotor = hardwareMap.dcMotor.get("left_motor");
rightMotor = hardwareMap.dcMotor.get("right_motor");
leftMotor.setDirection(DcMotor.Direction.REVERSE);
touch = hardwareMap.touchSensor.get("touch_sensor");
telemetry.addData("Mode", "waiting");
telemetry.update();
Logging.log("waiting for start");
// wait for start button.
waitForStart();
telemetry.addData("Mode", "running");
telemetry.update();
Logging.log("running");
sleep(1000);
// set power levels 75% left and 10% right to drive in an arc to the right.
leftMotor.setPower(0.75);
rightMotor.setPower(0.20);
resetStartTime();
// drive until touch sensor button pressed or 5 seconds passes.
boolean stopFlag = false;
while (opModeIsActive() && !stopFlag)
{
if (getRuntime() > 5)
{
Logging.log("timeout");
stopFlag = true;
}
if (touch.isPressed())
{
Logging.log("button touched");
stopFlag = true;
}
idle();
}
Logging.log("out of while loop");
// turn the motors off.
rightMotor.setPower(0);
leftMotor.setPower(0);
// demonstrate using format specifiers.
int i = 3;
double d = 3.75;
Logging.log("stopFlag=%b, i=%d, d=%f", stopFlag, i, d);
Logging.log("done");
}
}