Files
PhotonVision/photon-server/src/main/java/org/photonvision/server/RequestHandler.java

886 lines
35 KiB
Java
Raw Normal View History

/*
* Copyright (C) Photon Vision.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
2020-06-27 14:58:03 -07:00
package org.photonvision.server;
import com.fasterxml.jackson.annotation.JsonProperty;
import com.fasterxml.jackson.core.JsonProcessingException;
2020-06-27 14:58:03 -07:00
import com.fasterxml.jackson.databind.ObjectMapper;
import io.javalin.http.Context;
import io.javalin.http.UploadedFile;
import java.io.*;
import java.nio.file.Files;
import java.nio.file.Path;
import java.nio.file.Paths;
import java.util.ArrayList;
import java.util.HashMap;
import java.util.Optional;
import javax.imageio.ImageIO;
import org.apache.commons.io.FileUtils;
import org.opencv.core.Mat;
import org.opencv.core.MatOfByte;
import org.opencv.core.MatOfInt;
import org.opencv.imgcodecs.Imgcodecs;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.configuration.NetworkConfig;
import org.photonvision.common.dataflow.DataChangeDestination;
import org.photonvision.common.dataflow.DataChangeService;
import org.photonvision.common.dataflow.events.IncomingWebSocketEvent;
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
import org.photonvision.common.hardware.HardwareManager;
import org.photonvision.common.hardware.Platform;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.networking.NetworkManager;
import org.photonvision.common.util.ShellExec;
import org.photonvision.common.util.TimedTaskManager;
import org.photonvision.common.util.file.JacksonUtils;
import org.photonvision.common.util.file.ProgramDirectoryUtilities;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.camera.CameraQuirk;
import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.processes.VisionSourceManager;
2024-11-06 20:16:36 -05:00
import org.zeroturnaround.zip.ZipUtil;
2020-06-27 14:58:03 -07:00
public class RequestHandler {
// Treat all 2XX calls as "INFO"
// Treat all 4XX calls as "ERROR"
// Treat all 5XX calls as "ERROR"
private static final Logger logger = new Logger(RequestHandler.class, LogGroup.WebServer);
2020-06-27 14:58:03 -07:00
private static final ObjectMapper kObjectMapper = new ObjectMapper();
public static void onSettingsImportRequest(Context ctx) {
var file = ctx.uploadedFile("data");
if (file == null) {
ctx.status(400);
ctx.result(
"No File was sent with the request. Make sure that the settings zip is sent at the key 'data'");
logger.error(
"No File was sent with the request. Make sure that the settings zip is sent at the key 'data'");
return;
}
2023-10-05 18:22:56 -04:00
if (!file.extension().contains("zip")) {
ctx.status(400);
ctx.result(
"The uploaded file was not of type 'zip'. The uploaded file should be a .zip file.");
logger.error(
"The uploaded file was not of type 'zip'. The uploaded file should be a .zip file.");
return;
}
// Create a temp file
var tempFilePath = handleTempFileCreation(file);
if (tempFilePath.isEmpty()) {
ctx.status(500);
ctx.result("There was an error while creating a temporary copy of the file");
logger.error("There was an error while creating a temporary copy of the file");
return;
}
2024-10-24 20:48:02 -07:00
ConfigManager.getInstance().setWriteTaskEnabled(false);
ConfigManager.getInstance().disableFlushOnShutdown();
// We want to delete the -whole- zip file, so we need to teardown loggers for now
logger.info("Writing new settings zip (logs may be truncated)...");
Logger.closeAllLoggers();
if (ConfigManager.saveUploadedSettingsZip(tempFilePath.get())) {
ctx.status(200);
ctx.result("Successfully saved the uploaded settings zip, rebooting...");
restartProgram();
} else {
ctx.status(500);
ctx.result("There was an error while saving the uploaded zip file");
}
}
public static void onSettingsExportRequest(Context ctx) {
logger.info("Exporting Settings to ZIP Archive");
try {
var zip = ConfigManager.getInstance().getSettingsFolderAsZip();
var stream = new FileInputStream(zip);
logger.info("Uploading settings with size " + stream.available());
ctx.contentType("application/zip");
ctx.header(
"Content-Disposition", "attachment; filename=\"photonvision-settings-export.zip\"");
ctx.result(stream);
ctx.status(200);
} catch (IOException e) {
logger.error("Unable to export settings archive, bad recode from zip to byte");
ctx.status(500);
ctx.result("There was an error while exporting the settings archive");
}
}
public static void onHardwareConfigRequest(Context ctx) {
var file = ctx.uploadedFile("data");
if (file == null) {
ctx.status(400);
ctx.result(
"No File was sent with the request. Make sure that the hardware config json is sent at the key 'data'");
logger.error(
"No File was sent with the request. Make sure that the hardware config json is sent at the key 'data'");
return;
}
2023-10-05 18:22:56 -04:00
if (!file.extension().contains("json")) {
ctx.status(400);
ctx.result(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
logger.error(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
return;
}
// Create a temp file
var tempFilePath = handleTempFileCreation(file);
if (tempFilePath.isEmpty()) {
ctx.status(500);
ctx.result("There was an error while creating a temporary copy of the file");
logger.error("There was an error while creating a temporary copy of the file");
return;
}
if (ConfigManager.getInstance().saveUploadedHardwareConfig(tempFilePath.get().toPath())) {
ctx.status(200);
ctx.result("Successfully saved the uploaded hardware config, rebooting...");
logger.info("Successfully saved the uploaded hardware config, rebooting...");
restartProgram();
} else {
ctx.status(500);
ctx.result("There was an error while saving the uploaded hardware config");
logger.error("There was an error while saving the uploaded hardware config");
}
}
public static void onHardwareSettingsRequest(Context ctx) {
var file = ctx.uploadedFile("data");
if (file == null) {
ctx.status(400);
ctx.result(
"No File was sent with the request. Make sure that the hardware settings json is sent at the key 'data'");
logger.error(
"No File was sent with the request. Make sure that the hardware settings json is sent at the key 'data'");
return;
}
2023-10-05 18:22:56 -04:00
if (!file.extension().contains("json")) {
ctx.status(400);
ctx.result(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
logger.error(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
return;
}
// Create a temp file
var tempFilePath = handleTempFileCreation(file);
if (tempFilePath.isEmpty()) {
ctx.status(500);
ctx.result("There was an error while creating a temporary copy of the file");
logger.error("There was an error while creating a temporary copy of the file");
return;
}
if (ConfigManager.getInstance().saveUploadedHardwareSettings(tempFilePath.get().toPath())) {
ctx.status(200);
ctx.result("Successfully saved the uploaded hardware settings, rebooting...");
logger.info("Successfully saved the uploaded hardware settings, rebooting...");
restartProgram();
} else {
ctx.status(500);
ctx.result("There was an error while saving the uploaded hardware settings");
logger.error("There was an error while saving the uploaded hardware settings");
}
}
public static void onNetworkConfigRequest(Context ctx) {
var file = ctx.uploadedFile("data");
if (file == null) {
ctx.status(400);
ctx.result(
"No File was sent with the request. Make sure that the network config json is sent at the key 'data'");
logger.error(
"No File was sent with the request. Make sure that the network config json is sent at the key 'data'");
return;
}
2023-10-05 18:22:56 -04:00
if (!file.extension().contains("json")) {
ctx.status(400);
ctx.result(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
logger.error(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
return;
}
// Create a temp file
var tempFilePath = handleTempFileCreation(file);
if (tempFilePath.isEmpty()) {
ctx.status(500);
ctx.result("There was an error while creating a temporary copy of the file");
logger.error("There was an error while creating a temporary copy of the file");
return;
}
if (ConfigManager.getInstance().saveUploadedNetworkConfig(tempFilePath.get().toPath())) {
ctx.status(200);
ctx.result("Successfully saved the uploaded network config, rebooting...");
logger.info("Successfully saved the uploaded network config, rebooting...");
restartProgram();
} else {
ctx.status(500);
ctx.result("There was an error while saving the uploaded network config");
logger.error("There was an error while saving the uploaded network config");
}
}
2023-10-17 10:20:00 -04:00
public static void onAprilTagFieldLayoutRequest(Context ctx) {
var file = ctx.uploadedFile("data");
if (file == null) {
ctx.status(400);
ctx.result(
"No File was sent with the request. Make sure that the field layout json is sent at the key 'data'");
logger.error(
"No File was sent with the request. Make sure that the field layout json is sent at the key 'data'");
return;
}
if (!file.extension().contains("json")) {
ctx.status(400);
ctx.result(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
logger.error(
"The uploaded file was not of type 'json'. The uploaded file should be a .json file.");
return;
}
// Create a temp file
var tempFilePath = handleTempFileCreation(file);
if (tempFilePath.isEmpty()) {
ctx.status(500);
ctx.result("There was an error while creating a temporary copy of the file");
logger.error("There was an error while creating a temporary copy of the file");
return;
}
if (ConfigManager.getInstance().saveUploadedAprilTagFieldLayout(tempFilePath.get().toPath())) {
ctx.status(200);
ctx.result("Successfully saved the uploaded AprilTagFieldLayout, rebooting...");
logger.info("Successfully saved the uploaded AprilTagFieldLayout, rebooting...");
restartProgram();
2023-10-17 10:20:00 -04:00
} else {
ctx.status(500);
ctx.result("There was an error while saving the uploaded AprilTagFieldLayout");
logger.error("There was an error while saving the uploaded AprilTagFieldLayout");
}
}
public static void onOfflineUpdateRequest(Context ctx) {
var file = ctx.uploadedFile("jarData");
if (file == null) {
ctx.status(400);
ctx.result(
"No File was sent with the request. Make sure that the new jar is sent at the key 'jarData'");
logger.error(
"No File was sent with the request. Make sure that the new jar is sent at the key 'jarData'");
return;
}
2023-10-05 18:22:56 -04:00
if (!file.extension().contains("jar")) {
ctx.status(400);
ctx.result(
"The uploaded file was not of type 'jar'. The uploaded file should be a .jar file.");
logger.error(
"The uploaded file was not of type 'jar'. The uploaded file should be a .jar file.");
return;
}
try {
Path filePath =
Paths.get(ProgramDirectoryUtilities.getProgramDirectory(), "photonvision.jar");
File targetFile = new File(filePath.toString());
var stream = new FileOutputStream(targetFile);
2023-10-05 18:22:56 -04:00
file.content().transferTo(stream);
stream.close();
ctx.status(200);
ctx.result(
"Offline update successfully complete. PhotonVision will restart in the background.");
logger.info(
"Offline update successfully complete. PhotonVision will restart in the background.");
restartProgram();
} catch (FileNotFoundException e) {
ctx.result("The current program jar file couldn't be found.");
ctx.status(500);
logger.error("The current program jar file couldn't be found.", e);
} catch (IOException e) {
ctx.result("Unable to overwrite the existing program with the new program.");
ctx.status(500);
logger.error("Unable to overwrite the existing program with the new program.", e);
}
}
public static void onGeneralSettingsRequest(Context ctx) {
NetworkConfig config;
try {
config = kObjectMapper.readValue(ctx.bodyInputStream(), NetworkConfig.class);
ctx.status(200);
ctx.result("Successfully saved general settings");
logger.info("Successfully saved general settings");
} catch (IOException e) {
// If the settings can't be parsed, use the default network settings
config = new NetworkConfig();
ctx.status(400);
ctx.result("The provided general settings were malformed");
logger.error("The provided general settings were malformed", e);
}
ConfigManager.getInstance().setNetworkSettings(config);
ConfigManager.getInstance().requestSave();
NetworkManager.getInstance().reinitialize();
NetworkTablesManager.getInstance().setConfig(config);
}
public static class UICameraSettingsRequest {
@JsonProperty("fov")
double fov;
@JsonProperty("quirksToChange")
HashMap<CameraQuirk, Boolean> quirksToChange;
}
public static void onCameraSettingsRequest(Context ctx) {
try {
var data = kObjectMapper.readTree(ctx.bodyInputStream());
String cameraUniqueName = data.get("cameraUniqueName").asText();
var settings =
JacksonUtils.deserialize(data.get("settings").toString(), UICameraSettingsRequest.class);
var fov = settings.fov;
logger.info("Changing camera FOV to: " + fov);
logger.info("Changing quirks to: " + settings.quirksToChange.toString());
var module = VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName);
module.setFov(fov);
module.changeCameraQuirks(settings.quirksToChange);
module.saveModule();
ctx.status(200);
ctx.result("Successfully saved camera settings");
logger.info("Successfully saved camera settings");
} catch (NullPointerException | IOException e) {
ctx.status(400);
ctx.result("The provided camera settings were malformed");
logger.error("The provided camera settings were malformed", e);
}
}
public static void onLogExportRequest(Context ctx) {
if (!Platform.isLinux()) {
ctx.status(405);
ctx.result("Logs can only be exported on a Linux platform");
// INFO only log because this isn't ERROR worthy
logger.info("Logs can only be exported on a Linux platform");
return;
}
try {
ShellExec shell = new ShellExec();
var tempPath = Files.createTempFile("photonvision-journalctl", ".txt");
2024-11-06 20:16:36 -05:00
var tempPath2 = Files.createTempFile("photonvision-kernelogs", ".txt");
// In the command below:
// dmesg = output all kernel logs since current boot
// cat /var/log/kern.log = output all kernal logs since first boot
2024-11-06 20:16:36 -05:00
shell.executeBashCommand(
"journalctl -u photonvision.service > "
+ tempPath.toAbsolutePath()
+ " && dmesg > "
2024-11-06 20:16:36 -05:00
+ tempPath2.toAbsolutePath());
while (!shell.isOutputCompleted()) {
// TODO: add timeout
}
if (shell.getExitCode() == 0) {
2024-11-06 20:16:36 -05:00
// Wrote to the temp file! Zip and yeet it to the client
var out = Files.createTempFile("photonvision-logs", "zip").toFile();
try {
ZipUtil.packEntries(new File[] {tempPath.toFile(), tempPath2.toFile()}, out);
} catch (Exception e) {
e.printStackTrace();
}
var stream = new FileInputStream(out);
ctx.contentType("application/zip");
ctx.header("Content-Disposition", "attachment; filename=\"photonvision-logs.zip\"");
ctx.result(stream);
2024-11-06 20:16:36 -05:00
ctx.status(200);
logger.info("Outputting log ZIP with size " + stream.available());
} else {
ctx.status(500);
ctx.result("The journalctl service was unable to export logs");
logger.error("The journalctl service was unable to export logs");
}
} catch (IOException e) {
ctx.status(500);
ctx.result("There was an error while exporting journactl logs");
logger.error("There was an error while exporting journactl logs", e);
}
}
public static void onCalibrationEndRequest(Context ctx) {
logger.info("Calibrating camera! This will take a long time...");
String cameraUniqueName;
try {
cameraUniqueName =
kObjectMapper.readTree(ctx.bodyInputStream()).get("cameraUniqueName").asText();
var calData =
VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName).endCalibration();
if (calData == null) {
ctx.result("The calibration process failed");
ctx.status(500);
logger.error(
"The calibration process failed. Calibration data for module at cameraUniqueName ("
+ cameraUniqueName
+ ") was null");
return;
}
ctx.result("Camera calibration successfully completed!");
ctx.status(200);
logger.info("Camera calibration successfully completed!");
} catch (JsonProcessingException e) {
ctx.status(400);
ctx.result(
"The 'cameraUniqueName' field was not found in the request. Please make sure the cameraUniqueName of the vision module is specified with the 'cameraUniqueName' key.");
logger.error(
"The 'cameraUniqueName' field was not found in the request. Please make sure the cameraUniqueName of the vision module is specified with the 'cameraUniqueName' key.",
e);
} catch (Exception e) {
ctx.status(500);
ctx.result("There was an error while ending calibration");
logger.error("There was an error while ending calibration", e);
}
}
Save calibration data and show preliminary GUI (#1078) * Serialize all calibration data * Run lint * typing nit * fix code * move these tables around some * Add cool formatting * add request to get snapshots by resolution and camera * re-enable all resolutions * add wip so i can change computers (SQUASH ME AND KILL ME AHHHH) * Get everything working but viewing snapshots * Update RequestHandler.java * Update CameraCalibrationInfoCard.vue * Update CameraCalibrationInfoCard.vue * add observation viewer * round * fix illiegal import * Swap to PNG and serialize insolution * move import/export buttons TO THE TOP * Update WebsocketDataTypes.ts * Add snapshotname to observation * Refactor to serialize snapshot image itself * Run lint * Use new base64 image data in info card * Update SettingTypes.ts * Create calibration json -> mrcal converter script * Update calibrationUtils.py * Fix calibrate NPEs in teest * Run lint * Always run cornersubpix * Update CameraCalibrationInfoCard.vue Update CameraCalibrationInfoCard.vue * Update OpenCVHelp.java * Update OpenCVHelp.java * Replace test mode camera JSONs * Run wpiformat * Revert intrinsics but keep other data * Remove misc comments * Rename JsonMat->JsonImageMat and add calobject_warp * Update Server.java * Rename cameraExtrinsics to distCoeffs * fix typing issues * use util methods * Formatting fixes * fix styling * move to devTools * remove unneeded or unused imports * Remove fixed-right css If its really that big of a deal, we can add it back later, kind of a drag to fix rn. * Create util method * Remove extra legacy calibration things --------- Co-authored-by: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com>
2024-01-03 14:32:04 -07:00
public static void onDataCalibrationImportRequest(Context ctx) {
try {
var data = kObjectMapper.readTree(ctx.bodyInputStream());
Save calibration data and show preliminary GUI (#1078) * Serialize all calibration data * Run lint * typing nit * fix code * move these tables around some * Add cool formatting * add request to get snapshots by resolution and camera * re-enable all resolutions * add wip so i can change computers (SQUASH ME AND KILL ME AHHHH) * Get everything working but viewing snapshots * Update RequestHandler.java * Update CameraCalibrationInfoCard.vue * Update CameraCalibrationInfoCard.vue * add observation viewer * round * fix illiegal import * Swap to PNG and serialize insolution * move import/export buttons TO THE TOP * Update WebsocketDataTypes.ts * Add snapshotname to observation * Refactor to serialize snapshot image itself * Run lint * Use new base64 image data in info card * Update SettingTypes.ts * Create calibration json -> mrcal converter script * Update calibrationUtils.py * Fix calibrate NPEs in teest * Run lint * Always run cornersubpix * Update CameraCalibrationInfoCard.vue Update CameraCalibrationInfoCard.vue * Update OpenCVHelp.java * Update OpenCVHelp.java * Replace test mode camera JSONs * Run wpiformat * Revert intrinsics but keep other data * Remove misc comments * Rename JsonMat->JsonImageMat and add calobject_warp * Update Server.java * Rename cameraExtrinsics to distCoeffs * fix typing issues * use util methods * Formatting fixes * fix styling * move to devTools * remove unneeded or unused imports * Remove fixed-right css If its really that big of a deal, we can add it back later, kind of a drag to fix rn. * Create util method * Remove extra legacy calibration things --------- Co-authored-by: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com>
2024-01-03 14:32:04 -07:00
String cameraUniqueName = data.get("cameraUniqueName").asText();
Save calibration data and show preliminary GUI (#1078) * Serialize all calibration data * Run lint * typing nit * fix code * move these tables around some * Add cool formatting * add request to get snapshots by resolution and camera * re-enable all resolutions * add wip so i can change computers (SQUASH ME AND KILL ME AHHHH) * Get everything working but viewing snapshots * Update RequestHandler.java * Update CameraCalibrationInfoCard.vue * Update CameraCalibrationInfoCard.vue * add observation viewer * round * fix illiegal import * Swap to PNG and serialize insolution * move import/export buttons TO THE TOP * Update WebsocketDataTypes.ts * Add snapshotname to observation * Refactor to serialize snapshot image itself * Run lint * Use new base64 image data in info card * Update SettingTypes.ts * Create calibration json -> mrcal converter script * Update calibrationUtils.py * Fix calibrate NPEs in teest * Run lint * Always run cornersubpix * Update CameraCalibrationInfoCard.vue Update CameraCalibrationInfoCard.vue * Update OpenCVHelp.java * Update OpenCVHelp.java * Replace test mode camera JSONs * Run wpiformat * Revert intrinsics but keep other data * Remove misc comments * Rename JsonMat->JsonImageMat and add calobject_warp * Update Server.java * Rename cameraExtrinsics to distCoeffs * fix typing issues * use util methods * Formatting fixes * fix styling * move to devTools * remove unneeded or unused imports * Remove fixed-right css If its really that big of a deal, we can add it back later, kind of a drag to fix rn. * Create util method * Remove extra legacy calibration things --------- Co-authored-by: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com>
2024-01-03 14:32:04 -07:00
var coeffs =
kObjectMapper.convertValue(data.get("calibration"), CameraCalibrationCoefficients.class);
var uploadCalibrationEvent =
new IncomingWebSocketEvent<>(
DataChangeDestination.DCD_ACTIVEMODULE,
"calibrationUploaded",
coeffs,
cameraUniqueName,
Save calibration data and show preliminary GUI (#1078) * Serialize all calibration data * Run lint * typing nit * fix code * move these tables around some * Add cool formatting * add request to get snapshots by resolution and camera * re-enable all resolutions * add wip so i can change computers (SQUASH ME AND KILL ME AHHHH) * Get everything working but viewing snapshots * Update RequestHandler.java * Update CameraCalibrationInfoCard.vue * Update CameraCalibrationInfoCard.vue * add observation viewer * round * fix illiegal import * Swap to PNG and serialize insolution * move import/export buttons TO THE TOP * Update WebsocketDataTypes.ts * Add snapshotname to observation * Refactor to serialize snapshot image itself * Run lint * Use new base64 image data in info card * Update SettingTypes.ts * Create calibration json -> mrcal converter script * Update calibrationUtils.py * Fix calibrate NPEs in teest * Run lint * Always run cornersubpix * Update CameraCalibrationInfoCard.vue Update CameraCalibrationInfoCard.vue * Update OpenCVHelp.java * Update OpenCVHelp.java * Replace test mode camera JSONs * Run wpiformat * Revert intrinsics but keep other data * Remove misc comments * Rename JsonMat->JsonImageMat and add calobject_warp * Update Server.java * Rename cameraExtrinsics to distCoeffs * fix typing issues * use util methods * Formatting fixes * fix styling * move to devTools * remove unneeded or unused imports * Remove fixed-right css If its really that big of a deal, we can add it back later, kind of a drag to fix rn. * Create util method * Remove extra legacy calibration things --------- Co-authored-by: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com>
2024-01-03 14:32:04 -07:00
null);
DataChangeService.getInstance().publishEvent(uploadCalibrationEvent);
ctx.status(200);
ctx.result("Calibration imported successfully from imported data!");
logger.info("Calibration imported successfully from imported data!");
} catch (JsonProcessingException e) {
ctx.status(400);
ctx.result("The provided calibration data was malformed");
logger.error("The provided calibration data was malformed", e);
} catch (Exception e) {
ctx.status(500);
ctx.result("An error occurred while uploading calibration data");
logger.error("An error occurred while uploading calibration data", e);
}
}
public static void onProgramRestartRequest(Context ctx) {
// TODO, check if this was successful or not
ctx.status(204);
restartProgram();
}
public static void onDeviceRestartRequest(Context ctx) {
ctx.status(HardwareManager.getInstance().restartDevice() ? 204 : 500);
}
public static void onCameraNicknameChangeRequest(Context ctx) {
try {
var data = kObjectMapper.readTree(ctx.bodyInputStream());
String name = data.get("name").asText();
String cameraUniqueName = data.get("cameraUniqueName").asText();
VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName).setCameraNickname(name);
ctx.status(200);
ctx.result("Successfully changed the camera name to: " + name);
logger.info("Successfully changed the camera name to: " + name);
} catch (JsonProcessingException e) {
ctx.status(400);
ctx.result("The provided nickname data was malformed");
logger.error("The provided nickname data was malformed", e);
} catch (Exception e) {
ctx.status(500);
ctx.result("An error occurred while changing the camera's nickname");
logger.error("An error occurred while changing the camera's nickname", e);
}
}
public static void onMetricsPublishRequest(Context ctx) {
HardwareManager.getInstance().publishMetrics();
ctx.status(204);
}
public static void onCalibrationSnapshotRequest(Context ctx) {
logger.info(ctx.queryString().toString());
String cameraUniqueName = ctx.queryParam("cameraUniqueName");
var width = Integer.parseInt(ctx.queryParam("width"));
var height = Integer.parseInt(ctx.queryParam("height"));
var observationIdx = Integer.parseInt(ctx.queryParam("snapshotIdx"));
CameraCalibrationCoefficients calList =
VisionSourceManager.getInstance()
.vmm
.getModule(cameraUniqueName)
.getStateAsCameraConfig()
.calibrations
.stream()
.filter(
it ->
Math.abs(it.unrotatedImageSize.width - width) < 1e-4
&& Math.abs(it.unrotatedImageSize.height - height) < 1e-4)
.findFirst()
.orElse(null);
if (calList == null || calList.observations.size() < observationIdx) {
ctx.status(404);
return;
}
// encode as jpeg to save even more space. reduces size of a 1280p image from 300k to 25k
var jpegBytes = new MatOfByte();
Mat img = null;
try {
img =
Imgcodecs.imread(
calList.observations.get(observationIdx).snapshotDataLocation.toString());
} catch (Exception e) {
ctx.status(500);
ctx.result("Unable to read calibration image");
return;
}
if (img == null || img.empty()) {
ctx.status(500);
ctx.result("Unable to read calibration image");
return;
}
Imgcodecs.imencode(".jpg", img, jpegBytes, new MatOfInt(Imgcodecs.IMWRITE_JPEG_QUALITY, 60));
ctx.result(jpegBytes.toArray());
jpegBytes.release();
ctx.status(200);
}
public static void onCalibrationExportRequest(Context ctx) {
logger.info(ctx.queryString().toString());
String cameraUniqueName = ctx.queryParam("cameraUniqueName");
var width = Integer.parseInt(ctx.queryParam("width"));
var height = Integer.parseInt(ctx.queryParam("height"));
var cc =
VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName).getStateAsCameraConfig();
CameraCalibrationCoefficients calList =
cc.calibrations.stream()
.filter(
it ->
Math.abs(it.unrotatedImageSize.width - width) < 1e-4
&& Math.abs(it.unrotatedImageSize.height - height) < 1e-4)
.findFirst()
.orElse(null);
if (calList == null) {
ctx.status(404);
return;
}
var filename = "photon_calibration_" + cc.uniqueName + "_" + width + "x" + height + ".json";
ctx.contentType("application/zip");
ctx.header("Content-Disposition", "attachment; filename=\"" + filename + "\"");
ctx.json(calList);
ctx.status(200);
}
public static void onImageSnapshotsRequest(Context ctx) {
var snapshots = new ArrayList<HashMap<String, Object>>();
var cameraDirs = ConfigManager.getInstance().getImageSavePath().toFile().listFiles();
if (cameraDirs != null) {
try {
for (File cameraDir : cameraDirs) {
var cameraSnapshots = cameraDir.listFiles();
if (cameraSnapshots == null) continue;
String cameraUniqueName = cameraDir.getName();
for (File snapshot : cameraSnapshots) {
var snapshotData = new HashMap<String, Object>();
var bufferedImage = ImageIO.read(snapshot);
var buffer = new ByteArrayOutputStream();
ImageIO.write(bufferedImage, "jpg", buffer);
byte[] data = buffer.toByteArray();
snapshotData.put("snapshotName", snapshot.getName());
snapshotData.put("cameraUniqueName", cameraUniqueName);
snapshotData.put("snapshotData", data);
snapshots.add(snapshotData);
}
}
} catch (IOException e) {
ctx.status(500);
ctx.result("Unable to read saved images");
}
}
ctx.status(200);
ctx.json(snapshots);
}
Save calibration data and show preliminary GUI (#1078) * Serialize all calibration data * Run lint * typing nit * fix code * move these tables around some * Add cool formatting * add request to get snapshots by resolution and camera * re-enable all resolutions * add wip so i can change computers (SQUASH ME AND KILL ME AHHHH) * Get everything working but viewing snapshots * Update RequestHandler.java * Update CameraCalibrationInfoCard.vue * Update CameraCalibrationInfoCard.vue * add observation viewer * round * fix illiegal import * Swap to PNG and serialize insolution * move import/export buttons TO THE TOP * Update WebsocketDataTypes.ts * Add snapshotname to observation * Refactor to serialize snapshot image itself * Run lint * Use new base64 image data in info card * Update SettingTypes.ts * Create calibration json -> mrcal converter script * Update calibrationUtils.py * Fix calibrate NPEs in teest * Run lint * Always run cornersubpix * Update CameraCalibrationInfoCard.vue Update CameraCalibrationInfoCard.vue * Update OpenCVHelp.java * Update OpenCVHelp.java * Replace test mode camera JSONs * Run wpiformat * Revert intrinsics but keep other data * Remove misc comments * Rename JsonMat->JsonImageMat and add calobject_warp * Update Server.java * Rename cameraExtrinsics to distCoeffs * fix typing issues * use util methods * Formatting fixes * fix styling * move to devTools * remove unneeded or unused imports * Remove fixed-right css If its really that big of a deal, we can add it back later, kind of a drag to fix rn. * Create util method * Remove extra legacy calibration things --------- Co-authored-by: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com>
2024-01-03 14:32:04 -07:00
public static void onCameraCalibImagesRequest(Context ctx) {
try {
HashMap<String, HashMap<String, ArrayList<HashMap<String, Object>>>> snapshots =
new HashMap<>();
var cameraDirs = ConfigManager.getInstance().getCalibDir().toFile().listFiles();
if (cameraDirs != null) {
var camData = new HashMap<String, ArrayList<HashMap<String, Object>>>();
for (var cameraDir : cameraDirs) {
var resolutionDirs = cameraDir.listFiles();
if (resolutionDirs == null) continue;
for (var resolutionDir : resolutionDirs) {
var calibImages = resolutionDir.listFiles();
if (calibImages == null) continue;
var resolutionImages = new ArrayList<HashMap<String, Object>>();
for (var calibImg : calibImages) {
var snapshotData = new HashMap<String, Object>();
var bufferedImage = ImageIO.read(calibImg);
var buffer = new ByteArrayOutputStream();
ImageIO.write(bufferedImage, "png", buffer);
byte[] data = buffer.toByteArray();
snapshotData.put("snapshotData", data);
snapshotData.put("snapshotFilename", calibImg.getName());
resolutionImages.add(snapshotData);
}
camData.put(resolutionDir.getName(), resolutionImages);
}
var cameraName = cameraDir.getName();
snapshots.put(cameraName, camData);
}
}
ctx.json(snapshots);
} catch (Exception e) {
ctx.status(500);
ctx.result("An error occurred while getting calib data");
logger.error("An error occurred while getting calib data", e);
}
}
/**
* Create a temporary file using the UploadedFile from Javalin.
*
* @param file the uploaded file.
* @return Temporary file. Empty if the temporary file was unable to be created.
*/
private static Optional<File> handleTempFileCreation(UploadedFile file) {
var tempFilePath =
2023-10-05 18:22:56 -04:00
new File(Path.of(System.getProperty("java.io.tmpdir"), file.filename()).toString());
boolean makeDirsRes = tempFilePath.getParentFile().mkdirs();
if (!makeDirsRes && !(tempFilePath.getParentFile().exists())) {
2023-10-05 18:22:56 -04:00
logger.error(
"There was an error while creating "
+ tempFilePath.getAbsolutePath()
+ "! Exists: "
+ tempFilePath.getParentFile().exists());
2023-10-05 18:22:56 -04:00
return Optional.empty();
}
try {
2023-10-05 18:22:56 -04:00
FileUtils.copyInputStreamToFile(file.content(), tempFilePath);
} catch (IOException e) {
logger.error(
"There was an error while copying "
+ file.filename()
+ " to the temp file "
+ tempFilePath.getAbsolutePath());
return Optional.empty();
}
return Optional.of(tempFilePath);
}
/**
* Restart the running program. Note that this doesn't actually restart the program itself,
* instead, it relies on systemd or an equivalent.
*/
private static void restartProgram() {
TimedTaskManager.getInstance()
.addOneShotTask(
() -> {
if (Platform.isLinux()) {
try {
new ShellExec().executeBashCommand("systemctl restart photonvision.service");
} catch (IOException e) {
logger.error("Could not restart device!", e);
System.exit(0);
}
} else {
System.exit(0);
}
},
0);
}
2024-10-24 20:48:02 -07:00
public static void onNukeConfigDirectory(Context ctx) {
ConfigManager.getInstance().setWriteTaskEnabled(false);
ConfigManager.getInstance().disableFlushOnShutdown();
Logger.closeAllLoggers();
if (ConfigManager.nukeConfigDirectory()) {
ctx.status(200);
ctx.result("Successfully nuked config dir");
restartProgram();
} else {
ctx.status(500);
ctx.result("There was an error while nuking the config directory");
}
}
public static void onNukeOneCamera(Context ctx) {
try {
var payload = kObjectMapper.readTree(ctx.bodyInputStream());
var name = payload.get("cameraUniqueName").asText();
logger.warn("Deleting camera name " + name);
var cameraDir = ConfigManager.getInstance().getCalibrationImageSavePath(name).toFile();
if (cameraDir.exists()) {
FileUtils.deleteDirectory(cameraDir);
}
VisionSourceManager.getInstance().deleteVisionSource(name);
2024-10-24 20:48:02 -07:00
ctx.status(200);
} catch (IOException e) {
// todo
logger.error("asdf", e);
ctx.status(500);
}
}
public static void onActivateMatchedCameraRequest(Context ctx) {
logger.info(ctx.queryString().toString());
String cameraUniqueName = ctx.queryParam("cameraUniqueName");
if (VisionSourceManager.getInstance().reactivateDisabledCameraConfig(cameraUniqueName)) {
ctx.status(200);
} else {
ctx.status(403);
}
ctx.result("Successfully assigned camera with unique name: " + cameraUniqueName);
}
public static void onAssignUnmatchedCameraRequest(Context ctx) {
logger.info(ctx.queryString().toString());
PVCameraInfo camera;
try {
camera = JacksonUtils.deserialize(ctx.queryParam("cameraInfo"), PVCameraInfo.class);
} catch (IOException e) {
ctx.status(401);
return;
}
if (VisionSourceManager.getInstance().assignUnmatchedCamera(camera)) {
ctx.status(200);
} else {
ctx.status(404);
}
ctx.result("Successfully assigned camera: " + camera);
}
public static void onUnassignCameraRequest(Context ctx) {
logger.info(ctx.queryString().toString());
String cameraUniqueName = ctx.queryParam("cameraUniqueName");
if (VisionSourceManager.getInstance().deactivateVisionSource(cameraUniqueName)) {
ctx.status(200);
} else {
ctx.status(403);
}
ctx.status(200);
ctx.result("Successfully assigned camera with unique name: " + cameraUniqueName);
}
2020-06-27 14:58:03 -07:00
}