mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Fix driver mode settings, sort resolutions (#115)
* Fix DriverMode settings * Update FileVisionSource.java * Sort modes by resolution * Filter duplicated modes * run spotless * Fix calibration bug * run format * aaaaa * Add hardware and platform support * decrease timing sensitivity * Better handle jvm exitg * Make reboot happen immediately * Cleanup restart * Remove debug print * Fix Jackson exploding when deserializing old versions of configs * Add unit test for old config versions * Run format * Add a comment * remove isvendorcam from pipeline manager * oops
This commit is contained in:
@@ -49,7 +49,6 @@ public class CameraConfiguration {
|
||||
public CameraType cameraType = CameraType.UsbCamera;
|
||||
public double FOV = 70;
|
||||
public final List<CameraCalibrationCoefficients> calibrations;
|
||||
public List<Integer> cameraLeds = new ArrayList<>();
|
||||
public int currentPipelineIndex = 0;
|
||||
public Rotation2d camPitch = new Rotation2d();
|
||||
|
||||
@@ -89,7 +88,6 @@ public class CameraConfiguration {
|
||||
@JsonProperty("path") String path,
|
||||
@JsonProperty("cameraType") CameraType cameraType,
|
||||
@JsonProperty("calibration") List<CameraCalibrationCoefficients> calibrations,
|
||||
@JsonProperty("cameraLEDs") List<Integer> cameraLeds,
|
||||
@JsonProperty("currentPipelineIndex") int currentPipelineIndex,
|
||||
@JsonProperty("camPitch") Rotation2d camPitch) {
|
||||
this.baseName = baseName;
|
||||
@@ -99,7 +97,6 @@ public class CameraConfiguration {
|
||||
this.path = path;
|
||||
this.cameraType = cameraType;
|
||||
this.calibrations = calibrations != null ? calibrations : new ArrayList<>();
|
||||
this.cameraLeds = cameraLeds;
|
||||
this.currentPipelineIndex = currentPipelineIndex;
|
||||
this.camPitch = camPitch;
|
||||
|
||||
|
||||
@@ -301,12 +301,8 @@ public class ConfigManager {
|
||||
return loadedConfigurations;
|
||||
}
|
||||
|
||||
public void addCameraConfigurations(HashMap<VisionSource, List<CVPipelineSettings>> sources) {
|
||||
List<CameraConfiguration> list =
|
||||
sources.keySet().stream()
|
||||
.map(it -> it.getSettables().getConfiguration())
|
||||
.collect(Collectors.toList());
|
||||
getConfig().addCameraConfigs(list);
|
||||
public void addCameraConfigurations(HashMap<VisionSource, CameraConfiguration> sources) {
|
||||
getConfig().addCameraConfigs(sources.values());
|
||||
requestSave();
|
||||
}
|
||||
|
||||
|
||||
@@ -18,6 +18,8 @@
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.Collections;
|
||||
import java.util.List;
|
||||
|
||||
public class HardwareConfig {
|
||||
|
||||
@@ -47,6 +49,7 @@ public class HardwareConfig {
|
||||
// Device stuff
|
||||
public final String restartHardwareCommand;
|
||||
public final double vendorFOV; // -1 for unmanaged
|
||||
public final List<Integer> blacklistedResIndices; // this happens before the defaults are applied
|
||||
|
||||
public HardwareConfig() {
|
||||
deviceName = "";
|
||||
@@ -71,6 +74,7 @@ public class HardwareConfig {
|
||||
|
||||
restartHardwareCommand = "";
|
||||
vendorFOV = -1;
|
||||
blacklistedResIndices = Collections.emptyList();
|
||||
}
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
@@ -94,7 +98,8 @@ public class HardwareConfig {
|
||||
String gpuTempCommand,
|
||||
String ramUtilCommand,
|
||||
String restartHardwareCommand,
|
||||
double vendorFOV) {
|
||||
double vendorFOV,
|
||||
List<Integer> blacklistedResIndices) {
|
||||
this.deviceName = deviceName;
|
||||
this.deviceLogoPath = deviceLogoPath;
|
||||
this.supportURL = supportURL;
|
||||
@@ -115,6 +120,7 @@ public class HardwareConfig {
|
||||
this.ramUtilCommand = ramUtilCommand;
|
||||
this.restartHardwareCommand = restartHardwareCommand;
|
||||
this.vendorFOV = vendorFOV;
|
||||
this.blacklistedResIndices = blacklistedResIndices;
|
||||
}
|
||||
|
||||
public final boolean hasPresetFOV() {
|
||||
|
||||
@@ -17,11 +17,13 @@
|
||||
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
import java.util.Collection;
|
||||
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.hardware.Platform;
|
||||
import org.photonvision.common.util.SerializationUtils;
|
||||
import org.photonvision.vision.processes.VisionModule;
|
||||
import org.photonvision.vision.processes.VisionModuleManager;
|
||||
@@ -44,7 +46,7 @@ public class PhotonConfiguration {
|
||||
return cameraConfigurations;
|
||||
}
|
||||
|
||||
public void addCameraConfigs(List<CameraConfiguration> config) {
|
||||
public void addCameraConfigs(Collection<CameraConfiguration> config) {
|
||||
for (var c : config) {
|
||||
addCameraConfig(c);
|
||||
}
|
||||
@@ -95,8 +97,8 @@ public class PhotonConfiguration {
|
||||
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");
|
||||
generalSubmap.put("hardwareModel", hardwareConfig.deviceName);
|
||||
generalSubmap.put("hardwarePlatform", Platform.getCurrentPlatform().toString());
|
||||
settingsSubmap.put("general", generalSubmap);
|
||||
|
||||
map.put("settings", settingsSubmap);
|
||||
|
||||
@@ -19,14 +19,12 @@ package org.photonvision.common.hardware;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import java.io.IOException;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.ProgramStatus;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.dataflow.networktables.NTDataChangeListener;
|
||||
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.hardware.VisionLED.VisionLEDMode;
|
||||
import org.photonvision.common.hardware.metrics.MetricsBase;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
@@ -36,13 +34,17 @@ import org.photonvision.common.util.ShellExec;
|
||||
public class HardwareManager {
|
||||
private static HardwareManager instance;
|
||||
|
||||
private final HashMap<Integer, GPIOBase> VisionLEDs = new HashMap<>();
|
||||
private final ShellExec shellExec = new ShellExec(true, false);
|
||||
private final Logger logger = new Logger(HardwareManager.class, LogGroup.General);
|
||||
|
||||
private final HardwareConfig hardwareConfig;
|
||||
|
||||
@SuppressWarnings("FieldCanBeLocal")
|
||||
private final StatusLED statusLED;
|
||||
|
||||
private final NetworkTableEntry ledModeEntry;
|
||||
|
||||
@SuppressWarnings("FieldCanBeLocal")
|
||||
private final NTDataChangeListener ledModeListener;
|
||||
|
||||
public final VisionLED visionLED;
|
||||
@@ -64,17 +66,34 @@ public class HardwareManager {
|
||||
new VisionLED(
|
||||
hardwareConfig.ledPins,
|
||||
hardwareConfig.ledPWMFrequency,
|
||||
hardwareConfig.ledPWMRange.get(1));
|
||||
(hardwareConfig.ledPWMRange != null && hardwareConfig.ledPWMRange.size() == 2)
|
||||
? hardwareConfig.ledPWMRange.get(1)
|
||||
: 0);
|
||||
|
||||
ledModeEntry = NetworkTablesManager.getInstance().kRootTable.getEntry("ledMode");
|
||||
ledModeEntry.setNumber(VisionLEDMode.VLM_DEFAULT.value);
|
||||
ledModeListener = new NTDataChangeListener(ledModeEntry, visionLED::onLedModeChange);
|
||||
|
||||
Runtime.getRuntime().addShutdownHook(new Thread(this::onJvmExit));
|
||||
|
||||
// Start hardware metrics thread (Disabled until implemented)
|
||||
// if (Platform.isLinux()) MetricsPublisher.getInstance().startTask();
|
||||
}
|
||||
|
||||
private void onJvmExit() {
|
||||
logger.info("Shutting down...");
|
||||
visionLED.setState(false);
|
||||
}
|
||||
|
||||
public boolean restartDevice() {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
try {
|
||||
return shellExec.executeBashCommand("reboot now") == 0;
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not restart device!", e);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
try {
|
||||
return shellExec.executeBashCommand(hardwareConfig.restartHardwareCommand) == 0;
|
||||
} catch (IOException e) {
|
||||
|
||||
@@ -88,7 +88,7 @@ public enum Platform {
|
||||
return false;
|
||||
}
|
||||
|
||||
private static Platform getCurrentPlatform() {
|
||||
public static Platform getCurrentPlatform() {
|
||||
if (RuntimeDetector.isWindows()) {
|
||||
if (RuntimeDetector.is32BitIntel()) return WINDOWS_32;
|
||||
if (RuntimeDetector.is64BitIntel()) return WINDOWS_64;
|
||||
|
||||
@@ -18,6 +18,7 @@
|
||||
package org.photonvision.common.util.file;
|
||||
|
||||
import com.fasterxml.jackson.core.json.JsonReadFeature;
|
||||
import com.fasterxml.jackson.databind.DeserializationFeature;
|
||||
import com.fasterxml.jackson.databind.ObjectMapper;
|
||||
import com.fasterxml.jackson.databind.deser.std.StdDeserializer;
|
||||
import com.fasterxml.jackson.databind.json.JsonMapper;
|
||||
@@ -53,6 +54,7 @@ public class JacksonUtils {
|
||||
ObjectMapper objectMapper =
|
||||
JsonMapper.builder()
|
||||
.configure(JsonReadFeature.ALLOW_JAVA_COMMENTS, true)
|
||||
.configure(DeserializationFeature.FAIL_ON_UNKNOWN_PROPERTIES, false)
|
||||
.activateDefaultTyping(ptv, ObjectMapper.DefaultTyping.JAVA_LANG_OBJECT)
|
||||
.build();
|
||||
File jsonFile = new File(path.toString());
|
||||
|
||||
Reference in New Issue
Block a user