Skip to content

Commit

Permalink
removed legacy of maple config file
Browse files Browse the repository at this point in the history
  • Loading branch information
catr1xLiu committed Oct 12, 2024
1 parent bdfcbca commit bafdd34
Show file tree
Hide file tree
Showing 4 changed files with 0 additions and 441 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import edu.wpi.first.math.geometry.*;
import edu.wpi.first.wpilibj.DriverStation;
import frc.robot.utils.CustomConfigs.MapleConfigFile;
import org.photonvision.simulation.SimCameraProperties;

import java.io.IOException;
Expand Down Expand Up @@ -77,111 +76,6 @@ public SimCameraProperties getSimulationProperties() {
return cameraProperties;
}

public static List<PhotonCameraProperties> loadCamerasPropertiesFromConfig(String configName) {
final MapleConfigFile configFile;
try {
configFile = MapleConfigFile.fromDeployedConfig("PhotonCamerasProperties", configName);
} catch (IOException e) {
DriverStation.reportError(
"cannot find camera properties config file: "
+ configName
+ " from deploy directory",
true);
return new ArrayList<>();
}
return loadCamerasPropertiesFromConfig(configFile);
}

public static List<PhotonCameraProperties> loadCamerasPropertiesFromConfig(MapleConfigFile configFile) {
MapleConfigFile.ConfigBlock generalBlock = configFile.getBlock("GeneralInfo");
final int cameraAmount = generalBlock.getIntConfig("camerasAmount");
final double cameraFPS = generalBlock.getDoubleConfig("cameraFPS"),
averageLatencyMS = generalBlock.getDoubleConfig("averageLatencyMS"),
latencyStandardDeviationMS = generalBlock.getDoubleConfig("latencyStandardDeviationMS");

final List<PhotonCameraProperties> cameraProperties = new ArrayList<>(cameraAmount);

for (int i = 0; i < cameraAmount ; i++) {
final MapleConfigFile.ConfigBlock cameraBlock = configFile.getBlock("Camera"+i);
cameraProperties.add(loadSingleCameraPropertyFromBlock(
cameraBlock, cameraFPS, averageLatencyMS, latencyStandardDeviationMS
));
}

return cameraProperties;
}

private static PhotonCameraProperties loadSingleCameraPropertyFromBlock(MapleConfigFile.ConfigBlock cameraBlock, double cameraFPS, double averageLatencyMS, double latencyStandardDeviationMS) {
final Transform3d robotToCameraInstallation = new Transform3d(
new Translation3d(
cameraBlock.getDoubleConfig("mountPositionToRobotCenterForwardsMeters"),
cameraBlock.getDoubleConfig("mountPositionToRobotCenterLeftwardsMeters"),
cameraBlock.getDoubleConfig("mountHeightMeters")
),
new Rotation3d(
0,
-Math.toRadians(cameraBlock.getDoubleConfig("cameraPitchDegrees")),
Math.toRadians(cameraBlock.getDoubleConfig("cameraYawDegrees"))
));
final double cameraRollDeg = switch (cameraBlock.getIntConfig("captureOrientation")) {
case 1 -> 180;
case 2 -> -90;
case 3 -> 90;
default -> 0;
};
final Transform3d cameraInstallationToCapturedImage = new Transform3d(
new Translation3d(),
new Rotation3d(
Math.toRadians(cameraRollDeg),
0, 0
));
return new PhotonCameraProperties(
cameraBlock.getStringConfig("name"),
cameraFPS,
averageLatencyMS,
latencyStandardDeviationMS,
Rotation2d.fromDegrees(cameraBlock.getDoubleConfig("cameraFOVDegrees")),
cameraBlock.getDoubleConfig("calibrationAverageErrorPixel"),
cameraBlock.getDoubleConfig("calibrationErrorStandardDeviationPixel"),
cameraBlock.getIntConfig("captureWidthPixels"),
cameraBlock.getIntConfig("captureHeightPixels"),
robotToCameraInstallation.plus(cameraInstallationToCapturedImage)
);
}

public static MapleConfigFile createConfigFileForCameras(String name, int camerasAmount, double cameraFPS, double averageLatencyMS, double latencyStandardDeviationMS, int cameraWidthPixels, int cameraHeightPixels, double defaultCameraFOVDegrees) {
final MapleConfigFile configFile = new MapleConfigFile("PhotonCamerasProperties", name);
final MapleConfigFile.ConfigBlock generalBlock = configFile.getBlock("GeneralInfo");

generalBlock.putIntConfig("camerasAmount", camerasAmount);
generalBlock.putDoubleConfig("cameraFPS", cameraFPS);
generalBlock.putDoubleConfig("averageLatencyMS", averageLatencyMS);
generalBlock.putDoubleConfig("latencyStandardDeviationMS", latencyStandardDeviationMS);

for (int i = 0; i < camerasAmount; i++) {
createConfigBlockForCamera(
configFile.getBlock("Camera"+i),
cameraWidthPixels,cameraHeightPixels,defaultCameraFOVDegrees
);
}

return configFile;
}

private static void createConfigBlockForCamera(MapleConfigFile.ConfigBlock cameraBlock, int cameraWidthPixels, int cameraHeightPixels, double cameraFOVDegrees) {
cameraBlock.putStringConfig("name", "YOUR_CAMERA_NAME");
cameraBlock.putIntConfig("captureWidthPixels", cameraWidthPixels);
cameraBlock.putIntConfig("captureHeightPixels", cameraHeightPixels);
cameraBlock.putDoubleConfig("cameraFOVDegrees", cameraFOVDegrees);
cameraBlock.putDoubleConfig("calibrationAverageErrorPixel", 0.35);
cameraBlock.putDoubleConfig("calibrationErrorStandardDeviationPixel", 0.1);
cameraBlock.putDoubleConfig("mountPositionToRobotCenterForwardsMeters", 0);
cameraBlock.putDoubleConfig("mountPositionToRobotCenterLeftwardsMeters", 0);
cameraBlock.putDoubleConfig("mountHeightMeters", 0);
cameraBlock.putDoubleConfig("cameraPitchDegrees", 0);
cameraBlock.putDoubleConfig("cameraYawDegrees", 0);
}

@Override
public String toString() {
return String.format("""
Expand Down
277 changes: 0 additions & 277 deletions src/main/java/frc/robot/utils/CustomConfigs/MapleConfigFile.java

This file was deleted.

Loading

0 comments on commit bafdd34

Please sign in to comment.