-
Notifications
You must be signed in to change notification settings - Fork 12
/
RobotStateEstimator.java
287 lines (241 loc) · 11.3 KB
/
RobotStateEstimator.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
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
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
package com.team254.frc2022.subsystems;
import com.team254.frc2022.Constants;
import com.team254.frc2022.RobotState;
import com.team254.frc2022.planners.DriveMotionPlanner;
import com.team254.lib.loops.ILooper;
import com.team254.lib.loops.Loop;
import com.team254.lib.swerve.SwerveDriveOdometry;
import com.team254.lib.util.ReflectingCSVWriter;
import com.team254.lib.util.Units;
import com.team254.lib.util.Util;
import edu.wpi.first.util.WPIUtilJNI;
import edu.wpi.first.wpilibj.Timer;
import com.team254.lib.drivers.Subsystem;
import com.team254.lib.geometry.Pose2d;
import com.team254.lib.geometry.Rotation2d;
import com.team254.lib.geometry.Twist2d;
public class RobotStateEstimator extends Subsystem {
static RobotStateEstimator mInstance = null;
private Drive mDrive = null;
private final SwerveDriveOdometry mOdometry = new SwerveDriveOdometry(Constants.kKinematics, Pose2d.identity());
public static class OdometryLogValues {
public double timestamp;
public double frontLeftPosition;
public double frontRightPosition;
public double backLeftPosition;
public double backRightPosition;
public double frontLeftVelocity;
public double frontRightVelocity;
public double backLeftVelocity;
public double backRightVelocity;
public double frontLeftAngle;
public double frontRightAngle;
public double backLeftAngle;
public double backRightAngle;
public double gyroAngle;
public double frontLeftAngleSetpoint;
public double frontRightAngleSetpoint;
public double backLeftAngleSetpoint;
public double backRightAngleSetpoint;
public double frontLeftError;
public double frontRightError;
public double backLeftError;
public double backRightError;
public double timestamp1;
public double poseX;
public double autonXSetpoint;
public double xError;
public double timestamp2;
public double poseY;
public double autonYSetpoint;
public double yError;
public double timestamp3;
public double poseTheta;
public double autonHeadingSetpoint;
public double headingError;
public OdometryLogValues(double timestamp, double frontLeftPosition, double frontRightPosition, double backLeftPosition, double backRightPosition,
double frontLeftVelocity, double frontRightVelocity, double backLeftVelocity, double backRightVelocity,
double frontLeftAngle, double frontRightAngle, double backLeftAngle, double backRightAngle,
double flCLosedLoopErr,double frCLosedLoopErr,double blCLosedLoopErr,double brCLosedLoopErr,
double gyroAngle, double poseX, double poseY, double poseTheta,
double frontLeftAngleSetpoint, double frontRightAngleSetpoint, double backLeftAngleSetpoint, double backRightAngleSetpoint,
double xSetpoint, double ySetpoint, double headingSetpoint, double xError, double yError, double headingError) {
this.timestamp = timestamp;
this.timestamp1 = timestamp;
this.timestamp2 = timestamp;
this.timestamp3 = timestamp;
this.frontLeftPosition = frontLeftPosition;
this.frontRightPosition = frontRightPosition;
this.backLeftPosition = backLeftPosition;
this.backRightPosition = backRightPosition;
this.frontLeftVelocity = frontLeftVelocity;
this.frontRightVelocity = frontRightVelocity;
this.backLeftVelocity = backLeftVelocity;
this.backRightVelocity = backRightVelocity;
this.frontLeftAngle = frontLeftAngle;
this.frontRightAngle = frontRightAngle;
this.backLeftAngle = backLeftAngle;
this.backRightAngle = backRightAngle;
this.gyroAngle = gyroAngle;
this.poseX = poseX;
this.poseY = poseY;
this.poseTheta = poseTheta;
this.frontLeftAngleSetpoint = frontLeftAngleSetpoint;
this.frontRightAngleSetpoint = frontRightAngleSetpoint;
this.backLeftAngleSetpoint = backLeftAngleSetpoint;
this.backRightAngleSetpoint = backRightAngleSetpoint;
this.autonXSetpoint = xSetpoint;
this.autonYSetpoint = ySetpoint;
this.autonHeadingSetpoint = headingSetpoint;
this.xError = xError;
this.yError = yError;
this.headingError = headingError;
this.frontLeftError = flCLosedLoopErr;
this.frontRightError = frCLosedLoopErr;
this.backLeftError = blCLosedLoopErr;
this.backRightError = brCLosedLoopErr;
}
}
private ReflectingCSVWriter<OdometryLogValues> mCSVWriter = null;
public static RobotStateEstimator getInstance() {
if (mInstance == null) {
mInstance = new RobotStateEstimator();
}
return mInstance;
}
private RobotStateEstimator() {
mDrive = Drive.getInstance();
}
public Pose2d getEstimatedPose() {
return mOdometry.getPoseMeters();
}
@Override
public void registerEnabledLoops(ILooper looper) {
looper.register(new EnabledLoop());
}
private class EnabledLoop implements Loop {
@Override
public synchronized void onStart(double timestamp) {
//startLogging();
}
@Override
public synchronized void onLoop(double timestamp) {
synchronized(RobotStateEstimator.this) {
mOdometry.update(mDrive.getFieldRelativeGyroscopeRotation(), mDrive.getModuleStates());
Twist2d measured_velocity = mOdometry.getVelocity().toTwist2d();
Twist2d predicted_velocity = mDrive.getSetpoint().mChassisSpeeds.toTwist2d();
// TODO(maybe add actual velocity prediction)
RobotState.getInstance().addObservations(timestamp, mOdometry.getPoseMeters(),
measured_velocity, predicted_velocity);
// TODO(refactor to combine this method with the above)
RobotState.getInstance().addVehicleToTurretObservation(
timestamp,
Pose2d.fromRotation(Rotation2d.fromDegrees(Turret.getInstance().getAngle())),
Turret.getInstance().getVelocity());
if (mCSVWriter != null) {
try {
logCSV();
} catch (Exception e) {
e.printStackTrace();
}
}
}
}
@Override
public void onStop(double timestamp) {
stopLogging();
}
}
@Override
public void stop() {}
public void resetOdometry(Pose2d initialPose) {
synchronized(RobotStateEstimator.this) {
mOdometry.resetPosition(initialPose);
RobotState.getInstance().resetVision();
RobotState.getInstance().reset(Timer.getFPGATimestamp(), initialPose);
}
}
public synchronized void startLogging() {
if (mCSVWriter == null) {
mCSVWriter = new ReflectingCSVWriter<>("/home/lvuser/ODOMETRY-LOGS.csv", OdometryLogValues.class);
}
}
public synchronized void stopLogging() {
if (mCSVWriter != null) {
mCSVWriter.flush();
mCSVWriter = null;
}
}
private synchronized void logCSV() {
double currentTime = WPIUtilJNI.now() * 1.0e-6;
var modules_meas = mDrive.getModuleStates();
var modules_des = mDrive.getDesiredModuleStates();
double frontLeftPosition = modules_meas[Drive.kFrontLeftModuleIdx].distanceMeters;
double frontRightPosition = modules_meas[Drive.kFrontRightModuleIdx].distanceMeters;
double backLeftPosition = modules_meas[Drive.kBackLeftModuleIdx].distanceMeters;
double backRightPosition = modules_meas[Drive.kBackRightModuleIdx].distanceMeters;
double frontLeftVelocity = modules_meas[Drive.kFrontLeftModuleIdx].speedMetersPerSecond;
double frontRightVelocity = modules_meas[Drive.kFrontRightModuleIdx].speedMetersPerSecond;
double backLeftVelocity = modules_meas[Drive.kBackLeftModuleIdx].speedMetersPerSecond;
double backRightVelocity = modules_meas[Drive.kBackRightModuleIdx].speedMetersPerSecond;
double frontLeftAngle = modules_meas[Drive.kFrontLeftModuleIdx].angle.getRadians();
double frontRightAngle = modules_meas[Drive.kFrontRightModuleIdx].angle.getRadians();
double backLeftAngle = modules_meas[Drive.kBackLeftModuleIdx].angle.getRadians();
double backRightAngle = modules_meas[Drive.kBackRightModuleIdx].angle.getRadians();
double[] closed_loop_err = mDrive.getSteerClosedLoopErrors();
double flErr = closed_loop_err[Drive.kFrontLeftModuleIdx];
double frErr = closed_loop_err[Drive.kFrontRightModuleIdx];
double brErr = closed_loop_err[Drive.kBackRightModuleIdx];
double blErr = closed_loop_err[Drive.kBackLeftModuleIdx];
boolean stationary = mOdometry.getVelocity().toTwist2d().epsilonEquals(Twist2d.identity(), Util.kEpsilon);
Pose2d currentPose = mOdometry.getPoseMeters();
var desiredStates = mDrive.getSetpoint().mModuleStates;
Pose2d autonSetpoint = mDrive.getAutonSetpoint();
Pose2d autonError = mDrive.getAutonError();
OdometryLogValues logMsg = new OdometryLogValues(
currentTime,
frontLeftPosition,
frontRightPosition,
backLeftPosition,
backRightPosition,
frontLeftVelocity,
frontRightVelocity,
backLeftVelocity,
backRightVelocity,
frontLeftAngle,
frontRightAngle,
backLeftAngle,
backRightAngle,
flErr,
frErr,
blErr,
brErr,
mDrive.getFieldRelativeGyroscopeRotation().getDegrees(),
currentPose.getTranslation().x(),
currentPose.getTranslation().y(),
currentPose.getRotation().getDegrees(),
stationary ? frontLeftAngle : desiredStates[Drive.kFrontLeftModuleIdx].angle.getRadians(),
stationary ? frontRightAngle : desiredStates[Drive.kFrontRightModuleIdx].angle.getRadians(),
stationary ? backLeftAngle : desiredStates[Drive.kBackLeftModuleIdx].angle.getRadians(),
stationary ? backRightAngle : desiredStates[Drive.kBackRightModuleIdx].angle.getRadians(),
Units.inches_to_meters(autonSetpoint.getTranslation().x()),
Units.inches_to_meters(autonSetpoint.getTranslation().y()),
autonSetpoint.getRotation().getDegrees(),
autonError.getTranslation().x(),
autonError.getTranslation().y(),
autonError.getRotation().getDegrees()
);
mCSVWriter.add(logMsg);
}
@Override
public boolean checkSystem() {
return true;
}
@Override
public synchronized void outputTelemetry() {
RobotState.getInstance().outputToSmartDashboard();
// if (mCSVWriter != null) {
// mCSVWriter.write();
// }
}
}