mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
3d, camera calibration, backend settings hookup (#80)
* Implement new UI backend stuff * Kinda partially add resolution accuracy list * camera calibration go brrrrrrrr * ayyyy calibration works * Maybe fix grouping * Reorganize camera view * Fix settings not getting sent * Make pretty (#4) * Reorganize camera view * Apply some cosmetic layout changes to the cameras page * Fix pipeline rollback bug when starting on non-dashboard pages Co-authored-by: Matt <matthew.morley.ca@gmail.com> * Fix naming mismatch * Mostly make stuff work * rename robot-relative pose to camera-relative pose * SolvePNP memes, fix isFovConfigurable * Change config path to photonvision_config * netmask go poof, fix zip download? * Update index.js * Fix multi cam stuff? * Use LinearFilter instead * Fix multicam * aaa * start adding restart device and restart program, fix square size bug * Add some debug stuff * oop * Start fixing tests * Fix tests * Make target box proportinal * run spotless * Make crosshair h o t p i n k * Address review comments * Address review 2 electric booaloo * Possibly implement vendor FOV? * Make centroid crosshair gren * actually use FOV * Fix tests * actually fix tests Co-authored-by: Declan Freeman-Gleason <declanfreemangleason@gmail.com>
This commit is contained in:
@@ -20,6 +20,7 @@ package org.photonvision.common.configuration;
|
||||
import com.fasterxml.jackson.annotation.JsonCreator;
|
||||
import com.fasterxml.jackson.annotation.JsonIgnore;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
@@ -47,9 +48,10 @@ public class CameraConfiguration {
|
||||
|
||||
public CameraType cameraType = CameraType.UsbCamera;
|
||||
public double FOV = 70;
|
||||
public CameraCalibrationCoefficients calibration;
|
||||
public final List<CameraCalibrationCoefficients> calibrations;
|
||||
public List<Integer> cameraLeds = new ArrayList<>();
|
||||
public int currentPipelineIndex = -1;
|
||||
public int currentPipelineIndex = 0;
|
||||
public Rotation2d camPitch = new Rotation2d();
|
||||
|
||||
@JsonIgnore // this ignores the pipes as we serialize them to their own subfolder
|
||||
public List<CVPipelineSettings> pipelineSettings = new ArrayList<>();
|
||||
@@ -66,6 +68,7 @@ public class CameraConfiguration {
|
||||
this.uniqueName = uniqueName;
|
||||
this.nickname = nickname;
|
||||
this.path = path;
|
||||
this.calibrations = new ArrayList<>();
|
||||
|
||||
logger.debug(
|
||||
"Creating USB camera configuration for "
|
||||
@@ -85,18 +88,20 @@ public class CameraConfiguration {
|
||||
@JsonProperty("FOV") double FOV,
|
||||
@JsonProperty("path") String path,
|
||||
@JsonProperty("cameraType") CameraType cameraType,
|
||||
@JsonProperty("calibration") CameraCalibrationCoefficients calibration,
|
||||
@JsonProperty("calibration") List<CameraCalibrationCoefficients> calibrations,
|
||||
@JsonProperty("cameraLEDs") List<Integer> cameraLeds,
|
||||
@JsonProperty("currentPipelineIndex") int currentPipelineIndex) {
|
||||
@JsonProperty("currentPipelineIndex") int currentPipelineIndex,
|
||||
@JsonProperty("camPitch") Rotation2d camPitch) {
|
||||
this.baseName = baseName;
|
||||
this.uniqueName = uniqueName;
|
||||
this.nickname = nickname;
|
||||
this.FOV = FOV;
|
||||
this.path = path;
|
||||
this.cameraType = cameraType;
|
||||
this.calibration = calibration;
|
||||
this.calibrations = calibrations != null ? calibrations : new ArrayList<>();
|
||||
this.cameraLeds = cameraLeds;
|
||||
this.currentPipelineIndex = currentPipelineIndex;
|
||||
this.camPitch = camPitch;
|
||||
|
||||
logger.debug(
|
||||
"Creating camera configuration for "
|
||||
@@ -134,4 +139,13 @@ public class CameraConfiguration {
|
||||
public void setPipelineSettings(List<CVPipelineSettings> settings) {
|
||||
pipelineSettings = settings;
|
||||
}
|
||||
|
||||
public void addCalibration(CameraCalibrationCoefficients calibration) {
|
||||
logger.info("adding calibration " + calibration.resolution);
|
||||
calibrations.stream()
|
||||
.filter(it -> it.resolution.equals(calibration.resolution))
|
||||
.findAny()
|
||||
.ifPresent(calibrations::remove);
|
||||
calibrations.add(calibration);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -22,25 +22,30 @@ import java.io.File;
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Files;
|
||||
import java.nio.file.Path;
|
||||
import java.time.LocalDateTime;
|
||||
import java.time.format.DateTimeFormatter;
|
||||
import java.util.*;
|
||||
import java.util.stream.Collectors;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.file.FileUtils;
|
||||
import org.photonvision.common.util.file.JacksonUtils;
|
||||
import org.photonvision.vision.pipeline.CVPipelineSettings;
|
||||
import org.photonvision.vision.pipeline.DriverModePipelineSettings;
|
||||
import org.photonvision.vision.processes.VisionSource;
|
||||
import org.zeroturnaround.zip.ZipUtil;
|
||||
|
||||
public class ConfigManager {
|
||||
private static final Logger logger = new Logger(ConfigManager.class, LogGroup.General);
|
||||
private static ConfigManager INSTANCE;
|
||||
|
||||
private PhotonConfiguration config;
|
||||
final File rootFolder;
|
||||
private final File hardwareConfigFile;
|
||||
private final File networkConfigFile;
|
||||
private final File camerasFolder;
|
||||
|
||||
final File configDirectoryFile;
|
||||
|
||||
public static ConfigManager getInstance() {
|
||||
if (INSTANCE == null) {
|
||||
INSTANCE = new ConfigManager(getRootFolder());
|
||||
@@ -48,34 +53,58 @@ public class ConfigManager {
|
||||
return INSTANCE;
|
||||
}
|
||||
|
||||
public static void saveUploadedSettingsZip(File uploadPath) {
|
||||
logger.info(uploadPath.getAbsolutePath());
|
||||
var folderPath = Path.of(System.getProperty("java.io.tmpdir"), "photonvision").toFile();
|
||||
folderPath.mkdirs();
|
||||
ZipUtil.unpack(uploadPath, folderPath);
|
||||
FileUtils.deleteDirectory(getRootFolder());
|
||||
try {
|
||||
org.apache.commons.io.FileUtils.copyDirectory(folderPath, getRootFolder().toFile());
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
System.exit(666);
|
||||
}
|
||||
|
||||
public PhotonConfiguration getConfig() {
|
||||
return config;
|
||||
}
|
||||
|
||||
private static Path getRootFolder() {
|
||||
return Path.of("photonvision");
|
||||
return Path.of("photonvision_config");
|
||||
}
|
||||
|
||||
ConfigManager(Path rootFolder) {
|
||||
this.rootFolder = new File(rootFolder.toUri());
|
||||
ConfigManager(Path configDirectoryFile) {
|
||||
this.configDirectoryFile = new File(configDirectoryFile.toUri());
|
||||
this.hardwareConfigFile =
|
||||
new File(Path.of(rootFolder.toString(), "hardwareConfig.json").toUri());
|
||||
new File(Path.of(configDirectoryFile.toString(), "hardwareConfig.json").toUri());
|
||||
this.networkConfigFile =
|
||||
new File(Path.of(rootFolder.toString(), "networkSettings.json").toUri());
|
||||
this.camerasFolder = new File(Path.of(rootFolder.toString(), "cameras").toUri());
|
||||
new File(Path.of(configDirectoryFile.toString(), "networkSettings.json").toUri());
|
||||
this.camerasFolder = new File(Path.of(configDirectoryFile.toString(), "cameras").toUri());
|
||||
|
||||
load();
|
||||
}
|
||||
|
||||
private void load() {
|
||||
logger.info("Loading settings...");
|
||||
if (!rootFolder.exists()) {
|
||||
if (rootFolder.mkdirs()) {
|
||||
if (!configDirectoryFile.exists()) {
|
||||
if (configDirectoryFile.mkdirs()) {
|
||||
logger.debug("Root config folder did not exist. Created!");
|
||||
} else {
|
||||
logger.error("Failed to create root config folder!");
|
||||
}
|
||||
}
|
||||
if (!configDirectoryFile.canWrite()) {
|
||||
logger.debug("Making root dir writeable...");
|
||||
try {
|
||||
var success = configDirectoryFile.setWritable(true);
|
||||
if (success) logger.debug("Set root dir writeable!");
|
||||
else logger.error("Could not make root dir writeable!");
|
||||
} catch (SecurityException e) {
|
||||
logger.error("Could not make root dir writeable!", e);
|
||||
}
|
||||
}
|
||||
|
||||
HardwareConfig hardwareConfig;
|
||||
NetworkConfig networkConfig;
|
||||
@@ -130,16 +159,19 @@ public class ConfigManager {
|
||||
logger.info("Saving settings...");
|
||||
|
||||
try {
|
||||
JacksonUtils.serializer(hardwareConfigFile.toPath(), config.getHardwareConfig());
|
||||
JacksonUtils.serialize(hardwareConfigFile.toPath(), config.getHardwareConfig());
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save hardware config!", e);
|
||||
}
|
||||
try {
|
||||
JacksonUtils.serializer(networkConfigFile.toPath(), config.getNetworkConfig());
|
||||
JacksonUtils.serialize(networkConfigFile.toPath(), config.getNetworkConfig());
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save network config!", e);
|
||||
}
|
||||
|
||||
// Delete old configs
|
||||
FileUtils.deleteDirectory(camerasFolder.toPath());
|
||||
|
||||
// save all of our cameras
|
||||
var cameraConfigMap = config.getCameraConfigurations();
|
||||
for (var subdirName : cameraConfigMap.keySet()) {
|
||||
@@ -152,25 +184,16 @@ public class ConfigManager {
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serializer(Path.of(subdir.toString(), "config.json"), camConfig);
|
||||
JacksonUtils.serialize(Path.of(subdir.toString(), "config.json"), camConfig);
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save config.json for " + subdir);
|
||||
logger.error("Could not save config.json for " + subdir, e);
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serializer(
|
||||
JacksonUtils.serialize(
|
||||
Path.of(subdir.toString(), "drivermode.json"), camConfig.driveModeSettings);
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save drivermode.json for " + subdir);
|
||||
}
|
||||
|
||||
// Delete old pipe configs so that we don't get any conflicts
|
||||
try {
|
||||
var pipelineFolder = Path.of(subdir.toString(), "pipelines");
|
||||
if (pipelineFolder.toFile().exists())
|
||||
Files.list(pipelineFolder).map(Path::toFile).filter(File::exists).forEach(File::delete);
|
||||
} catch (IOException e) {
|
||||
logger.error("Exception while deleting old configs!", e);
|
||||
logger.error("Could not save drivermode.json for " + subdir, e);
|
||||
}
|
||||
|
||||
for (var pipe : camConfig.pipelineSettings) {
|
||||
@@ -182,7 +205,7 @@ public class ConfigManager {
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serializer(pipePath, pipe);
|
||||
JacksonUtils.serialize(pipePath, pipe);
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save " + pipe.pipelineNickname + ".json!", e);
|
||||
}
|
||||
@@ -207,6 +230,7 @@ public class ConfigManager {
|
||||
cameraConfigPath.toAbsolutePath(), CameraConfiguration.class);
|
||||
} catch (JsonProcessingException e) {
|
||||
logger.error("Camera config deserialization failed!", e);
|
||||
e.printStackTrace();
|
||||
}
|
||||
if (loadedConfig == null) { // If the file could not be deserialized
|
||||
logger.warn("Could not load camera " + subdir + "'s config.json! Loading " + "default");
|
||||
@@ -243,7 +267,11 @@ public class ConfigManager {
|
||||
.map(
|
||||
p -> {
|
||||
var relativizedFilePath =
|
||||
rootFolder.toPath().toAbsolutePath().relativize(p).toString();
|
||||
configDirectoryFile
|
||||
.toPath()
|
||||
.toAbsolutePath()
|
||||
.relativize(p)
|
||||
.toString();
|
||||
try {
|
||||
return JacksonUtils.deserialize(p, CVPipelineSettings.class);
|
||||
} catch (JsonProcessingException e) {
|
||||
@@ -284,4 +312,28 @@ public class ConfigManager {
|
||||
getConfig().addCameraConfig(uniqueName, config);
|
||||
save();
|
||||
}
|
||||
|
||||
public File getSettingsFolderAsZip() {
|
||||
File out = Path.of(System.getProperty("java.io.tmpdir"), "photonvision-settings.zip").toFile();
|
||||
try {
|
||||
ZipUtil.pack(configDirectoryFile, out);
|
||||
} catch (Exception e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
return out;
|
||||
}
|
||||
|
||||
public void setNetworkSettings(NetworkConfig networkConfig) {
|
||||
getConfig().setNetworkConfig(networkConfig);
|
||||
save();
|
||||
}
|
||||
|
||||
public Path getLogPath() {
|
||||
var dateString = DateTimeFormatter.ofPattern("yyyy-M-d_hh-mm-ss").format(LocalDateTime.now());
|
||||
var logFile =
|
||||
Path.of(configDirectoryFile.toString(), "logs", "photonvision-" + dateString + ".log")
|
||||
.toFile();
|
||||
if (!logFile.getParentFile().exists()) logFile.getParentFile().mkdirs();
|
||||
return logFile.toPath();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -17,12 +17,8 @@
|
||||
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonCreator;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Map;
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
public class HardwareConfig {
|
||||
|
||||
public final String deviceName;
|
||||
@@ -47,6 +43,10 @@ public class HardwareConfig {
|
||||
public final String gpuTempCommand;
|
||||
public final String ramUtilCommand;
|
||||
|
||||
// Device stuff
|
||||
public final String restartHardwareCommand;
|
||||
public final double vendorFOV; // -1 for unmanaged
|
||||
|
||||
public HardwareConfig() {
|
||||
deviceName = "";
|
||||
deviceLogoPath = "";
|
||||
@@ -66,32 +66,54 @@ public class HardwareConfig {
|
||||
gpuTempCommand = "";
|
||||
ramUtilCommand = "";
|
||||
ledBlinkCommand = "";
|
||||
|
||||
restartHardwareCommand = "";
|
||||
vendorFOV = -1;
|
||||
}
|
||||
|
||||
@JsonCreator
|
||||
@SuppressWarnings("unused")
|
||||
public HardwareConfig(
|
||||
@JsonProperty("deviceName") String deviceName,
|
||||
@JsonProperty("deviceLogoPath") String deviceLogoPath,
|
||||
@JsonProperty("supportURL") String supportURL,
|
||||
@JsonProperty("hardware") Map<String, ?> hardware,
|
||||
@JsonProperty("metrics") Map<String, ?> metrics) {
|
||||
String deviceName,
|
||||
String deviceLogoPath,
|
||||
String supportURL,
|
||||
ArrayList<Integer> ledPins,
|
||||
String ledSetCommand,
|
||||
boolean ledsCanDim,
|
||||
ArrayList<Integer> ledPWMRange,
|
||||
String ledPWMSetRange,
|
||||
int ledPWMFrequency,
|
||||
String ledDimCommand,
|
||||
String ledBlinkCommand,
|
||||
String cpuTempCommand,
|
||||
String cpuMemoryCommand,
|
||||
String cpuUtilCommand,
|
||||
String gpuMemoryCommand,
|
||||
String gpuTempCommand,
|
||||
String ramUtilCommand,
|
||||
String restartHardwareCommand,
|
||||
double vendorFOV) {
|
||||
this.deviceName = deviceName;
|
||||
this.deviceLogoPath = deviceLogoPath;
|
||||
this.supportURL = supportURL;
|
||||
this.ledPins = (ArrayList<Integer>) hardware.get("leds");
|
||||
this.ledSetCommand = (String) hardware.get("ledSetCommand");
|
||||
this.ledsCanDim = (Boolean) hardware.get("ledsCanDim");
|
||||
this.ledPWMRange = (ArrayList<Integer>) hardware.get("ledPWMRange");
|
||||
this.ledPWMSetRange = (String) hardware.get("ledPWMSetRange");
|
||||
this.ledPWMFrequency = (Integer) hardware.get("ledPWMFrequency");
|
||||
this.ledDimCommand = (String) hardware.get("ledDimCommand");
|
||||
this.ledBlinkCommand = (String) hardware.get("ledBlinkCommand");
|
||||
this.ledPins = ledPins;
|
||||
this.ledSetCommand = ledSetCommand;
|
||||
this.ledsCanDim = ledsCanDim;
|
||||
this.ledPWMRange = ledPWMRange;
|
||||
this.ledPWMSetRange = ledPWMSetRange;
|
||||
this.ledPWMFrequency = ledPWMFrequency;
|
||||
this.ledDimCommand = ledDimCommand;
|
||||
this.ledBlinkCommand = ledBlinkCommand;
|
||||
this.cpuTempCommand = cpuTempCommand;
|
||||
this.cpuMemoryCommand = cpuMemoryCommand;
|
||||
this.cpuUtilCommand = cpuUtilCommand;
|
||||
this.gpuMemoryCommand = gpuMemoryCommand;
|
||||
this.gpuTempCommand = gpuTempCommand;
|
||||
this.ramUtilCommand = ramUtilCommand;
|
||||
this.restartHardwareCommand = restartHardwareCommand;
|
||||
this.vendorFOV = vendorFOV;
|
||||
}
|
||||
|
||||
this.cpuTempCommand = (String) metrics.get("cpuTemp");
|
||||
this.cpuMemoryCommand = (String) metrics.get("cpuMemory");
|
||||
this.cpuUtilCommand = (String) metrics.get("cpuUtil");
|
||||
this.gpuMemoryCommand = (String) metrics.get("gpuMemory");
|
||||
this.gpuTempCommand = (String) metrics.get("gpuUtil");
|
||||
this.ramUtilCommand = (String) metrics.get("ramUtil");
|
||||
public final boolean hasPresetFOV() {
|
||||
return vendorFOV > 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -18,23 +18,57 @@
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.photonvision.common.networking.NetworkMode;
|
||||
|
||||
public class NetworkConfig {
|
||||
public int teamNumber = 1;
|
||||
public NetworkMode connectionType = NetworkMode.DHCP;
|
||||
public String ip = "";
|
||||
public String gateway = "";
|
||||
public String staticIp = "";
|
||||
public String netmask = "";
|
||||
public String hostname = "photonvision";
|
||||
|
||||
// TODO implement networking
|
||||
public boolean shouldManage;
|
||||
|
||||
public NetworkConfig() {}
|
||||
|
||||
public NetworkConfig(
|
||||
int teamNumber,
|
||||
NetworkMode connectionType,
|
||||
String staticIp,
|
||||
String netmask,
|
||||
String hostname,
|
||||
boolean shouldManage) {
|
||||
this.teamNumber = teamNumber;
|
||||
this.connectionType = connectionType;
|
||||
this.staticIp = staticIp;
|
||||
this.netmask = netmask;
|
||||
this.hostname = hostname;
|
||||
this.shouldManage = shouldManage;
|
||||
}
|
||||
|
||||
public static NetworkConfig fromHashMap(Map<String, Object> map) {
|
||||
// teamNumber (int), supported (bool), connectionType (int),
|
||||
// staticIp (str), netmask (str), hostname (str)
|
||||
var ret = new NetworkConfig();
|
||||
ret.teamNumber = Integer.parseInt(map.get("teamNumber").toString());
|
||||
ret.shouldManage = (Boolean) map.get("supported");
|
||||
ret.connectionType = NetworkMode.values()[(Integer) map.get("connectionType")];
|
||||
ret.staticIp = (String) map.get("staticIp");
|
||||
ret.netmask = (String) map.get("netmask");
|
||||
ret.hostname = (String) map.get("hostname");
|
||||
return ret;
|
||||
}
|
||||
|
||||
public HashMap<String, Object> toHashMap() {
|
||||
HashMap<String, Object> tmp = new HashMap<>();
|
||||
tmp.put("teamNumber", teamNumber);
|
||||
tmp.put("supported", shouldManage);
|
||||
tmp.put("connectionType", connectionType.ordinal());
|
||||
tmp.put("ip", ip);
|
||||
tmp.put("gateway", gateway);
|
||||
tmp.put("staticIp", staticIp);
|
||||
tmp.put("netmask", netmask);
|
||||
tmp.put("hostname", hostname);
|
||||
return tmp;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -21,6 +21,7 @@ import java.util.HashMap;
|
||||
import java.util.List;
|
||||
import java.util.Map;
|
||||
import java.util.stream.Collectors;
|
||||
import org.photonvision.PhotonVersion;
|
||||
import org.photonvision.common.util.SerializationUtils;
|
||||
import org.photonvision.vision.processes.VisionModule;
|
||||
import org.photonvision.vision.processes.VisionModuleManager;
|
||||
@@ -35,6 +36,10 @@ public class PhotonConfiguration {
|
||||
return networkConfig;
|
||||
}
|
||||
|
||||
public void setNetworkConfig(NetworkConfig networkConfig) {
|
||||
this.networkConfig = networkConfig;
|
||||
}
|
||||
|
||||
public HashMap<String, CameraConfiguration> getCameraConfigurations() {
|
||||
return cameraConfigurations;
|
||||
}
|
||||
@@ -54,6 +59,7 @@ public class PhotonConfiguration {
|
||||
}
|
||||
|
||||
private HardwareConfig hardwareConfig;
|
||||
|
||||
private NetworkConfig networkConfig;
|
||||
|
||||
private HashMap<String, CameraConfiguration> cameraConfigurations;
|
||||
@@ -73,8 +79,9 @@ public class PhotonConfiguration {
|
||||
|
||||
public Map<String, Object> toHashMap() {
|
||||
Map<String, Object> map = new HashMap<>();
|
||||
var settingsSubmap = new HashMap<String, Object>();
|
||||
|
||||
map.put("networkSettings", networkConfig.toHashMap());
|
||||
settingsSubmap.put("networkSettings", networkConfig.toHashMap());
|
||||
map.put(
|
||||
"cameraSettings",
|
||||
VisionModuleManager.getInstance().getModules().stream()
|
||||
@@ -82,6 +89,17 @@ public class PhotonConfiguration {
|
||||
.map(SerializationUtils::objectToHashMap)
|
||||
.collect(Collectors.toList()));
|
||||
|
||||
settingsSubmap.put("lighting", SerializationUtils.objectToHashMap(hardwareConfig));
|
||||
|
||||
var generalSubmap = new HashMap<String, Object>();
|
||||
generalSubmap.put("version", PhotonVersion.versionString);
|
||||
generalSubmap.put("gpuAcceleration", false); // TODO gpu accel and accel type
|
||||
generalSubmap.put("gpuAccelerationType", "Unknown");
|
||||
generalSubmap.put("hardwareModel", "Unknown"); // TODO hardware model and platform
|
||||
generalSubmap.put("hardwarePlatform", "Unknown");
|
||||
settingsSubmap.put("general", generalSubmap);
|
||||
|
||||
map.put("settings", settingsSubmap);
|
||||
return map;
|
||||
}
|
||||
|
||||
@@ -95,5 +113,7 @@ public class PhotonConfiguration {
|
||||
public HashMap<Integer, HashMap<String, Object>> videoFormatList;
|
||||
public int outputStreamPort;
|
||||
public int inputStreamPort;
|
||||
public List<HashMap<String, Object>> calibrations;
|
||||
public boolean isFovConfigurable = true;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -68,6 +68,7 @@ public class DataChangeService {
|
||||
}
|
||||
} catch (Exception e) {
|
||||
logger.error("Exception when dispatching event!", e);
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -52,8 +52,6 @@ public class NTDataPublisher implements CVPipelineResultConsumer {
|
||||
private final Supplier<Integer> pipelineIndexSupplier;
|
||||
private final BooleanSupplier driverModeSupplier;
|
||||
|
||||
private String currentCameraNickname;
|
||||
|
||||
public NTDataPublisher(
|
||||
String cameraNickname,
|
||||
Supplier<Integer> pipelineIndexSupplier,
|
||||
@@ -65,7 +63,6 @@ public class NTDataPublisher implements CVPipelineResultConsumer {
|
||||
this.driverModeSupplier = driverModeSupplier;
|
||||
this.driverModeConsumer = driverModeConsumer;
|
||||
|
||||
currentCameraNickname = cameraNickname;
|
||||
updateCameraNickname(cameraNickname);
|
||||
updateEntries();
|
||||
}
|
||||
@@ -146,7 +143,6 @@ public class NTDataPublisher implements CVPipelineResultConsumer {
|
||||
removeEntries();
|
||||
subTable = rootTable.getSubTable(newCameraNickname);
|
||||
updateEntries();
|
||||
currentCameraNickname = newCameraNickname;
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -170,9 +166,9 @@ public class NTDataPublisher implements CVPipelineResultConsumer {
|
||||
targetAreaEntry.forceSetDouble(bestTarget.getArea());
|
||||
targetSkewEntry.forceSetDouble(bestTarget.getSkew());
|
||||
|
||||
var poseX = bestTarget.getRobotRelativePose().getTranslation().getX();
|
||||
var poseY = bestTarget.getRobotRelativePose().getTranslation().getY();
|
||||
var poseRot = bestTarget.getRobotRelativePose().getRotation().getDegrees();
|
||||
var poseX = bestTarget.getCameraToTarget().getTranslation().getX();
|
||||
var poseY = bestTarget.getCameraToTarget().getTranslation().getY();
|
||||
var poseRot = bestTarget.getCameraToTarget().getRotation().getDegrees();
|
||||
targetPoseEntry.forceSetDoubleArray(new double[] {poseX, poseY, poseRot});
|
||||
} else {
|
||||
targetPitchEntry.forceSetDouble(0);
|
||||
|
||||
@@ -27,6 +27,7 @@ import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.scripting.ScriptEventType;
|
||||
import org.photonvision.common.scripting.ScriptManager;
|
||||
|
||||
// TODO refactor this to be a singleton
|
||||
public class NetworkTablesManager {
|
||||
|
||||
private NetworkTablesManager() {}
|
||||
|
||||
@@ -18,7 +18,6 @@
|
||||
package org.photonvision.common.dataflow.websocket;
|
||||
|
||||
import com.fasterxml.jackson.core.JsonProcessingException;
|
||||
import edu.wpi.first.wpilibj.MedianFilter;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.HashMap;
|
||||
@@ -31,10 +30,7 @@ import org.photonvision.vision.pipeline.result.CVPipelineResult;
|
||||
public class UIDataPublisher implements CVPipelineResultConsumer {
|
||||
private static final Logger logger = new Logger(UIDataPublisher.class, LogGroup.VisionModule);
|
||||
|
||||
// TODO check if this is the right spot to do FPS calculation
|
||||
private final MedianFilter fpsAverager = new MedianFilter(10);
|
||||
private final int index;
|
||||
private long lastRunTime = 0;
|
||||
private long lastUIResultUpdateTime = 0;
|
||||
|
||||
public UIDataPublisher(int index) {
|
||||
@@ -45,16 +41,12 @@ public class UIDataPublisher implements CVPipelineResultConsumer {
|
||||
public void accept(CVPipelineResult result) {
|
||||
var now = System.currentTimeMillis();
|
||||
|
||||
var fps = fpsAverager.calculate(1000.0 / (now - lastRunTime));
|
||||
lastRunTime = now;
|
||||
|
||||
// only update the UI at 15hz
|
||||
if (lastUIResultUpdateTime + 1000.0 / 15.0 > now) return;
|
||||
if (lastUIResultUpdateTime + 1000.0 / 10.0 > now) return;
|
||||
|
||||
var uiMap = new HashMap<Integer, HashMap<String, Object>>();
|
||||
var dataMap = new HashMap<String, Object>();
|
||||
|
||||
dataMap.put("fps", fps);
|
||||
dataMap.put("latency", result.getLatencyMillis());
|
||||
|
||||
var targets = result.targets;
|
||||
|
||||
@@ -26,6 +26,7 @@ import org.photonvision.common.util.ShellExec;
|
||||
|
||||
public abstract class GPIOBase {
|
||||
private static final Logger logger = new Logger(GPIOBase.class, LogGroup.General);
|
||||
private static final ShellExec runCommand = new ShellExec(true, true);
|
||||
|
||||
public static HashMap<String, String> commands =
|
||||
new HashMap<>() {
|
||||
@@ -39,8 +40,6 @@ public abstract class GPIOBase {
|
||||
}
|
||||
};
|
||||
|
||||
private static final ShellExec runCommand = new ShellExec(true, true);
|
||||
|
||||
public static String execute(String command) {
|
||||
try {
|
||||
runCommand.executeBashCommand(command);
|
||||
|
||||
@@ -17,6 +17,7 @@
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
@@ -24,12 +25,20 @@ import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.hardware.GPIO.PiGPIO;
|
||||
import org.photonvision.common.hardware.metrics.MetricsBase;
|
||||
import org.photonvision.common.hardware.metrics.MetricsPublisher;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.ShellExec;
|
||||
|
||||
public class HardwareManager {
|
||||
HardwareConfig hardwareConfig;
|
||||
private static final HashMap<Integer, GPIOBase> LEDs = new HashMap<>();
|
||||
private final HashMap<Integer, GPIOBase> LEDs = new HashMap<>();
|
||||
private final ShellExec shellExec = new ShellExec(true, false);
|
||||
private final Logger logger = new Logger(HardwareManager.class, LogGroup.General);
|
||||
|
||||
public static HardwareManager getInstance() {
|
||||
if (Singleton.INSTANCE == null) {
|
||||
Singleton.INSTANCE = new HardwareManager();
|
||||
}
|
||||
return Singleton.INSTANCE;
|
||||
}
|
||||
|
||||
@@ -52,6 +61,7 @@ public class HardwareManager {
|
||||
// Start hardware metrics thread
|
||||
MetricsPublisher.getInstance().startTask();
|
||||
}
|
||||
|
||||
/** Example: HardwareManager.getInstance().getPWM(port).dimLEDs(int dimValue); */
|
||||
public GPIOBase getGPIO(int pin) {
|
||||
return LEDs.get(pin);
|
||||
@@ -81,7 +91,20 @@ public class HardwareManager {
|
||||
LEDs.values().forEach(GPIOBase::shutdown);
|
||||
}
|
||||
|
||||
public boolean restartDevice() {
|
||||
try {
|
||||
return shellExec.executeBashCommand(hardwareConfig.restartHardwareCommand) == 0;
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not restart device!", e);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
public HardwareConfig getConfig() {
|
||||
return hardwareConfig;
|
||||
}
|
||||
|
||||
private static class Singleton {
|
||||
private static final HardwareManager INSTANCE = new HardwareManager();
|
||||
private static HardwareManager INSTANCE;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -36,8 +36,9 @@ public enum Platform {
|
||||
// Completely unsupported
|
||||
UNSUPPORTED("Unsupported Platform");
|
||||
|
||||
private static final ShellExec shell = new ShellExec(true, false);
|
||||
public final String value;
|
||||
public final boolean isRoot = checkForRoot();
|
||||
public static final boolean isRoot = checkForRoot();
|
||||
|
||||
Platform(String value) {
|
||||
this.value = value;
|
||||
@@ -54,21 +55,21 @@ public enum Platform {
|
||||
return this == WINDOWS_64 || this == WINDOWS_32;
|
||||
}
|
||||
|
||||
public boolean isLinux() {
|
||||
return this == LINUX_64 || this == LINUX_RASPBIAN || this == LINUX_ARM64;
|
||||
public static boolean isLinux() {
|
||||
return getCurrentPlatform() == LINUX_64
|
||||
|| getCurrentPlatform() == LINUX_RASPBIAN
|
||||
|| getCurrentPlatform() == LINUX_ARM64;
|
||||
}
|
||||
|
||||
public static boolean isRaspberryPi() {
|
||||
return CurrentPlatform.equals(LINUX_RASPBIAN);
|
||||
}
|
||||
|
||||
private static ShellExec shell = new ShellExec(true, false);
|
||||
|
||||
@SuppressWarnings("StatementWithEmptyBody")
|
||||
private boolean checkForRoot() {
|
||||
private static boolean checkForRoot() {
|
||||
if (isLinux()) {
|
||||
try {
|
||||
shell.execute("id", null, true, "-u");
|
||||
shell.executeBashCommand("id -u");
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
@@ -17,28 +17,22 @@
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
public class CPU extends MetricsBase {
|
||||
public class CPUMetrics extends MetricsBase {
|
||||
|
||||
private CPU() {}
|
||||
|
||||
public static CPU getInstance() {
|
||||
return Singleton.INSTANCE;
|
||||
}
|
||||
public CPUMetrics() {}
|
||||
|
||||
public double getMemory() {
|
||||
if (cpuMemoryCommand.isEmpty()) return 0;
|
||||
return execute(cpuMemoryCommand);
|
||||
}
|
||||
|
||||
// TODO: Command should return in Celsius
|
||||
public double getTemp() {
|
||||
if (cpuTemperatureCommand.isEmpty()) return 0;
|
||||
return execute(cpuTemperatureCommand) / 1000;
|
||||
}
|
||||
|
||||
public double getUtilization() {
|
||||
return execute(cpuUtilizationCommand);
|
||||
}
|
||||
|
||||
private static class Singleton {
|
||||
public static final CPU INSTANCE = new CPU();
|
||||
}
|
||||
}
|
||||
@@ -17,14 +17,7 @@
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
public class GPU extends MetricsBase {
|
||||
|
||||
private GPU() {}
|
||||
|
||||
public static GPU getInstance() {
|
||||
return Singleton.INSTANCE;
|
||||
}
|
||||
|
||||
public class GPUMetrics extends MetricsBase {
|
||||
public double getMemory() {
|
||||
return execute(gpuMemoryCommand);
|
||||
}
|
||||
@@ -32,8 +25,4 @@ public class GPU extends MetricsBase {
|
||||
public double getTemp() {
|
||||
return execute(gpuTemperatureCommand) / 10;
|
||||
}
|
||||
|
||||
private static class Singleton {
|
||||
public static final GPU INSTANCE = new GPU();
|
||||
}
|
||||
}
|
||||
@@ -28,18 +28,18 @@ import org.photonvision.server.UIUpdateType;
|
||||
public class MetricsPublisher {
|
||||
private final HashMap<String, Double> metrics;
|
||||
private static final Logger logger = new Logger(MetricsPublisher.class, LogGroup.General);
|
||||
private static CPU cpu;
|
||||
private static GPU gpu;
|
||||
private static RAM ram;
|
||||
private static CPUMetrics cpuMetrics;
|
||||
private static GPUMetrics gpuMetrics;
|
||||
private static RAMMetrics ramMetrics;
|
||||
|
||||
public static MetricsPublisher getInstance() {
|
||||
return Singleton.INSTANCE;
|
||||
}
|
||||
|
||||
private MetricsPublisher() {
|
||||
cpu = CPU.getInstance();
|
||||
gpu = GPU.getInstance();
|
||||
ram = RAM.getInstance();
|
||||
cpuMetrics = new CPUMetrics();
|
||||
gpuMetrics = new GPUMetrics();
|
||||
ramMetrics = new RAMMetrics();
|
||||
|
||||
metrics = new HashMap<>();
|
||||
}
|
||||
@@ -49,12 +49,12 @@ public class MetricsPublisher {
|
||||
.addTask(
|
||||
"Metrics",
|
||||
() -> {
|
||||
metrics.put("cpuTemp", cpu.getTemp());
|
||||
metrics.put("cpuUtil", cpu.getUtilization());
|
||||
metrics.put("cpuMem", cpu.getMemory());
|
||||
metrics.put("gpuTemp", gpu.getTemp());
|
||||
metrics.put("gpuMem", gpu.getMemory());
|
||||
metrics.put("ramUtil", ram.getUsedRam());
|
||||
metrics.put("cpuTemp", cpuMetrics.getTemp());
|
||||
metrics.put("cpuUtil", cpuMetrics.getUtilization());
|
||||
metrics.put("cpuMem", cpuMetrics.getMemory());
|
||||
metrics.put("gpuTemp", gpuMetrics.getTemp());
|
||||
metrics.put("gpuMem", gpuMetrics.getMemory());
|
||||
metrics.put("ramUtil", ramMetrics.getUsedRam());
|
||||
|
||||
DataChangeService.getInstance()
|
||||
.publishEvent(
|
||||
|
||||
@@ -17,19 +17,10 @@
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
public class RAM extends MetricsBase {
|
||||
private RAM() {}
|
||||
|
||||
public static RAM getInstance() {
|
||||
return Singleton.INSTANCE;
|
||||
}
|
||||
|
||||
public class RAMMetrics extends MetricsBase {
|
||||
// TODO: Output in MBs for consistency
|
||||
public double getUsedRam() {
|
||||
if (ramUsageCommand.isEmpty()) return 0;
|
||||
return execute(ramUsageCommand) / 1000;
|
||||
}
|
||||
|
||||
private static class Singleton {
|
||||
public static final RAM INSTANCE = new RAM();
|
||||
}
|
||||
}
|
||||
@@ -17,21 +17,18 @@
|
||||
|
||||
package org.photonvision.common.logging;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.io.PrintWriter;
|
||||
import java.io.StringWriter;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.channels.AsynchronousFileChannel;
|
||||
import java.io.*;
|
||||
import java.nio.file.Path;
|
||||
import java.nio.file.StandardOpenOption;
|
||||
import java.text.SimpleDateFormat;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Date;
|
||||
import java.util.HashMap;
|
||||
import java.util.List;
|
||||
import java.util.function.Supplier;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.dataflow.DataChangeService;
|
||||
import org.photonvision.common.dataflow.events.OutgoingUIEvent;
|
||||
import org.photonvision.common.util.TimedTaskManager;
|
||||
import org.photonvision.server.SocketHandler;
|
||||
import org.photonvision.server.UIUpdateType;
|
||||
|
||||
@@ -102,6 +99,7 @@ public class Logger {
|
||||
static {
|
||||
currentAppenders.add(new ConsoleLogAppender());
|
||||
currentAppenders.add(new UILogAppender());
|
||||
addFileAppender(ConfigManager.getInstance().getLogPath());
|
||||
}
|
||||
|
||||
@SuppressWarnings("ResultOfMethodCallIgnored")
|
||||
@@ -115,7 +113,7 @@ public class Logger {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
currentAppenders.add(new AsyncFileLogAppender(logFilePath));
|
||||
currentAppenders.add(new FileLogAppender(logFilePath));
|
||||
}
|
||||
|
||||
public static void setLevel(LogGroup group, LogLevel newLevel) {
|
||||
@@ -177,7 +175,7 @@ public class Logger {
|
||||
*/
|
||||
public void error(String message, Throwable t) {
|
||||
log(message, LogLevel.ERROR);
|
||||
log(convertStackTraceToString(t), LogLevel.ERROR, LogLevel.TRACE);
|
||||
log(convertStackTraceToString(t), LogLevel.ERROR, LogLevel.DEBUG);
|
||||
}
|
||||
|
||||
public void warn(Supplier<String> messageSupplier) {
|
||||
@@ -239,25 +237,40 @@ public class Logger {
|
||||
var messageMap = new SocketHandler.UIMap();
|
||||
messageMap.put("logMessage", message);
|
||||
messageMap.put("logLevel", level.code);
|
||||
var superMap = new SocketHandler.UIMap();
|
||||
superMap.put("logMessage", messageMap);
|
||||
DataChangeService.getInstance()
|
||||
.publishEvent(new OutgoingUIEvent<>(UIUpdateType.BROADCAST, "log", messageMap, null));
|
||||
.publishEvent(new OutgoingUIEvent<>(UIUpdateType.BROADCAST, "log", superMap, null));
|
||||
}
|
||||
}
|
||||
|
||||
private static class AsyncFileLogAppender implements LogAppender {
|
||||
private final Path filePath;
|
||||
private static class FileLogAppender implements LogAppender {
|
||||
private OutputStream out;
|
||||
|
||||
public AsyncFileLogAppender(Path logFilePath) {
|
||||
this.filePath = logFilePath;
|
||||
public FileLogAppender(Path logFilePath) {
|
||||
try {
|
||||
this.out = new FileOutputStream(logFilePath.toFile());
|
||||
TimedTaskManager.getInstance()
|
||||
.addTask(
|
||||
"FileLogAppender",
|
||||
() -> {
|
||||
try {
|
||||
out.flush();
|
||||
} catch (IOException ignored) {
|
||||
}
|
||||
},
|
||||
30000L);
|
||||
} catch (FileNotFoundException e) {
|
||||
out = null;
|
||||
System.err.println("Unable to log to file " + logFilePath.toString());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void log(String message, LogLevel level) {
|
||||
try (AsynchronousFileChannel asyncFile =
|
||||
AsynchronousFileChannel.open(
|
||||
filePath, StandardOpenOption.WRITE, StandardOpenOption.CREATE)) {
|
||||
|
||||
asyncFile.write(ByteBuffer.wrap(message.getBytes()), 0);
|
||||
message += "\n";
|
||||
try {
|
||||
out.write(message.getBytes());
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
@@ -84,7 +84,7 @@ public class LinuxNetworking extends SysNetworking {
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean setStatic(String ipAddress, String netmask, String gateway) {
|
||||
public boolean setStatic(String ipAddress, String netmask) {
|
||||
setDHCP(); // clean up old static interface
|
||||
File dhcpConf = new File(PATH);
|
||||
try {
|
||||
@@ -93,7 +93,6 @@ public class LinuxNetworking extends SysNetworking {
|
||||
InetAddress iNetMask = InetAddress.getByName(netmask);
|
||||
int prefix = convertNetmaskToCIDR(iNetMask);
|
||||
lines.add("static ip_address=" + ipAddress + "/" + prefix);
|
||||
lines.add("static routers=" + gateway);
|
||||
FileUtils.writeLines(dhcpConf, lines);
|
||||
return true;
|
||||
} catch (IOException e) {
|
||||
|
||||
@@ -27,25 +27,23 @@ public class NetworkInterface {
|
||||
|
||||
public final String name;
|
||||
public final String displayName;
|
||||
public final String IPAddress;
|
||||
public final String Netmask;
|
||||
public final String Gateway;
|
||||
public final String Broadcast;
|
||||
public final String ipAddress;
|
||||
public final String netmask;
|
||||
public final String broadcast;
|
||||
|
||||
public NetworkInterface(java.net.NetworkInterface inetface, InterfaceAddress ifaceAddress) {
|
||||
name = inetface.getName();
|
||||
displayName = inetface.getDisplayName();
|
||||
|
||||
var inetAddress = ifaceAddress.getAddress();
|
||||
IPAddress = inetAddress.getHostAddress();
|
||||
Netmask = getIPv4LocalNetMask(ifaceAddress);
|
||||
ipAddress = inetAddress.getHostAddress();
|
||||
netmask = getIPv4LocalNetMask(ifaceAddress);
|
||||
|
||||
// TODO: (low) hack to "get" gateway, this is gross and bad, pls fix
|
||||
var splitIPAddr = IPAddress.split("\\.");
|
||||
var splitIPAddr = ipAddress.split("\\.");
|
||||
splitIPAddr[3] = "1";
|
||||
Gateway = String.join(".", splitIPAddr);
|
||||
splitIPAddr[3] = "255";
|
||||
Broadcast = String.join(".", splitIPAddr);
|
||||
broadcast = String.join(".", splitIPAddr);
|
||||
}
|
||||
|
||||
private static String getIPv4LocalNetMask(InterfaceAddress interfaceAddress) {
|
||||
|
||||
@@ -17,7 +17,17 @@
|
||||
|
||||
package org.photonvision.common.networking;
|
||||
|
||||
import java.io.IOException;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.ShellExec;
|
||||
|
||||
public class NetworkManager {
|
||||
|
||||
private static final Logger logger = new Logger(NetworkManager.class, LogGroup.General);
|
||||
|
||||
private NetworkManager() {}
|
||||
|
||||
private static class SingletonHolder {
|
||||
@@ -35,5 +45,28 @@ public class NetworkManager {
|
||||
if (!isManaged) {
|
||||
return;
|
||||
}
|
||||
|
||||
var config = ConfigManager.getInstance().getConfig().getNetworkConfig();
|
||||
if (Platform.isLinux()) {
|
||||
if (!Platform.isRoot) {
|
||||
logger.error("Cannot manage network without root!");
|
||||
return;
|
||||
}
|
||||
|
||||
if (config.connectionType == NetworkMode.DHCP) {
|
||||
return; // TODO do we need to reconnect or something?
|
||||
} else if (config.connectionType == NetworkMode.STATIC) {
|
||||
try {
|
||||
new ShellExec()
|
||||
.executeBashCommand("ip addr add " + config.staticIp + "/24" + " dev eth0");
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public void reinitialize() {
|
||||
initialize(ConfigManager.getInstance().getConfig().getNetworkConfig().shouldManage);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -78,7 +78,7 @@ public abstract class SysNetworking {
|
||||
|
||||
public abstract boolean setHostname(String hostname);
|
||||
|
||||
public abstract boolean setStatic(String ipAddress, String netmask, String gateway);
|
||||
public abstract boolean setStatic(String ipAddress, String netmask);
|
||||
|
||||
public abstract List<java.net.NetworkInterface> getNetworkInterfaces() throws SocketException;
|
||||
}
|
||||
|
||||
@@ -102,8 +102,7 @@ public class ScriptManager {
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serializer(
|
||||
scriptConfigPath, eventsConfig.toArray(new ScriptConfig[0]), true);
|
||||
JacksonUtils.serialize(scriptConfigPath, eventsConfig.toArray(new ScriptConfig[0]), true);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to initialize!", e);
|
||||
}
|
||||
|
||||
@@ -24,6 +24,7 @@ import java.nio.file.Path;
|
||||
import java.nio.file.attribute.PosixFileAttributes;
|
||||
import java.nio.file.attribute.PosixFilePermission;
|
||||
import java.util.Arrays;
|
||||
import java.util.Comparator;
|
||||
import java.util.HashSet;
|
||||
import java.util.Set;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
@@ -38,6 +39,25 @@ public class FileUtils {
|
||||
private static final Set<PosixFilePermission> allReadWriteExecutePerms =
|
||||
new HashSet<>(Arrays.asList(PosixFilePermission.values()));
|
||||
|
||||
public static void deleteDirectory(Path path) {
|
||||
try {
|
||||
// create a stream
|
||||
var files = Files.walk(path);
|
||||
|
||||
// delete directory including files and sub-folders
|
||||
files
|
||||
.sorted(Comparator.reverseOrder())
|
||||
.map(Path::toFile)
|
||||
.filter(File::isFile)
|
||||
.forEach(File::delete);
|
||||
|
||||
// close the stream
|
||||
files.close();
|
||||
} catch (IOException e) {
|
||||
logger.error("Exception deleting files in " + path + "!", e);
|
||||
}
|
||||
}
|
||||
|
||||
public static void setFilePerms(Path path) throws IOException {
|
||||
if (!Platform.CurrentPlatform.isWindows()) {
|
||||
File thisFile = path.toFile();
|
||||
|
||||
@@ -32,11 +32,11 @@ import java.io.IOException;
|
||||
import java.nio.file.Path;
|
||||
|
||||
public class JacksonUtils {
|
||||
public static <T> void serializer(Path path, T object) throws IOException {
|
||||
serializer(path, object, false);
|
||||
public static <T> void serialize(Path path, T object) throws IOException {
|
||||
serialize(path, object, false);
|
||||
}
|
||||
|
||||
public static <T> void serializer(Path path, T object, boolean forceSync) throws IOException {
|
||||
public static <T> void serialize(Path path, T object, boolean forceSync) throws IOException {
|
||||
PolymorphicTypeValidator ptv =
|
||||
BasicPolymorphicTypeValidator.builder().allowIfBaseType(object.getClass()).build();
|
||||
ObjectMapper objectMapper =
|
||||
@@ -93,7 +93,17 @@ public class JacksonUtils {
|
||||
}
|
||||
|
||||
private static void saveJsonString(String json, Path path, boolean forceSync) throws IOException {
|
||||
FileOutputStream fileOutputStream = new FileOutputStream(path.toFile());
|
||||
var file = path.toFile();
|
||||
if (file.getParentFile() != null && !file.getParentFile().exists()) {
|
||||
file.getParentFile().mkdirs();
|
||||
}
|
||||
if (!file.exists()) {
|
||||
if (!file.canWrite()) {
|
||||
file.setWritable(true);
|
||||
}
|
||||
file.createNewFile();
|
||||
}
|
||||
FileOutputStream fileOutputStream = new FileOutputStream(file);
|
||||
fileOutputStream.write(json.getBytes());
|
||||
fileOutputStream.flush();
|
||||
if (forceSync) {
|
||||
|
||||
Reference in New Issue
Block a user