-
Notifications
You must be signed in to change notification settings - Fork 6
Expand file tree
/
Copy pathConceptDatalogger.java
More file actions
150 lines (116 loc) · 5.44 KB
/
ConceptDatalogger.java
File metadata and controls
150 lines (116 loc) · 5.44 KB
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
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
/*
This sample FTC OpMode uses methods of the Datalogger class to specify and
collect robot data to be logged in a CSV file, ready for download and charting.
For instructions, see the tutorial at the FTC Wiki:
https://github.com/FIRST-Tech-Challenge/FtcRobotController/wiki/Datalogging
The Datalogger class is suitable for FTC OnBot Java (OBJ) programmers.
Its methods can be made available for FTC Blocks, by creating myBlocks in OBJ.
Android Studio programmers can see instructions in the Datalogger class notes.
Credit to @Windwoes (https://github.com/Windwoes).
*/
package org.firstinspires.ftc.teamcode;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.VoltageSensor;
import org.firstinspires.ftc.robotcore.external.navigation.Orientation;
@TeleOp(name = "Concept Datalogger v01", group = "Datalogging")
public class ConceptDatalogger extends LinearOpMode
{
Datalog datalog;
BNO055IMU imu;
VoltageSensor battery;
@Override
public void runOpMode() throws InterruptedException
{
// Get devices from the hardwareMap.
// If needed, change "Control Hub" to (e.g.) "Expansion Hub 1".
battery = hardwareMap.voltageSensor.get("Control Hub");
imu = hardwareMap.get(BNO055IMU.class, "imu");
// Initialize the datalog
datalog = new Datalog("datalog_01");
// You do not need to fill every field of the datalog
// every time you call writeLine(); those fields will simply
// contain the last value.
datalog.opModeStatus.set("INIT");
datalog.battery.set(battery.getVoltage());
datalog.writeLine();
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
parameters.angleUnit = BNO055IMU.AngleUnit.DEGREES;
imu.initialize(parameters);
telemetry.setMsTransmissionInterval(50);
waitForStart();
datalog.opModeStatus.set("RUNNING");
for (int i = 0; opModeIsActive(); i++)
{
// Note that the order in which we set datalog fields
// does *not* matter! The order is configured inside
// the Datalog class constructor.
datalog.loopCounter.set(i);
datalog.battery.set(battery.getVoltage());
Orientation orientation = imu.getAngularOrientation();
datalog.yaw.set(orientation.firstAngle);
datalog.pitch.set(orientation.secondAngle);
datalog.roll.set(orientation.thirdAngle);
// The logged timestamp is taken when writeLine() is called.
datalog.writeLine();
// Datalog fields are stored as text only; do not format here.
telemetry.addData("Yaw", datalog.yaw);
telemetry.addData("Pitch", datalog.pitch);
telemetry.addData("Roll", datalog.roll);
telemetry.addLine();
telemetry.addData("OpMode Status", datalog.opModeStatus);
telemetry.addData("Loop Counter", datalog.loopCounter);
telemetry.addData("Battery", datalog.battery);
telemetry.update();
sleep(20);
}
/*
* The datalog is automatically closed and flushed to disk after
* the OpMode ends - no need to do that manually :')
*/
}
/*
* This class encapsulates all the fields that will go into the datalog.
*/
public static class Datalog
{
// The underlying datalogger object - it cares only about an array of loggable fields
private final Datalogger datalogger;
// These are all of the fields that we want in the datalog.
// Note that order here is NOT important. The order is important in the setFields() call below
public Datalogger.GenericField opModeStatus = new Datalogger.GenericField("OpModeStatus");
public Datalogger.GenericField loopCounter = new Datalogger.GenericField("Loop Counter");
public Datalogger.GenericField yaw = new Datalogger.GenericField("Yaw");
public Datalogger.GenericField pitch = new Datalogger.GenericField("Pitch");
public Datalogger.GenericField roll = new Datalogger.GenericField("Roll");
public Datalogger.GenericField battery = new Datalogger.GenericField("Battery");
public Datalog(String name)
{
// Build the underlying datalog object
datalogger = new Datalogger.Builder()
// Pass through the filename
.setFilename(name)
// Request an automatic timestamp field
.setAutoTimestamp(Datalogger.AutoTimestamp.DECIMAL_SECONDS)
// Tell it about the fields we care to log.
// Note that order *IS* important here! The order in which we list
// the fields is the order in which they will appear in the log.
.setFields(
opModeStatus,
loopCounter,
yaw,
pitch,
roll,
battery
)
.build();
}
// Tell the datalogger to gather the values of the fields
// and write a new line in the log.
public void writeLine()
{
datalogger.writeLine();
}
}
}