mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Split photon-server and photon-core (#211)
Uses multiple Gradle projects to support the split.
This commit is contained in:
@@ -1,25 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common;
|
||||
|
||||
public enum ProgramStatus {
|
||||
UHOH,
|
||||
RUNNING,
|
||||
RUNNING_NT,
|
||||
RUNNING_NT_TARGET
|
||||
}
|
||||
@@ -1,150 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
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;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.camera.CameraType;
|
||||
import org.photonvision.vision.pipeline.CVPipelineSettings;
|
||||
import org.photonvision.vision.pipeline.DriverModePipelineSettings;
|
||||
import org.photonvision.vision.processes.PipelineManager;
|
||||
|
||||
public class CameraConfiguration {
|
||||
private static final Logger logger = new Logger(CameraConfiguration.class, LogGroup.Camera);
|
||||
|
||||
/** Name as reported by CSCore */
|
||||
public String baseName = "";
|
||||
|
||||
/** Name used to title the subfolder of this config */
|
||||
public String uniqueName = "";
|
||||
|
||||
/** User-set nickname */
|
||||
public String nickname = "";
|
||||
|
||||
/** Can be either path (ex /dev/videoX) or index (ex 1). */
|
||||
public String path = "";
|
||||
|
||||
public CameraType cameraType = CameraType.UsbCamera;
|
||||
public double FOV = 70;
|
||||
public final List<CameraCalibrationCoefficients> calibrations;
|
||||
public int currentPipelineIndex = 0;
|
||||
public Rotation2d camPitch = new Rotation2d();
|
||||
|
||||
public int streamIndex = 0; // 0 index means ports [1181, 1182], 1 means [1183, 1184], etc...
|
||||
|
||||
@JsonIgnore // this ignores the pipes as we serialize them to their own subfolder
|
||||
public List<CVPipelineSettings> pipelineSettings = new ArrayList<>();
|
||||
|
||||
@JsonIgnore
|
||||
public DriverModePipelineSettings driveModeSettings = new DriverModePipelineSettings();
|
||||
|
||||
public CameraConfiguration(String baseName, String path) {
|
||||
this(baseName, baseName, baseName, path);
|
||||
}
|
||||
|
||||
public CameraConfiguration(String baseName, String uniqueName, String nickname, String path) {
|
||||
this.baseName = baseName;
|
||||
this.uniqueName = uniqueName;
|
||||
this.nickname = nickname;
|
||||
this.path = path;
|
||||
this.calibrations = new ArrayList<>();
|
||||
|
||||
logger.debug(
|
||||
"Creating USB camera configuration for "
|
||||
+ cameraType
|
||||
+ baseName
|
||||
+ " (AKA "
|
||||
+ nickname
|
||||
+ ") at "
|
||||
+ path);
|
||||
}
|
||||
|
||||
@JsonCreator
|
||||
public CameraConfiguration(
|
||||
@JsonProperty("baseName") String baseName,
|
||||
@JsonProperty("uniqueName") String uniqueName,
|
||||
@JsonProperty("nickname") String nickname,
|
||||
@JsonProperty("FOV") double FOV,
|
||||
@JsonProperty("path") String path,
|
||||
@JsonProperty("cameraType") CameraType cameraType,
|
||||
@JsonProperty("calibration") List<CameraCalibrationCoefficients> calibrations,
|
||||
@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.calibrations = calibrations != null ? calibrations : new ArrayList<>();
|
||||
this.currentPipelineIndex = currentPipelineIndex;
|
||||
this.camPitch = camPitch;
|
||||
|
||||
logger.debug(
|
||||
"Creating camera configuration for "
|
||||
+ cameraType
|
||||
+ baseName
|
||||
+ " (AKA "
|
||||
+ nickname
|
||||
+ ") at "
|
||||
+ path);
|
||||
}
|
||||
|
||||
public void addPipelineSettings(List<CVPipelineSettings> settings) {
|
||||
for (var setting : settings) {
|
||||
addPipelineSetting(setting);
|
||||
}
|
||||
}
|
||||
|
||||
public void addPipelineSetting(CVPipelineSettings setting) {
|
||||
if (pipelineSettings.stream()
|
||||
.anyMatch(s -> s.pipelineNickname.equalsIgnoreCase(setting.pipelineNickname))) {
|
||||
logger.error("Could not name two pipelines the same thing! Renaming");
|
||||
setting.pipelineNickname += "_1"; // TODO verify this logic
|
||||
}
|
||||
|
||||
if (pipelineSettings.stream().anyMatch(s -> s.pipelineIndex == setting.pipelineIndex)) {
|
||||
var newIndex = pipelineSettings.size();
|
||||
logger.error("Could not insert two pipelines at same index! Changing to " + newIndex);
|
||||
setting.pipelineIndex = newIndex; // TODO verify this logic
|
||||
}
|
||||
|
||||
pipelineSettings.add(setting);
|
||||
pipelineSettings.sort(PipelineManager.PipelineSettingsIndexComparator);
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
@@ -1,436 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
import com.fasterxml.jackson.core.JsonProcessingException;
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Files;
|
||||
import java.nio.file.Path;
|
||||
import java.text.DateFormat;
|
||||
import java.text.ParseException;
|
||||
import java.text.SimpleDateFormat;
|
||||
import java.time.LocalDateTime;
|
||||
import java.time.format.DateTimeFormatter;
|
||||
import java.time.temporal.TemporalAccessor;
|
||||
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.TimedTaskManager;
|
||||
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;
|
||||
|
||||
public static final String HW_CFG_FNAME = "hardwareConfig.json";
|
||||
public static final String HW_SET_FNAME = "hardwareSettings.json";
|
||||
public static final String NET_SET_FNAME = "networkSettings.json";
|
||||
|
||||
private PhotonConfiguration config;
|
||||
private final File hardwareConfigFile;
|
||||
private final File hardwareSettingsFile;
|
||||
private final File networkConfigFile;
|
||||
private final File camerasFolder;
|
||||
|
||||
final File configDirectoryFile;
|
||||
|
||||
private long saveRequestTimestamp = -1;
|
||||
|
||||
public static ConfigManager getInstance() {
|
||||
if (INSTANCE == null) {
|
||||
INSTANCE = new ConfigManager(getRootFolder());
|
||||
}
|
||||
return INSTANCE;
|
||||
}
|
||||
|
||||
public static void saveUploadedSettingsZip(File uploadPath) {
|
||||
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());
|
||||
logger.info("Copied settings successfully!");
|
||||
} catch (IOException e) {
|
||||
logger.error("Exception copying uploaded settings!", e);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
public PhotonConfiguration getConfig() {
|
||||
return config;
|
||||
}
|
||||
|
||||
private static Path getRootFolder() {
|
||||
return Path.of("photonvision_config");
|
||||
}
|
||||
|
||||
ConfigManager(Path configDirectoryFile) {
|
||||
this.configDirectoryFile = new File(configDirectoryFile.toUri());
|
||||
this.hardwareConfigFile =
|
||||
new File(Path.of(configDirectoryFile.toString(), HW_CFG_FNAME).toUri());
|
||||
this.hardwareSettingsFile =
|
||||
new File(Path.of(configDirectoryFile.toString(), HW_SET_FNAME).toUri());
|
||||
this.networkConfigFile =
|
||||
new File(Path.of(configDirectoryFile.toString(), NET_SET_FNAME).toUri());
|
||||
this.camerasFolder = new File(Path.of(configDirectoryFile.toString(), "cameras").toUri());
|
||||
|
||||
TimedTaskManager.getInstance().addTask("ConfigManager", this::checkSaveAndWrite, 1000);
|
||||
}
|
||||
|
||||
public void load() {
|
||||
logger.info("Loading settings...");
|
||||
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;
|
||||
HardwareSettings hardwareSettings;
|
||||
NetworkConfig networkConfig;
|
||||
|
||||
if (hardwareConfigFile.exists()) {
|
||||
try {
|
||||
hardwareConfig =
|
||||
JacksonUtils.deserialize(hardwareConfigFile.toPath(), HardwareConfig.class);
|
||||
if (hardwareConfig == null) {
|
||||
logger.error("Could not deserialize hardware config! Loading defaults");
|
||||
hardwareConfig = new HardwareConfig();
|
||||
}
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not deserialize hardware config! Loading defaults");
|
||||
hardwareConfig = new HardwareConfig();
|
||||
}
|
||||
} else {
|
||||
logger.info("Hardware config does not exist! Loading defaults");
|
||||
hardwareConfig = new HardwareConfig();
|
||||
}
|
||||
|
||||
if (hardwareSettingsFile.exists()) {
|
||||
try {
|
||||
hardwareSettings =
|
||||
JacksonUtils.deserialize(hardwareSettingsFile.toPath(), HardwareSettings.class);
|
||||
if (hardwareSettings == null) {
|
||||
logger.error("Could not deserialize hardware settings! Loading defaults");
|
||||
hardwareSettings = new HardwareSettings();
|
||||
}
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not deserialize hardware settings! Loading defaults");
|
||||
hardwareSettings = new HardwareSettings();
|
||||
}
|
||||
} else {
|
||||
logger.info("Hardware settings does not exist! Loading defaults");
|
||||
hardwareSettings = new HardwareSettings();
|
||||
}
|
||||
|
||||
if (networkConfigFile.exists()) {
|
||||
try {
|
||||
networkConfig = JacksonUtils.deserialize(networkConfigFile.toPath(), NetworkConfig.class);
|
||||
if (networkConfig == null) {
|
||||
logger.error("Could not deserialize network config! Loading defaults");
|
||||
networkConfig = new NetworkConfig();
|
||||
}
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not deserialize network config! Loading defaults");
|
||||
networkConfig = new NetworkConfig();
|
||||
}
|
||||
} else {
|
||||
logger.info("Network config file does not exist! Loading defaults");
|
||||
networkConfig = new NetworkConfig();
|
||||
}
|
||||
|
||||
if (!camerasFolder.exists()) {
|
||||
if (camerasFolder.mkdirs()) {
|
||||
logger.debug("Cameras config folder did not exist. Created!");
|
||||
} else {
|
||||
logger.error("Failed to create cameras config folder!");
|
||||
}
|
||||
}
|
||||
|
||||
HashMap<String, CameraConfiguration> cameraConfigurations = loadCameraConfigs();
|
||||
|
||||
this.config =
|
||||
new PhotonConfiguration(
|
||||
hardwareConfig, hardwareSettings, networkConfig, cameraConfigurations);
|
||||
}
|
||||
|
||||
public void saveToDisk() {
|
||||
// Delete old configs
|
||||
FileUtils.deleteDirectory(camerasFolder.toPath());
|
||||
|
||||
try {
|
||||
JacksonUtils.serialize(networkConfigFile.toPath(), config.getNetworkConfig());
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save network config!", e);
|
||||
}
|
||||
try {
|
||||
JacksonUtils.serialize(hardwareSettingsFile.toPath(), config.getHardwareSettings());
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save hardware config!", e);
|
||||
}
|
||||
|
||||
// save all of our cameras
|
||||
var cameraConfigMap = config.getCameraConfigurations();
|
||||
for (var subdirName : cameraConfigMap.keySet()) {
|
||||
var camConfig = cameraConfigMap.get(subdirName);
|
||||
var subdir = Path.of(camerasFolder.toPath().toString(), subdirName);
|
||||
|
||||
if (!subdir.toFile().exists()) {
|
||||
// TODO: check for error
|
||||
subdir.toFile().mkdirs();
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serialize(Path.of(subdir.toString(), "config.json"), camConfig);
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save config.json for " + subdir, e);
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serialize(
|
||||
Path.of(subdir.toString(), "drivermode.json"), camConfig.driveModeSettings);
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save drivermode.json for " + subdir, e);
|
||||
}
|
||||
|
||||
for (var pipe : camConfig.pipelineSettings) {
|
||||
var pipePath = Path.of(subdir.toString(), "pipelines", pipe.pipelineNickname + ".json");
|
||||
|
||||
if (!pipePath.getParent().toFile().exists()) {
|
||||
// TODO: check for error
|
||||
pipePath.getParent().toFile().mkdirs();
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serialize(pipePath, pipe);
|
||||
} catch (IOException e) {
|
||||
logger.error("Could not save " + pipe.pipelineNickname + ".json!", e);
|
||||
}
|
||||
}
|
||||
}
|
||||
logger.info("Settings saved!");
|
||||
}
|
||||
|
||||
private HashMap<String, CameraConfiguration> loadCameraConfigs() {
|
||||
HashMap<String, CameraConfiguration> loadedConfigurations = new HashMap<>();
|
||||
try {
|
||||
var subdirectories =
|
||||
Files.list(camerasFolder.toPath())
|
||||
.filter(f -> f.toFile().isDirectory())
|
||||
.collect(Collectors.toList());
|
||||
|
||||
for (var subdir : subdirectories) {
|
||||
var cameraConfigPath = Path.of(subdir.toString(), "config.json");
|
||||
CameraConfiguration loadedConfig = null;
|
||||
try {
|
||||
loadedConfig =
|
||||
JacksonUtils.deserialize(
|
||||
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");
|
||||
continue; // TODO how do we later try to load this camera if it gets reconnected?
|
||||
}
|
||||
|
||||
// At this point we have only loaded the base stuff
|
||||
// We still need to deserialize pipelines, as well as
|
||||
// driver mode settings
|
||||
var driverModeFile = Path.of(subdir.toString(), "drivermode.json");
|
||||
DriverModePipelineSettings driverMode;
|
||||
try {
|
||||
driverMode =
|
||||
JacksonUtils.deserialize(
|
||||
driverModeFile.toAbsolutePath(), DriverModePipelineSettings.class);
|
||||
} catch (JsonProcessingException e) {
|
||||
logger.error("Could not deserialize drivermode.json! Loading defaults");
|
||||
logger.debug(Arrays.toString(e.getStackTrace()));
|
||||
driverMode = new DriverModePipelineSettings();
|
||||
}
|
||||
if (driverMode == null) {
|
||||
logger.warn(
|
||||
"Could not load camera " + subdir + "'s drivermode.json! Loading" + " default");
|
||||
driverMode = new DriverModePipelineSettings();
|
||||
}
|
||||
|
||||
// Load pipelines by mapping the files within the pipelines subdir
|
||||
// to their deserialized equivalents
|
||||
var pipelineSubdirectory = Path.of(subdir.toString(), "pipelines");
|
||||
List<CVPipelineSettings> settings =
|
||||
pipelineSubdirectory.toFile().exists()
|
||||
? Files.list(pipelineSubdirectory)
|
||||
.filter(p -> p.toFile().isFile())
|
||||
.map(
|
||||
p -> {
|
||||
var relativizedFilePath =
|
||||
configDirectoryFile
|
||||
.toPath()
|
||||
.toAbsolutePath()
|
||||
.relativize(p)
|
||||
.toString();
|
||||
try {
|
||||
return JacksonUtils.deserialize(p, CVPipelineSettings.class);
|
||||
} catch (JsonProcessingException e) {
|
||||
logger.error("Exception while deserializing " + relativizedFilePath, e);
|
||||
} catch (IOException e) {
|
||||
logger.warn(
|
||||
"Could not load pipeline at "
|
||||
+ relativizedFilePath
|
||||
+ "! Skipping...");
|
||||
}
|
||||
return null;
|
||||
})
|
||||
.filter(Objects::nonNull)
|
||||
.collect(Collectors.toList())
|
||||
: Collections.emptyList();
|
||||
|
||||
loadedConfig.driveModeSettings = driverMode;
|
||||
loadedConfig.addPipelineSettings(settings);
|
||||
|
||||
loadedConfigurations.put(subdir.toFile().getName(), loadedConfig);
|
||||
}
|
||||
} catch (IOException e) {
|
||||
logger.error("Error loading camera configs!", e);
|
||||
}
|
||||
return loadedConfigurations;
|
||||
}
|
||||
|
||||
public void addCameraConfigurations(HashMap<VisionSource, CameraConfiguration> sources) {
|
||||
getConfig().addCameraConfigs(sources.values());
|
||||
requestSave();
|
||||
}
|
||||
|
||||
public void saveModule(CameraConfiguration config, String uniqueName) {
|
||||
getConfig().addCameraConfig(uniqueName, config);
|
||||
requestSave();
|
||||
}
|
||||
|
||||
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);
|
||||
requestSave();
|
||||
}
|
||||
|
||||
public Path getLogsDir() {
|
||||
return Path.of(configDirectoryFile.toString(), "logs");
|
||||
}
|
||||
|
||||
public Path getCalibDir() {
|
||||
return Path.of(configDirectoryFile.toString(), "calibImgs");
|
||||
}
|
||||
|
||||
public static final String LOG_PREFIX = "photonvision-";
|
||||
public static final String LOG_EXT = ".log";
|
||||
public static final String LOG_DATE_TIME_FORMAT = "yyyy-M-d_hh-mm-ss";
|
||||
|
||||
public String taToLogFname(TemporalAccessor date) {
|
||||
var dateString = DateTimeFormatter.ofPattern(LOG_DATE_TIME_FORMAT).format(date);
|
||||
return LOG_PREFIX + dateString + LOG_EXT;
|
||||
}
|
||||
|
||||
public Date logFnameToDate(String fname) throws ParseException {
|
||||
// Strip away known unneded portions of the log file name
|
||||
fname = fname.replace(LOG_PREFIX, "").replace(LOG_EXT, "");
|
||||
DateFormat format = new SimpleDateFormat(LOG_DATE_TIME_FORMAT);
|
||||
return format.parse(fname);
|
||||
}
|
||||
|
||||
public Path getLogPath() {
|
||||
var logFile = Path.of(this.getLogsDir().toString(), taToLogFname(LocalDateTime.now())).toFile();
|
||||
if (!logFile.getParentFile().exists()) logFile.getParentFile().mkdirs();
|
||||
return logFile.toPath();
|
||||
}
|
||||
|
||||
public Path getImageSavePath() {
|
||||
var imgFilePath = Path.of(configDirectoryFile.toString(), "imgSaves").toFile();
|
||||
if (!imgFilePath.exists()) imgFilePath.mkdirs();
|
||||
return imgFilePath.toPath();
|
||||
}
|
||||
|
||||
public Path getHardwareConfigFile() {
|
||||
return this.hardwareConfigFile.toPath();
|
||||
}
|
||||
|
||||
public Path getHardwareSettingsFile() {
|
||||
return this.hardwareSettingsFile.toPath();
|
||||
}
|
||||
|
||||
public Path getNetworkConfigFile() {
|
||||
return this.networkConfigFile.toPath();
|
||||
}
|
||||
|
||||
public void saveUploadedHardwareConfig(Path uploadPath) {
|
||||
FileUtils.deleteFile(this.getHardwareConfigFile());
|
||||
FileUtils.copyFile(uploadPath, this.getHardwareConfigFile());
|
||||
}
|
||||
|
||||
public void saveUploadedHardwareSettings(Path uploadPath) {
|
||||
FileUtils.deleteFile(this.getHardwareSettingsFile());
|
||||
FileUtils.copyFile(uploadPath, this.getHardwareSettingsFile());
|
||||
}
|
||||
|
||||
public void saveUploadedNetworkConfig(Path uploadPath) {
|
||||
FileUtils.deleteFile(this.getNetworkConfigFile());
|
||||
FileUtils.copyFile(uploadPath, this.getNetworkConfigFile());
|
||||
}
|
||||
|
||||
public void requestSave() {
|
||||
logger.trace("Requesting save...");
|
||||
saveRequestTimestamp = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
private void checkSaveAndWrite() {
|
||||
// Only save if 1 second has past since the request was made
|
||||
if (saveRequestTimestamp > 0 && (System.currentTimeMillis() - saveRequestTimestamp) > 1000L) {
|
||||
saveRequestTimestamp = -1;
|
||||
logger.debug("Saving to disk...");
|
||||
saveToDisk();
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,127 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Collections;
|
||||
import java.util.List;
|
||||
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
public class HardwareConfig {
|
||||
|
||||
public final String deviceName;
|
||||
public final String deviceLogoPath;
|
||||
public final String supportURL;
|
||||
|
||||
// LED control
|
||||
public final ArrayList<Integer> ledPins;
|
||||
public final String ledSetCommand;
|
||||
public final boolean ledsCanDim;
|
||||
public final ArrayList<Integer> ledBrightnessRange;
|
||||
public final String ledDimCommand;
|
||||
public final String ledBlinkCommand;
|
||||
public final ArrayList<Integer> statusRGBPins;
|
||||
|
||||
// Metrics
|
||||
public final String cpuTempCommand;
|
||||
public final String cpuMemoryCommand;
|
||||
public final String cpuUtilCommand;
|
||||
public final String gpuMemoryCommand;
|
||||
public final String ramUtilCommand;
|
||||
public final String gpuMemUsageCommand;
|
||||
public final String diskUsageCommand;
|
||||
|
||||
// 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 = "";
|
||||
deviceLogoPath = "";
|
||||
supportURL = "";
|
||||
ledPins = new ArrayList<>();
|
||||
ledSetCommand = "";
|
||||
ledsCanDim = false;
|
||||
ledBrightnessRange = new ArrayList<>();
|
||||
statusRGBPins = new ArrayList<>();
|
||||
ledDimCommand = "";
|
||||
|
||||
cpuTempCommand = "";
|
||||
cpuMemoryCommand = "";
|
||||
cpuUtilCommand = "";
|
||||
gpuMemoryCommand = "";
|
||||
ramUtilCommand = "";
|
||||
ledBlinkCommand = "";
|
||||
gpuMemUsageCommand = "";
|
||||
diskUsageCommand = "";
|
||||
|
||||
restartHardwareCommand = "";
|
||||
vendorFOV = -1;
|
||||
blacklistedResIndices = Collections.emptyList();
|
||||
}
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
public HardwareConfig(
|
||||
String deviceName,
|
||||
String deviceLogoPath,
|
||||
String supportURL,
|
||||
ArrayList<Integer> ledPins,
|
||||
String ledSetCommand,
|
||||
boolean ledsCanDim,
|
||||
ArrayList<Integer> ledBrightnessRange,
|
||||
String ledDimCommand,
|
||||
String ledBlinkCommand,
|
||||
ArrayList<Integer> statusRGBPins,
|
||||
String cpuTempCommand,
|
||||
String cpuMemoryCommand,
|
||||
String cpuUtilCommand,
|
||||
String gpuMemoryCommand,
|
||||
String ramUtilCommand,
|
||||
String gpuMemUsageCommand,
|
||||
String diskUsageCommand,
|
||||
String restartHardwareCommand,
|
||||
double vendorFOV,
|
||||
List<Integer> blacklistedResIndices) {
|
||||
this.deviceName = deviceName;
|
||||
this.deviceLogoPath = deviceLogoPath;
|
||||
this.supportURL = supportURL;
|
||||
this.ledPins = ledPins;
|
||||
this.ledSetCommand = ledSetCommand;
|
||||
this.ledsCanDim = ledsCanDim;
|
||||
this.ledBrightnessRange = ledBrightnessRange;
|
||||
this.ledDimCommand = ledDimCommand;
|
||||
this.ledBlinkCommand = ledBlinkCommand;
|
||||
this.statusRGBPins = statusRGBPins;
|
||||
this.cpuTempCommand = cpuTempCommand;
|
||||
this.cpuMemoryCommand = cpuMemoryCommand;
|
||||
this.cpuUtilCommand = cpuUtilCommand;
|
||||
this.gpuMemoryCommand = gpuMemoryCommand;
|
||||
this.ramUtilCommand = ramUtilCommand;
|
||||
this.gpuMemUsageCommand = gpuMemUsageCommand;
|
||||
this.diskUsageCommand = diskUsageCommand;
|
||||
this.restartHardwareCommand = restartHardwareCommand;
|
||||
this.vendorFOV = vendorFOV;
|
||||
this.blacklistedResIndices = blacklistedResIndices;
|
||||
}
|
||||
|
||||
public final boolean hasPresetFOV() {
|
||||
return vendorFOV > 0;
|
||||
}
|
||||
}
|
||||
@@ -1,22 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
public class HardwareSettings {
|
||||
public int ledBrightnessPercentage = 100;
|
||||
}
|
||||
@@ -1,91 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.configuration;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonCreator;
|
||||
import com.fasterxml.jackson.annotation.JsonGetter;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import com.fasterxml.jackson.annotation.JsonSetter;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.networking.NetworkMode;
|
||||
|
||||
public class NetworkConfig {
|
||||
public int teamNumber = 0;
|
||||
public NetworkMode connectionType = NetworkMode.DHCP;
|
||||
public String staticIp = "";
|
||||
public String hostname = "photonvision";
|
||||
public boolean runNTServer = false;
|
||||
|
||||
private boolean shouldManage;
|
||||
|
||||
public NetworkConfig() {
|
||||
setShouldManage(false);
|
||||
}
|
||||
|
||||
@JsonCreator
|
||||
public NetworkConfig(
|
||||
@JsonProperty("teamNumber") int teamNumber,
|
||||
@JsonProperty("connectionType") NetworkMode connectionType,
|
||||
@JsonProperty("staticIp") String staticIp,
|
||||
@JsonProperty("hostname") String hostname,
|
||||
@JsonProperty("runNTServer") boolean runNTServer,
|
||||
@JsonProperty("shouldManage") boolean shouldManage) {
|
||||
this.teamNumber = teamNumber;
|
||||
this.connectionType = connectionType;
|
||||
this.staticIp = staticIp;
|
||||
this.hostname = hostname;
|
||||
this.runNTServer = runNTServer;
|
||||
setShouldManage(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.connectionType = NetworkMode.values()[(Integer) map.get("connectionType")];
|
||||
ret.staticIp = (String) map.get("staticIp");
|
||||
ret.hostname = (String) map.get("hostname");
|
||||
ret.runNTServer = (Boolean) map.get("runNTServer");
|
||||
ret.setShouldManage((Boolean) map.get("supported"));
|
||||
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("staticIp", staticIp);
|
||||
tmp.put("hostname", hostname);
|
||||
tmp.put("runNTServer", runNTServer);
|
||||
return tmp;
|
||||
}
|
||||
|
||||
@JsonGetter("shouldManage")
|
||||
public boolean shouldManage() {
|
||||
return this.shouldManage || Platform.isRaspberryPi();
|
||||
}
|
||||
|
||||
@JsonSetter("shouldManage")
|
||||
public void setShouldManage(boolean shouldManage) {
|
||||
this.shouldManage = shouldManage || Platform.isRaspberryPi();
|
||||
}
|
||||
}
|
||||
@@ -1,142 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
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.raspi.PicamJNI;
|
||||
import org.photonvision.vision.processes.VisionModule;
|
||||
import org.photonvision.vision.processes.VisionModuleManager;
|
||||
|
||||
// TODO rename this class
|
||||
public class PhotonConfiguration {
|
||||
|
||||
private HardwareConfig hardwareConfig;
|
||||
private HardwareSettings hardwareSettings;
|
||||
private NetworkConfig networkConfig;
|
||||
private HashMap<String, CameraConfiguration> cameraConfigurations;
|
||||
|
||||
public PhotonConfiguration(
|
||||
HardwareConfig hardwareConfig,
|
||||
HardwareSettings hardwareSettings,
|
||||
NetworkConfig networkConfig) {
|
||||
this(hardwareConfig, hardwareSettings, networkConfig, new HashMap<>());
|
||||
}
|
||||
|
||||
public PhotonConfiguration(
|
||||
HardwareConfig hardwareConfig,
|
||||
HardwareSettings hardwareSettings,
|
||||
NetworkConfig networkConfig,
|
||||
HashMap<String, CameraConfiguration> cameraConfigurations) {
|
||||
this.hardwareConfig = hardwareConfig;
|
||||
this.hardwareSettings = hardwareSettings;
|
||||
this.networkConfig = networkConfig;
|
||||
this.cameraConfigurations = cameraConfigurations;
|
||||
}
|
||||
|
||||
public HardwareConfig getHardwareConfig() {
|
||||
return hardwareConfig;
|
||||
}
|
||||
|
||||
public NetworkConfig getNetworkConfig() {
|
||||
return networkConfig;
|
||||
}
|
||||
|
||||
public HardwareSettings getHardwareSettings() {
|
||||
return hardwareSettings;
|
||||
}
|
||||
|
||||
public void setNetworkConfig(NetworkConfig networkConfig) {
|
||||
this.networkConfig = networkConfig;
|
||||
}
|
||||
|
||||
public HashMap<String, CameraConfiguration> getCameraConfigurations() {
|
||||
return cameraConfigurations;
|
||||
}
|
||||
|
||||
public void addCameraConfigs(Collection<CameraConfiguration> config) {
|
||||
for (var c : config) {
|
||||
addCameraConfig(c);
|
||||
}
|
||||
}
|
||||
|
||||
public void addCameraConfig(CameraConfiguration config) {
|
||||
addCameraConfig(config.uniqueName, config);
|
||||
}
|
||||
|
||||
public void addCameraConfig(String name, CameraConfiguration config) {
|
||||
cameraConfigurations.put(name, config);
|
||||
}
|
||||
|
||||
public Map<String, Object> toHashMap() {
|
||||
Map<String, Object> map = new HashMap<>();
|
||||
var settingsSubmap = new HashMap<String, Object>();
|
||||
|
||||
settingsSubmap.put("networkSettings", networkConfig.toHashMap());
|
||||
map.put(
|
||||
"cameraSettings",
|
||||
VisionModuleManager.getInstance().getModules().stream()
|
||||
.map(VisionModule::toUICameraConfig)
|
||||
.map(SerializationUtils::objectToHashMap)
|
||||
.collect(Collectors.toList()));
|
||||
|
||||
var lightingConfig = new UILightingConfig();
|
||||
lightingConfig.brightness = hardwareSettings.ledBrightnessPercentage;
|
||||
lightingConfig.supported = (hardwareConfig.ledPins.size() != 0);
|
||||
settingsSubmap.put("lighting", SerializationUtils.objectToHashMap(lightingConfig));
|
||||
|
||||
var generalSubmap = new HashMap<String, Object>();
|
||||
generalSubmap.put("version", PhotonVersion.versionString);
|
||||
generalSubmap.put(
|
||||
"gpuAcceleration",
|
||||
PicamJNI.isSupported()
|
||||
? "Zerocopy MMAL on " + PicamJNI.getSensorModel().getFriendlyName()
|
||||
: ""); // TODO add support for other types of GPU accel
|
||||
generalSubmap.put("hardwareModel", hardwareConfig.deviceName);
|
||||
generalSubmap.put("hardwarePlatform", Platform.getCurrentPlatform().toString());
|
||||
settingsSubmap.put("general", generalSubmap);
|
||||
|
||||
map.put("settings", settingsSubmap);
|
||||
return map;
|
||||
}
|
||||
|
||||
public static class UILightingConfig {
|
||||
public int brightness = 0;
|
||||
public boolean supported = true;
|
||||
}
|
||||
|
||||
public static class UICameraConfiguration {
|
||||
@SuppressWarnings("unused")
|
||||
public double fov, tiltDegrees;
|
||||
public String nickname;
|
||||
public HashMap<String, Object> currentPipelineSettings;
|
||||
public int currentPipelineIndex;
|
||||
public List<String> pipelineNicknames;
|
||||
public HashMap<Integer, HashMap<String, Object>> videoFormatList;
|
||||
public int outputStreamPort;
|
||||
public int inputStreamPort;
|
||||
public List<HashMap<String, Object>> calibrations;
|
||||
public boolean isFovConfigurable = true;
|
||||
}
|
||||
}
|
||||
@@ -1,23 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow;
|
||||
|
||||
import java.util.function.Consumer;
|
||||
import org.photonvision.vision.pipeline.result.CVPipelineResult;
|
||||
|
||||
public interface CVPipelineResultConsumer extends Consumer<CVPipelineResult> {}
|
||||
@@ -1,35 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.List;
|
||||
|
||||
public enum DataChangeDestination {
|
||||
DCD_ACTIVEMODULE,
|
||||
DCD_ACTIVEPIPELINESETTINGS,
|
||||
DCD_GENSETTINGS,
|
||||
DCD_UI,
|
||||
DCD_OTHER;
|
||||
|
||||
public static final List<DataChangeDestination> AllDestinations =
|
||||
Arrays.asList(DataChangeDestination.values());
|
||||
|
||||
public static class DataChangeDestinationList extends ArrayList<DataChangeDestination> {}
|
||||
}
|
||||
@@ -1,111 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow;
|
||||
|
||||
import java.util.concurrent.BlockingQueue;
|
||||
import java.util.concurrent.CopyOnWriteArrayList;
|
||||
import java.util.concurrent.LinkedBlockingQueue;
|
||||
import java.util.stream.Collectors;
|
||||
import org.photonvision.common.dataflow.events.DataChangeEvent;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
@SuppressWarnings("rawtypes")
|
||||
public class DataChangeService {
|
||||
|
||||
private static final Logger logger = new Logger(DataChangeService.class, LogGroup.WebServer);
|
||||
|
||||
private static class ThreadSafeSingleton {
|
||||
private static final DataChangeService INSTANCE = new DataChangeService();
|
||||
}
|
||||
|
||||
public static DataChangeService getInstance() {
|
||||
return ThreadSafeSingleton.INSTANCE;
|
||||
}
|
||||
|
||||
private final CopyOnWriteArrayList<DataChangeSubscriber> subscribers;
|
||||
|
||||
@SuppressWarnings("FieldCanBeLocal")
|
||||
private final Thread dispatchThread;
|
||||
|
||||
private final BlockingQueue<DataChangeEvent> eventQueue = new LinkedBlockingQueue<>();
|
||||
|
||||
private DataChangeService() {
|
||||
subscribers = new CopyOnWriteArrayList<>();
|
||||
dispatchThread = new Thread(this::dispatchFromQueue);
|
||||
dispatchThread.setName("DataChangeEventDispatchThread");
|
||||
dispatchThread.start();
|
||||
}
|
||||
|
||||
public boolean hasEvents() {
|
||||
return !eventQueue.isEmpty();
|
||||
}
|
||||
|
||||
private void dispatchFromQueue() {
|
||||
while (true) {
|
||||
try {
|
||||
var taken = eventQueue.take();
|
||||
for (var sub : subscribers) {
|
||||
if (sub.wantedSources.contains(taken.sourceType)
|
||||
&& sub.wantedDestinations.contains(taken.destType)) {
|
||||
sub.onDataChangeEvent(taken);
|
||||
}
|
||||
}
|
||||
} catch (Exception e) {
|
||||
logger.error("Exception when dispatching event!", e);
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public void addSubscriber(DataChangeSubscriber subscriber) {
|
||||
if (!subscribers.addIfAbsent(subscriber)) {
|
||||
logger.warn("Attempted to add already added subscriber!");
|
||||
} else {
|
||||
logger.debug(
|
||||
() -> {
|
||||
var sources =
|
||||
subscriber.wantedSources.stream()
|
||||
.map(Enum::toString)
|
||||
.collect(Collectors.joining(", "));
|
||||
var dests =
|
||||
subscriber.wantedDestinations.stream()
|
||||
.map(Enum::toString)
|
||||
.collect(Collectors.joining(", "));
|
||||
|
||||
return "Added subscriber - " + "Sources: " + sources + ", Destinations: " + dests;
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
public void addSubscribers(DataChangeSubscriber... subs) {
|
||||
for (var sub : subs) {
|
||||
addSubscriber(sub);
|
||||
}
|
||||
}
|
||||
|
||||
public void publishEvent(DataChangeEvent event) {
|
||||
eventQueue.offer(event);
|
||||
}
|
||||
|
||||
public void publishEvents(DataChangeEvent... events) {
|
||||
for (var event : events) {
|
||||
publishEvent(event);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.List;
|
||||
|
||||
public enum DataChangeSource {
|
||||
DCS_WEBSOCKET,
|
||||
DCS_HTTP,
|
||||
DCS_NETWORKTABLES,
|
||||
DCS_VISIONMODULE,
|
||||
DCS_OTHER;
|
||||
|
||||
public static final List<DataChangeSource> AllSources = Arrays.asList(DataChangeSource.values());
|
||||
|
||||
public static class DataChangeSourceList extends ArrayList<DataChangeSource> {}
|
||||
}
|
||||
@@ -1,56 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow;
|
||||
|
||||
import java.util.List;
|
||||
import java.util.Objects;
|
||||
import org.photonvision.common.dataflow.events.DataChangeEvent;
|
||||
|
||||
@SuppressWarnings("rawtypes")
|
||||
public abstract class DataChangeSubscriber {
|
||||
public final List<DataChangeSource> wantedSources;
|
||||
public final List<DataChangeDestination> wantedDestinations;
|
||||
|
||||
private final int hash;
|
||||
|
||||
public DataChangeSubscriber(
|
||||
List<DataChangeSource> wantedSources, List<DataChangeDestination> wantedDestinations) {
|
||||
this.wantedSources = wantedSources;
|
||||
this.wantedDestinations = wantedDestinations;
|
||||
hash = Objects.hash(wantedSources, wantedDestinations);
|
||||
}
|
||||
|
||||
public DataChangeSubscriber() {
|
||||
this(DataChangeSource.AllSources, DataChangeDestination.AllDestinations);
|
||||
}
|
||||
|
||||
public DataChangeSubscriber(DataChangeSource.DataChangeSourceList wantedSources) {
|
||||
this(wantedSources, DataChangeDestination.AllDestinations);
|
||||
}
|
||||
|
||||
public DataChangeSubscriber(DataChangeDestination.DataChangeDestinationList wantedDestinations) {
|
||||
this(DataChangeSource.AllSources, wantedDestinations);
|
||||
}
|
||||
|
||||
public abstract void onDataChangeEvent(DataChangeEvent<?> event);
|
||||
|
||||
@Override
|
||||
public int hashCode() {
|
||||
return hash;
|
||||
}
|
||||
}
|
||||
@@ -1,54 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.events;
|
||||
|
||||
import org.photonvision.common.dataflow.DataChangeDestination;
|
||||
import org.photonvision.common.dataflow.DataChangeSource;
|
||||
|
||||
public class DataChangeEvent<T> {
|
||||
public final DataChangeSource sourceType;
|
||||
public final DataChangeDestination destType;
|
||||
public final String propertyName;
|
||||
public final T data;
|
||||
|
||||
public DataChangeEvent(
|
||||
DataChangeSource sourceType,
|
||||
DataChangeDestination destType,
|
||||
String propertyName,
|
||||
T newValue) {
|
||||
this.sourceType = sourceType;
|
||||
this.destType = destType;
|
||||
this.propertyName = propertyName;
|
||||
this.data = newValue;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "DataChangeEvent{"
|
||||
+ "sourceType="
|
||||
+ sourceType
|
||||
+ ", destType="
|
||||
+ destType
|
||||
+ ", propertyName='"
|
||||
+ propertyName
|
||||
+ '\''
|
||||
+ ", data="
|
||||
+ data
|
||||
+ '}';
|
||||
}
|
||||
}
|
||||
@@ -1,31 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.events;
|
||||
|
||||
import org.photonvision.common.dataflow.DataChangeDestination;
|
||||
import org.photonvision.common.dataflow.DataChangeSource;
|
||||
|
||||
public class HTTPRequestEvent<T> extends DataChangeEvent<T> {
|
||||
public HTTPRequestEvent(
|
||||
DataChangeSource sourceType,
|
||||
DataChangeDestination destType,
|
||||
String propertyName,
|
||||
T newValue) {
|
||||
super(sourceType, destType, propertyName, newValue);
|
||||
}
|
||||
}
|
||||
@@ -1,67 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.events;
|
||||
|
||||
import io.javalin.websocket.WsContext;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.dataflow.DataChangeDestination;
|
||||
import org.photonvision.common.dataflow.DataChangeSource;
|
||||
|
||||
public class IncomingWebSocketEvent<T> extends DataChangeEvent<T> {
|
||||
|
||||
public final Integer cameraIndex;
|
||||
public final WsContext originContext;
|
||||
|
||||
public IncomingWebSocketEvent(DataChangeDestination destType, String propertyName, T newValue) {
|
||||
this(destType, propertyName, newValue, null, null);
|
||||
}
|
||||
|
||||
public IncomingWebSocketEvent(
|
||||
DataChangeDestination destType,
|
||||
String propertyName,
|
||||
T newValue,
|
||||
Integer cameraIndex,
|
||||
WsContext originContext) {
|
||||
super(DataChangeSource.DCS_WEBSOCKET, destType, propertyName, newValue);
|
||||
this.cameraIndex = cameraIndex;
|
||||
this.originContext = originContext;
|
||||
}
|
||||
|
||||
@SuppressWarnings("unchecked")
|
||||
public IncomingWebSocketEvent(
|
||||
DataChangeDestination destType, String dataKey, HashMap<String, Object> data) {
|
||||
this(destType, dataKey, (T) data.get(dataKey));
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "IncomingWebSocketEvent{"
|
||||
+ "cameraIndex="
|
||||
+ cameraIndex
|
||||
+ ", sourceType="
|
||||
+ sourceType
|
||||
+ ", destType="
|
||||
+ destType
|
||||
+ ", propertyName='"
|
||||
+ propertyName
|
||||
+ '\''
|
||||
+ ", data="
|
||||
+ data
|
||||
+ '}';
|
||||
}
|
||||
}
|
||||
@@ -1,44 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.events;
|
||||
|
||||
import io.javalin.websocket.WsContext;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.dataflow.DataChangeDestination;
|
||||
import org.photonvision.common.dataflow.DataChangeSource;
|
||||
|
||||
public class OutgoingUIEvent<T> extends DataChangeEvent<T> {
|
||||
public final WsContext originContext;
|
||||
|
||||
public OutgoingUIEvent(String propertyName, T newValue) {
|
||||
this(propertyName, newValue, null);
|
||||
}
|
||||
|
||||
public OutgoingUIEvent(String propertyName, T newValue, WsContext originContext) {
|
||||
super(DataChangeSource.DCS_WEBSOCKET, DataChangeDestination.DCD_UI, propertyName, newValue);
|
||||
this.originContext = originContext;
|
||||
}
|
||||
|
||||
public static OutgoingUIEvent<HashMap<String, Object>> wrappedOf(
|
||||
String commandName, String propertyName, Object value, WsContext originContext) {
|
||||
HashMap<String, Object> data = new HashMap<>();
|
||||
data.put(propertyName, value);
|
||||
|
||||
return new OutgoingUIEvent<>(commandName, data, originContext);
|
||||
}
|
||||
}
|
||||
@@ -1,39 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.networktables;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.EntryNotification;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import java.util.function.Consumer;
|
||||
|
||||
public class NTDataChangeListener {
|
||||
|
||||
private final NetworkTableEntry watchedEntry;
|
||||
private final int listenerID;
|
||||
|
||||
public NTDataChangeListener(
|
||||
NetworkTableEntry watchedEntry, Consumer<EntryNotification> dataChangeConsumer) {
|
||||
this.watchedEntry = watchedEntry;
|
||||
listenerID = watchedEntry.addListener(dataChangeConsumer, EntryListenerFlags.kUpdate);
|
||||
}
|
||||
|
||||
public void remove() {
|
||||
watchedEntry.removeListener(listenerID);
|
||||
}
|
||||
}
|
||||
@@ -1,204 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.networktables;
|
||||
|
||||
import edu.wpi.first.networktables.EntryNotification;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.Consumer;
|
||||
import java.util.function.Supplier;
|
||||
import org.photonvision.common.dataflow.CVPipelineResultConsumer;
|
||||
import org.photonvision.common.dataflow.structures.Packet;
|
||||
import org.photonvision.vision.pipeline.result.CVPipelineResult;
|
||||
import org.photonvision.vision.pipeline.result.SimplePipelineResult;
|
||||
|
||||
public class NTDataPublisher implements CVPipelineResultConsumer {
|
||||
|
||||
private final NetworkTable rootTable = NetworkTablesManager.getInstance().kRootTable;
|
||||
private NetworkTable subTable;
|
||||
private NetworkTableEntry rawBytesEntry;
|
||||
|
||||
private NetworkTableEntry pipelineIndexEntry;
|
||||
private final Consumer<Integer> pipelineIndexConsumer;
|
||||
private NTDataChangeListener pipelineIndexListener;
|
||||
private NetworkTableEntry driverModeEntry;
|
||||
private final Consumer<Boolean> driverModeConsumer;
|
||||
private NTDataChangeListener driverModeListener;
|
||||
|
||||
private NetworkTableEntry latencyMillisEntry;
|
||||
private NetworkTableEntry hasTargetEntry;
|
||||
private NetworkTableEntry targetPitchEntry;
|
||||
private NetworkTableEntry targetYawEntry;
|
||||
private NetworkTableEntry targetAreaEntry;
|
||||
private NetworkTableEntry targetPoseEntry;
|
||||
private NetworkTableEntry targetSkewEntry;
|
||||
|
||||
// The raw position of the best target, in pixels.
|
||||
private NetworkTableEntry bestTargetPosX;
|
||||
private NetworkTableEntry bestTargetPosY;
|
||||
|
||||
private final Supplier<Integer> pipelineIndexSupplier;
|
||||
private final BooleanSupplier driverModeSupplier;
|
||||
|
||||
public NTDataPublisher(
|
||||
String cameraNickname,
|
||||
Supplier<Integer> pipelineIndexSupplier,
|
||||
Consumer<Integer> pipelineIndexConsumer,
|
||||
BooleanSupplier driverModeSupplier,
|
||||
Consumer<Boolean> driverModeConsumer) {
|
||||
this.pipelineIndexSupplier = pipelineIndexSupplier;
|
||||
this.pipelineIndexConsumer = pipelineIndexConsumer;
|
||||
this.driverModeSupplier = driverModeSupplier;
|
||||
this.driverModeConsumer = driverModeConsumer;
|
||||
|
||||
updateCameraNickname(cameraNickname);
|
||||
updateEntries();
|
||||
}
|
||||
|
||||
private void onPipelineIndexChange(EntryNotification entryNotification) {
|
||||
var newIndex = (int) entryNotification.value.getDouble();
|
||||
var originalIndex = pipelineIndexSupplier.get();
|
||||
|
||||
// ignore indexes below 0
|
||||
if (newIndex < 0) {
|
||||
pipelineIndexEntry.forceSetNumber(originalIndex);
|
||||
return;
|
||||
}
|
||||
|
||||
if (newIndex == originalIndex) {
|
||||
// TODO: Log
|
||||
return;
|
||||
}
|
||||
|
||||
pipelineIndexConsumer.accept(newIndex);
|
||||
var setIndex = pipelineIndexSupplier.get();
|
||||
if (newIndex != setIndex) { // set failed
|
||||
pipelineIndexEntry.forceSetNumber(setIndex);
|
||||
// TODO: Log
|
||||
}
|
||||
// TODO: Log
|
||||
}
|
||||
|
||||
private void onDriverModeChange(EntryNotification entryNotification) {
|
||||
var newDriverMode = entryNotification.value.getBoolean();
|
||||
var originalDriverMode = driverModeSupplier.getAsBoolean();
|
||||
|
||||
if (newDriverMode == originalDriverMode) {
|
||||
// TODO: Log
|
||||
return;
|
||||
}
|
||||
|
||||
driverModeConsumer.accept(newDriverMode);
|
||||
// TODO: Log
|
||||
}
|
||||
|
||||
@SuppressWarnings("DuplicatedCode")
|
||||
private void removeEntries() {
|
||||
if (rawBytesEntry != null) rawBytesEntry.delete();
|
||||
if (pipelineIndexListener != null) pipelineIndexListener.remove();
|
||||
if (pipelineIndexEntry != null) pipelineIndexEntry.delete();
|
||||
if (driverModeListener != null) driverModeListener.remove();
|
||||
if (driverModeEntry != null) driverModeEntry.delete();
|
||||
if (latencyMillisEntry != null) latencyMillisEntry.delete();
|
||||
if (hasTargetEntry != null) hasTargetEntry.delete();
|
||||
if (targetPitchEntry != null) targetPitchEntry.delete();
|
||||
if (targetAreaEntry != null) targetAreaEntry.delete();
|
||||
if (targetYawEntry != null) targetYawEntry.delete();
|
||||
if (targetPoseEntry != null) targetPoseEntry.delete();
|
||||
if (targetSkewEntry != null) targetSkewEntry.delete();
|
||||
if (bestTargetPosX != null) bestTargetPosX.delete();
|
||||
if (bestTargetPosY != null) bestTargetPosY.delete();
|
||||
}
|
||||
|
||||
private void updateEntries() {
|
||||
rawBytesEntry = subTable.getEntry("rawBytes");
|
||||
|
||||
if (pipelineIndexListener != null) {
|
||||
pipelineIndexListener.remove();
|
||||
}
|
||||
pipelineIndexEntry = subTable.getEntry("pipelineIndex");
|
||||
pipelineIndexListener =
|
||||
new NTDataChangeListener(pipelineIndexEntry, this::onPipelineIndexChange);
|
||||
|
||||
if (driverModeListener != null) {
|
||||
driverModeListener.remove();
|
||||
}
|
||||
driverModeEntry = subTable.getEntry("driverMode");
|
||||
driverModeListener = new NTDataChangeListener(driverModeEntry, this::onDriverModeChange);
|
||||
|
||||
latencyMillisEntry = subTable.getEntry("latencyMillis");
|
||||
hasTargetEntry = subTable.getEntry("hasTarget");
|
||||
|
||||
targetPitchEntry = subTable.getEntry("targetPitch");
|
||||
targetAreaEntry = subTable.getEntry("targetArea");
|
||||
targetYawEntry = subTable.getEntry("targetYaw");
|
||||
targetPoseEntry = subTable.getEntry("targetPose");
|
||||
targetSkewEntry = subTable.getEntry("targetSkew");
|
||||
|
||||
bestTargetPosX = subTable.getEntry("targetPixelsX");
|
||||
bestTargetPosY = subTable.getEntry("targetPixelsY");
|
||||
}
|
||||
|
||||
public void updateCameraNickname(String newCameraNickname) {
|
||||
removeEntries();
|
||||
subTable = rootTable.getSubTable(newCameraNickname);
|
||||
updateEntries();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void accept(CVPipelineResult result) {
|
||||
var simplified = new SimplePipelineResult(result);
|
||||
Packet packet = new Packet(simplified.getPacketSize());
|
||||
simplified.populatePacket(packet);
|
||||
|
||||
rawBytesEntry.forceSetRaw(packet.getData());
|
||||
|
||||
pipelineIndexEntry.forceSetNumber(pipelineIndexSupplier.get());
|
||||
driverModeEntry.forceSetBoolean(driverModeSupplier.getAsBoolean());
|
||||
latencyMillisEntry.forceSetDouble(result.getLatencyMillis());
|
||||
hasTargetEntry.forceSetBoolean(result.hasTargets());
|
||||
|
||||
if (result.hasTargets()) {
|
||||
var bestTarget = result.targets.get(0);
|
||||
|
||||
targetPitchEntry.forceSetDouble(bestTarget.getPitch());
|
||||
targetYawEntry.forceSetDouble(bestTarget.getYaw());
|
||||
targetAreaEntry.forceSetDouble(bestTarget.getArea());
|
||||
targetSkewEntry.forceSetDouble(bestTarget.getSkew());
|
||||
|
||||
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});
|
||||
|
||||
var targetOffsetPoint = bestTarget.getTargetOffsetPoint();
|
||||
bestTargetPosX.forceSetDouble(targetOffsetPoint.x);
|
||||
bestTargetPosY.forceSetDouble(targetOffsetPoint.y);
|
||||
} else {
|
||||
targetPitchEntry.forceSetDouble(0);
|
||||
targetYawEntry.forceSetDouble(0);
|
||||
targetAreaEntry.forceSetDouble(0);
|
||||
targetSkewEntry.forceSetDouble(0);
|
||||
targetPoseEntry.forceSetDoubleArray(new double[] {0, 0, 0});
|
||||
bestTargetPosX.forceSetDouble(0);
|
||||
bestTargetPosY.forceSetDouble(0);
|
||||
}
|
||||
rootTable.getInstance().flush();
|
||||
}
|
||||
}
|
||||
@@ -1,95 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.networktables;
|
||||
|
||||
import edu.wpi.first.networktables.LogMessage;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import java.util.function.Consumer;
|
||||
import org.photonvision.common.configuration.NetworkConfig;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.scripting.ScriptEventType;
|
||||
import org.photonvision.common.scripting.ScriptManager;
|
||||
|
||||
public class NetworkTablesManager {
|
||||
|
||||
private final NetworkTableInstance ntInstance = NetworkTableInstance.getDefault();
|
||||
private final String kRootTableName = "/photonvision";
|
||||
public final NetworkTable kRootTable = ntInstance.getTable(kRootTableName);
|
||||
|
||||
private NetworkTablesManager() {
|
||||
ntInstance.addLogger(new NTLogger(), 0, 255); // to hide error messages
|
||||
}
|
||||
|
||||
private static NetworkTablesManager INSTANCE;
|
||||
|
||||
public static NetworkTablesManager getInstance() {
|
||||
if (INSTANCE == null) INSTANCE = new NetworkTablesManager();
|
||||
return INSTANCE;
|
||||
}
|
||||
|
||||
private static final Logger logger = new Logger(NetworkTablesManager.class, LogGroup.General);
|
||||
|
||||
private static class NTLogger implements Consumer<LogMessage> {
|
||||
|
||||
private boolean hasReportedConnectionFailure = false;
|
||||
private long lastConnectMessageMillis = 0;
|
||||
|
||||
@Override
|
||||
public void accept(LogMessage logMessage) {
|
||||
if (!hasReportedConnectionFailure && logMessage.message.contains("timed out")) {
|
||||
logger.error("NT Connection has failed! Will retry in background.");
|
||||
hasReportedConnectionFailure = true;
|
||||
} else if (logMessage.message.contains("connected")
|
||||
&& System.currentTimeMillis() - lastConnectMessageMillis > 125) {
|
||||
logger.info("NT Connected!");
|
||||
hasReportedConnectionFailure = false;
|
||||
lastConnectMessageMillis = System.currentTimeMillis();
|
||||
ScriptManager.queueEvent(ScriptEventType.kNTConnected);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public void setConfig(NetworkConfig config) {
|
||||
if (config.runNTServer) {
|
||||
setServerMode();
|
||||
} else {
|
||||
setClientMode(config.teamNumber);
|
||||
}
|
||||
}
|
||||
|
||||
private void setClientMode(int teamNumber) {
|
||||
logger.info("Starting NT Client");
|
||||
ntInstance.stopServer();
|
||||
|
||||
ntInstance.startClientTeam(teamNumber);
|
||||
if (ntInstance.isConnected()) {
|
||||
logger.info("[NetworkTablesManager] Connected to the robot!");
|
||||
} else {
|
||||
logger.error(
|
||||
"[NetworkTablesManager] Could not connect to the robot! Will retry in the background...");
|
||||
}
|
||||
}
|
||||
|
||||
private void setServerMode() {
|
||||
logger.info("Starting NT Server");
|
||||
ntInstance.stopClient();
|
||||
ntInstance.startServer();
|
||||
}
|
||||
}
|
||||
@@ -1,165 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.structures;
|
||||
|
||||
/** A packet that holds byte-packed data to be sent over NetworkTables. */
|
||||
public class Packet {
|
||||
// Size of the packet.
|
||||
int size;
|
||||
// Data stored in the packet.
|
||||
byte[] packetData;
|
||||
// Read and write positions.
|
||||
int readPos, writePos;
|
||||
|
||||
/** Constructs an empty packet. */
|
||||
public Packet(int size) {
|
||||
this.size = size;
|
||||
packetData = new byte[size];
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructs a packet with the given data.
|
||||
*
|
||||
* @param data The packet data.
|
||||
*/
|
||||
public Packet(byte[] data) {
|
||||
packetData = data;
|
||||
size = packetData.length;
|
||||
}
|
||||
|
||||
/** Clears the packet and resets the read and write positions. */
|
||||
public void clear() {
|
||||
packetData = new byte[size];
|
||||
readPos = 0;
|
||||
writePos = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the packet data.
|
||||
*
|
||||
* @return The packet data.
|
||||
*/
|
||||
public byte[] getData() {
|
||||
return packetData;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the packet data.
|
||||
*
|
||||
* @param data The packet data.
|
||||
*/
|
||||
public void setData(byte[] data) {
|
||||
packetData = data;
|
||||
size = data.length;
|
||||
}
|
||||
|
||||
/**
|
||||
* Encodes the byte into the packet.
|
||||
*
|
||||
* @param src The byte to encode.
|
||||
*/
|
||||
public void encode(byte src) {
|
||||
packetData[writePos++] = src;
|
||||
}
|
||||
|
||||
/**
|
||||
* Encodes the integer into the packet.
|
||||
*
|
||||
* @param src The integer to encode.
|
||||
*/
|
||||
public void encode(int src) {
|
||||
packetData[writePos++] = (byte) (src >>> 24);
|
||||
packetData[writePos++] = (byte) (src >>> 16);
|
||||
packetData[writePos++] = (byte) (src >>> 8);
|
||||
packetData[writePos++] = (byte) src;
|
||||
}
|
||||
|
||||
/**
|
||||
* Encodes the double into the packet.
|
||||
*
|
||||
* @param src The double to encode.
|
||||
*/
|
||||
public void encode(double src) {
|
||||
long data = Double.doubleToRawLongBits(src);
|
||||
packetData[writePos++] = (byte) ((data >> 56) & 0xff);
|
||||
packetData[writePos++] = (byte) ((data >> 48) & 0xff);
|
||||
packetData[writePos++] = (byte) ((data >> 40) & 0xff);
|
||||
packetData[writePos++] = (byte) ((data >> 32) & 0xff);
|
||||
packetData[writePos++] = (byte) ((data >> 24) & 0xff);
|
||||
packetData[writePos++] = (byte) ((data >> 16) & 0xff);
|
||||
packetData[writePos++] = (byte) ((data >> 8) & 0xff);
|
||||
packetData[writePos++] = (byte) (data & 0xff);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encodes the boolean into the packet.
|
||||
*
|
||||
* @param src The boolean to encode.
|
||||
*/
|
||||
public void encode(boolean src) {
|
||||
packetData[writePos++] = src ? (byte) 1 : (byte) 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a decoded byte from the packet.
|
||||
*
|
||||
* @return A decoded byte from the packet.
|
||||
*/
|
||||
public byte decodeByte() {
|
||||
return packetData[readPos++];
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a decoded int from the packet.
|
||||
*
|
||||
* @return A decoded int from the packet.
|
||||
*/
|
||||
public int decodeInt() {
|
||||
return (0xff & packetData[readPos++]) << 24
|
||||
| (0xff & packetData[readPos++]) << 16
|
||||
| (0xff & packetData[readPos++]) << 8
|
||||
| (0xff & packetData[readPos++]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a decoded double from the packet.
|
||||
*
|
||||
* @return A decoded double from the packet.
|
||||
*/
|
||||
public double decodeDouble() {
|
||||
long data =
|
||||
(long) (0xff & packetData[readPos++]) << 56
|
||||
| (long) (0xff & packetData[readPos++]) << 48
|
||||
| (long) (0xff & packetData[readPos++]) << 40
|
||||
| (long) (0xff & packetData[readPos++]) << 32
|
||||
| (long) (0xff & packetData[readPos++]) << 24
|
||||
| (long) (0xff & packetData[readPos++]) << 16
|
||||
| (long) (0xff & packetData[readPos++]) << 8
|
||||
| (long) (0xff & packetData[readPos++]);
|
||||
return Double.longBitsToDouble(data);
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a decoded boolean from the packet.
|
||||
*
|
||||
* @return A decoded boolean from the packet.
|
||||
*/
|
||||
public boolean decodeBoolean() {
|
||||
return packetData[readPos++] == 1;
|
||||
}
|
||||
}
|
||||
@@ -1,74 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.dataflow.websocket;
|
||||
|
||||
import com.fasterxml.jackson.core.JsonProcessingException;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.dataflow.CVPipelineResultConsumer;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.server.SocketHandler;
|
||||
import org.photonvision.vision.pipeline.result.CVPipelineResult;
|
||||
|
||||
public class UIDataPublisher implements CVPipelineResultConsumer {
|
||||
private static final Logger logger = new Logger(UIDataPublisher.class, LogGroup.VisionModule);
|
||||
|
||||
private final int index;
|
||||
private long lastUIResultUpdateTime = 0;
|
||||
|
||||
public UIDataPublisher(int index) {
|
||||
this.index = index;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void accept(CVPipelineResult result) {
|
||||
var now = System.currentTimeMillis();
|
||||
|
||||
// only update the UI at 15hz
|
||||
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", result.fps);
|
||||
dataMap.put("latency", result.getLatencyMillis());
|
||||
|
||||
var targets = result.targets;
|
||||
|
||||
var uiTargets = new ArrayList<HashMap<String, Object>>();
|
||||
for (var t : targets) {
|
||||
uiTargets.add(t.toHashMap());
|
||||
}
|
||||
dataMap.put("targets", uiTargets);
|
||||
|
||||
uiMap.put(index, dataMap);
|
||||
var retMap = new HashMap<String, Object>();
|
||||
retMap.put("updatePipelineResult", uiMap);
|
||||
|
||||
try {
|
||||
SocketHandler.getInstance().broadcastMessage(retMap, null);
|
||||
} catch (JsonProcessingException e) {
|
||||
logger.error(e.getMessage());
|
||||
logger.error(Arrays.toString(e.getStackTrace()));
|
||||
}
|
||||
|
||||
lastUIResultUpdateTime = now;
|
||||
}
|
||||
}
|
||||
@@ -1,100 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO;
|
||||
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
|
||||
public class CustomGPIO extends GPIOBase {
|
||||
|
||||
private boolean currentState;
|
||||
private final int port;
|
||||
|
||||
public CustomGPIO(int port) {
|
||||
this.port = port;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void togglePin() {
|
||||
if (this.port != -1) {
|
||||
execute(
|
||||
commands
|
||||
.get("setState")
|
||||
.replace("{s}", String.valueOf(!currentState))
|
||||
.replace("{p}", String.valueOf(this.port)));
|
||||
currentState = !currentState;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getPinNumber() {
|
||||
return port;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setStateImpl(boolean state) {
|
||||
if (this.port != -1) {
|
||||
execute(
|
||||
commands
|
||||
.get("setState")
|
||||
.replace("{s}", String.valueOf(state))
|
||||
.replace("{p}", String.valueOf(port)));
|
||||
currentState = state;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean shutdown() {
|
||||
if (this.port != -1) {
|
||||
execute(commands.get("shutdown"));
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getStateImpl() {
|
||||
return currentState;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void blinkImpl(int pulseTimeMillis, int blinks) {
|
||||
execute(
|
||||
commands
|
||||
.get("blink")
|
||||
.replace("{pulseTime}", String.valueOf(pulseTimeMillis))
|
||||
.replace("{blinks}", String.valueOf(blinks))
|
||||
.replace("{p}", String.valueOf(this.port)));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setBrightnessImpl(int brightness) {
|
||||
execute(
|
||||
commands
|
||||
.get("dim")
|
||||
.replace("{p}", String.valueOf(port))
|
||||
.replace("{v}", String.valueOf(brightness)));
|
||||
}
|
||||
|
||||
public static void setConfig(HardwareConfig config) {
|
||||
if (Platform.isRaspberryPi()) return;
|
||||
commands.replace("setState", config.ledSetCommand);
|
||||
commands.replace("dim", config.ledDimCommand);
|
||||
commands.replace("blink", config.ledBlinkCommand);
|
||||
}
|
||||
}
|
||||
@@ -1,99 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO;
|
||||
|
||||
import java.util.Arrays;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
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);
|
||||
|
||||
protected static HashMap<String, String> commands =
|
||||
new HashMap<>() {
|
||||
{
|
||||
put("setState", "");
|
||||
put("shutdown", "");
|
||||
put("dim", "");
|
||||
put("blink", "");
|
||||
}
|
||||
};
|
||||
|
||||
protected static String execute(String command) {
|
||||
try {
|
||||
runCommand.executeBashCommand(command);
|
||||
} catch (Exception e) {
|
||||
logger.error(Arrays.toString(e.getStackTrace()));
|
||||
return "";
|
||||
}
|
||||
return runCommand.getOutput();
|
||||
}
|
||||
|
||||
public abstract int getPinNumber();
|
||||
|
||||
public void setState(boolean state) {
|
||||
if (getPinNumber() != -1) {
|
||||
setStateImpl(state);
|
||||
}
|
||||
}
|
||||
|
||||
protected abstract void setStateImpl(boolean state);
|
||||
|
||||
public final void setOff() {
|
||||
setState(false);
|
||||
}
|
||||
|
||||
public final void setOn() {
|
||||
setState(true);
|
||||
}
|
||||
|
||||
public void togglePin() {
|
||||
setState(!getStateImpl());
|
||||
}
|
||||
|
||||
public abstract boolean shutdown();
|
||||
|
||||
public final boolean getState() {
|
||||
if (getPinNumber() != -1) {
|
||||
return getStateImpl();
|
||||
} else return false;
|
||||
}
|
||||
|
||||
public abstract boolean getStateImpl();
|
||||
|
||||
public final void blink(int pulseTimeMillis, int blinks) {
|
||||
if (getPinNumber() != -1) {
|
||||
blinkImpl(pulseTimeMillis, blinks);
|
||||
}
|
||||
}
|
||||
|
||||
protected abstract void blinkImpl(int pulseTimeMillis, int blinks);
|
||||
|
||||
public final void setBrightness(int brightness) {
|
||||
if (getPinNumber() != -1) {
|
||||
if (brightness > 100) brightness = 100;
|
||||
if (brightness < 0) brightness = 0;
|
||||
setBrightnessImpl(brightness);
|
||||
}
|
||||
}
|
||||
|
||||
protected abstract void setBrightnessImpl(int brightness);
|
||||
}
|
||||
@@ -1,40 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
@SuppressWarnings("SpellCheckingInspection")
|
||||
public enum PigpioCommand {
|
||||
PCMD_READ(3), // int gpio_read(unsigned gpio)
|
||||
PCMD_WRITE(4), // int gpio_write(unsigned gpio, unsigned level)
|
||||
PCMD_WVCLR(27), // int wave_clear(void)
|
||||
PCMD_WVAG(28), // int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses)
|
||||
PCMD_WVHLT(33), // int wave_tx_stop(void)
|
||||
PCMD_WVCRE(49), // int wave_create(void)
|
||||
PCMD_WVDEL(50), // int wave_delete(unsigned wave_id)
|
||||
PCMD_WVTX(51), // int wave_tx_send(unsigned wave_id) (once)
|
||||
PCMD_WVTXR(52), // int wave_tx_send(unsigned wave_id) (repeat)
|
||||
PCMD_GDC(83), // int get_duty_cyle(unsigned user_gpio)
|
||||
PCMD_HP(86), // int hardware_pwm(unsigned gpio, unsigned PWMfreq, unsigned PWMduty)
|
||||
PCMD_WVTXM(100); // int wave_tx_send(unsigned wave_id, unsigned wave_mode)
|
||||
|
||||
public final int value;
|
||||
|
||||
PigpioCommand(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
@@ -1,344 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import java.util.HashMap;
|
||||
|
||||
/**
|
||||
* A class that defines the exceptions that can be thrown by Pigpio.
|
||||
*
|
||||
* <p>Credit to nkolban
|
||||
* https://github.com/nkolban/jpigpio/blob/master/JPigpio/src/jpigpio/PigpioException.java
|
||||
*/
|
||||
@SuppressWarnings({"SpellCheckingInspection", "unused", "RedundantSuppression"})
|
||||
public class PigpioException extends Exception {
|
||||
|
||||
private int rc = -99999999;
|
||||
private static final long serialVersionUID = 443595760654129068L;
|
||||
|
||||
public PigpioException() {
|
||||
super();
|
||||
}
|
||||
|
||||
public PigpioException(int rc) {
|
||||
super();
|
||||
this.rc = rc;
|
||||
}
|
||||
|
||||
public PigpioException(int rc, String msg) {
|
||||
super(msg);
|
||||
this.rc = rc;
|
||||
}
|
||||
|
||||
public PigpioException(String arg0, Throwable arg1, boolean arg2, boolean arg3) {
|
||||
super(arg0, arg1, arg2, arg3);
|
||||
}
|
||||
|
||||
public PigpioException(String arg0, Throwable arg1) {
|
||||
super(arg0, arg1);
|
||||
}
|
||||
|
||||
public PigpioException(String arg0) {
|
||||
super(arg0);
|
||||
}
|
||||
|
||||
public PigpioException(Throwable arg0) {
|
||||
super(arg0);
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getMessage() {
|
||||
return "(" + rc + ") " + getMessageForError(rc);
|
||||
}
|
||||
|
||||
/**
|
||||
* Retrieve the error code that was returned by the underlying Pigpio call.
|
||||
*
|
||||
* @return The error code that was returned by the underlying Pigpio call.
|
||||
*/
|
||||
public int getErrorCode() {
|
||||
return rc;
|
||||
} // End of getErrorCode
|
||||
|
||||
// Public constants for the error codes that can be thrown by Pigpio
|
||||
public static final int PI_INIT_FAILED = -1; // gpioInitialise failed
|
||||
public static final int PI_BAD_USER_GPIO = -2; // gpio not 0-31
|
||||
public static final int PI_BAD_GPIO = -3; // gpio not 0-53
|
||||
public static final int PI_BAD_MODE = -4; // mode not 0-7
|
||||
public static final int PI_BAD_LEVEL = -5; // level not 0-1
|
||||
public static final int PI_BAD_PUD = -6; // pud not 0-2
|
||||
public static final int PI_BAD_PULSEWIDTH = -7; // pulsewidth not 0 or 500-2500
|
||||
public static final int PI_BAD_DUTYCYCLE = -8; // dutycycle outside set range
|
||||
public static final int PI_BAD_TIMER = -9; // timer not 0-9
|
||||
public static final int PI_BAD_MS = -10; // ms not 10-60000
|
||||
public static final int PI_BAD_TIMETYPE = -11; // timetype not 0-1
|
||||
public static final int PI_BAD_SECONDS = -12; // seconds < 0
|
||||
public static final int PI_BAD_MICROS = -13; // micros not 0-999999
|
||||
public static final int PI_TIMER_FAILED = -14; // gpioSetTimerFunc failed
|
||||
public static final int PI_BAD_WDOG_TIMEOUT = -15; // timeout not 0-60000
|
||||
public static final int PI_NO_ALERT_FUNC = -16; // DEPRECATED
|
||||
public static final int PI_BAD_CLK_PERIPH = -17; // clock peripheral not 0-1
|
||||
public static final int PI_BAD_CLK_SOURCE = -18; // DEPRECATED
|
||||
public static final int PI_BAD_CLK_MICROS = -19; // clock micros not 1, 2, 4, 5, 8, or 10
|
||||
public static final int PI_BAD_BUF_MILLIS = -20; // buf millis not 100-10000
|
||||
public static final int PI_BAD_DUTYRANGE = -21; // dutycycle range not 25-40000
|
||||
public static final int PI_BAD_DUTY_RANGE = -21; // DEPRECATED (use PI_BAD_DUTYRANGE)
|
||||
public static final int PI_BAD_SIGNUM = -22; // signum not 0-63
|
||||
public static final int PI_BAD_PATHNAME = -23; // can't open pathname
|
||||
public static final int PI_NO_HANDLE = -24; // no handle available
|
||||
public static final int PI_BAD_HANDLE = -25; // unknown handle
|
||||
public static final int PI_BAD_IF_FLAGS = -26; // ifFlags > 3
|
||||
public static final int PI_BAD_CHANNEL = -27; // DMA channel not 0-14
|
||||
public static final int PI_BAD_PRIM_CHANNEL = -27; // DMA primary channel not 0-14
|
||||
public static final int PI_BAD_SOCKET_PORT = -28; // socket port not 1024-32000
|
||||
public static final int PI_BAD_FIFO_COMMAND = -29; // unrecognized fifo command
|
||||
public static final int PI_BAD_SECO_CHANNEL = -30; // DMA secondary channel not 0-6
|
||||
public static final int PI_NOT_INITIALISED = -31; // function called before gpioInitialise
|
||||
public static final int PI_INITIALISED = -32; // function called after gpioInitialise
|
||||
public static final int PI_BAD_WAVE_MODE = -33; // waveform mode not 0-1
|
||||
public static final int PI_BAD_CFG_INTERNAL = -34; // bad parameter in gpioCfgInternals call
|
||||
public static final int PI_BAD_WAVE_BAUD = -35; // baud rate not 50-250K(RX)/50-1M(TX)
|
||||
public static final int PI_TOO_MANY_PULSES = -36; // waveform has too many pulses
|
||||
public static final int PI_TOO_MANY_CHARS = -37; // waveform has too many chars
|
||||
public static final int PI_NOT_SERIAL_GPIO = -38; // no serial read in progress on gpio
|
||||
public static final int PI_BAD_SERIAL_STRUC = -39; // bad (null) serial structure parameter
|
||||
public static final int PI_BAD_SERIAL_BUF = -40; // bad (null) serial buf parameter
|
||||
public static final int PI_NOT_PERMITTED = -41; // gpio operation not permitted
|
||||
public static final int PI_SOME_PERMITTED = -42; // one or more gpios not permitted
|
||||
public static final int PI_BAD_WVSC_COMMND = -43; // bad WVSC subcommand
|
||||
public static final int PI_BAD_WVSM_COMMND = -44; // bad WVSM subcommand
|
||||
public static final int PI_BAD_WVSP_COMMND = -45; // bad WVSP subcommand
|
||||
public static final int PI_BAD_PULSELEN = -46; // trigger pulse length not 1-100
|
||||
public static final int PI_BAD_SCRIPT = -47; // invalid script
|
||||
public static final int PI_BAD_SCRIPT_ID = -48; // unknown script id
|
||||
public static final int PI_BAD_SER_OFFSET = -49; // add serial data offset > 30 minutes
|
||||
public static final int PI_GPIO_IN_USE = -50; // gpio already in use
|
||||
public static final int PI_BAD_SERIAL_COUNT = -51; // must read at least a byte at a time
|
||||
public static final int PI_BAD_PARAM_NUM = -52; // script parameter id not 0-9
|
||||
public static final int PI_DUP_TAG = -53; // script has duplicate tag
|
||||
public static final int PI_TOO_MANY_TAGS = -54; // script has too many tags
|
||||
public static final int PI_BAD_SCRIPT_CMD = -55; // illegal script command
|
||||
public static final int PI_BAD_VAR_NUM = -56; // script variable id not 0-149
|
||||
public static final int PI_NO_SCRIPT_ROOM = -57; // no more room for scripts
|
||||
public static final int PI_NO_MEMORY = -58; // can't allocate temporary memory
|
||||
public static final int PI_SOCK_READ_FAILED = -59; // socket read failed
|
||||
public static final int PI_SOCK_WRIT_FAILED = -60; // socket write failed
|
||||
public static final int PI_TOO_MANY_PARAM = -61; // too many script parameters (> 10)
|
||||
public static final int PI_NOT_HALTED = -62; // script already running or failed
|
||||
public static final int PI_BAD_TAG = -63; // script has unresolved tag
|
||||
public static final int PI_BAD_MICS_DELAY = -64; // bad MICS delay (too large)
|
||||
public static final int PI_BAD_MILS_DELAY = -65; // bad MILS delay (too large)
|
||||
public static final int PI_BAD_WAVE_ID = -66; // non existent wave id
|
||||
public static final int PI_TOO_MANY_CBS = -67; // No more CBs for waveform
|
||||
public static final int PI_TOO_MANY_OOL = -68; // No more OOL for waveform
|
||||
public static final int PI_EMPTY_WAVEFORM = -69; // attempt to create an empty waveform
|
||||
public static final int PI_NO_WAVEFORM_ID = -70; // no more waveforms
|
||||
public static final int PI_I2C_OPEN_FAILED = -71; // can't open I2C device
|
||||
public static final int PI_SER_OPEN_FAILED = -72; // can't open serial device
|
||||
public static final int PI_SPI_OPEN_FAILED = -73; // can't open SPI device
|
||||
public static final int PI_BAD_I2C_BUS = -74; // bad I2C bus
|
||||
public static final int PI_BAD_I2C_ADDR = -75; // bad I2C address
|
||||
public static final int PI_BAD_SPI_CHANNEL = -76; // bad SPI channel
|
||||
public static final int PI_BAD_FLAGS = -77; // bad i2c/spi/ser open flags
|
||||
public static final int PI_BAD_SPI_SPEED = -78; // bad SPI speed
|
||||
public static final int PI_BAD_SER_DEVICE = -79; // bad serial device name
|
||||
public static final int PI_BAD_SER_SPEED = -80; // bad serial baud rate
|
||||
public static final int PI_BAD_PARAM = -81; // bad i2c/spi/ser parameter
|
||||
public static final int PI_I2C_WRITE_FAILED = -82; // i2c write failed
|
||||
public static final int PI_I2C_READ_FAILED = -83; // i2c read failed
|
||||
public static final int PI_BAD_SPI_COUNT = -84; // bad SPI count
|
||||
public static final int PI_SER_WRITE_FAILED = -85; // ser write failed
|
||||
public static final int PI_SER_READ_FAILED = -86; // ser read failed
|
||||
public static final int PI_SER_READ_NO_DATA = -87; // ser read no data available
|
||||
public static final int PI_UNKNOWN_COMMAND = -88; // unknown command
|
||||
public static final int PI_SPI_XFER_FAILED = -89; // spi xfer/read/write failed
|
||||
public static final int PI_BAD_POINTER = -90; // bad (NULL) pointer
|
||||
public static final int PI_NO_AUX_SPI = -91; // need a A+/B+/Pi2 for auxiliary SPI
|
||||
public static final int PI_NOT_PWM_GPIO = -92; // gpio is not in use for PWM
|
||||
public static final int PI_NOT_SERVO_GPIO = -93; // gpio is not in use for servo pulses
|
||||
public static final int PI_NOT_HCLK_GPIO = -94; // gpio has no hardware clock
|
||||
public static final int PI_NOT_HPWM_GPIO = -95; // gpio has no hardware PWM
|
||||
public static final int PI_BAD_HPWM_FREQ = -96; // hardware PWM frequency not 1-125M
|
||||
public static final int PI_BAD_HPWM_DUTY = -97; // hardware PWM dutycycle not 0-1M
|
||||
public static final int PI_BAD_HCLK_FREQ = -98; // hardware clock frequency not 4689-250M
|
||||
public static final int PI_BAD_HCLK_PASS = -99; // need password to use hardware clock 1
|
||||
public static final int PI_HPWM_ILLEGAL = -100; // illegal, PWM in use for main clock
|
||||
public static final int PI_BAD_DATABITS = -101; // serial data bits not 1-32
|
||||
public static final int PI_BAD_STOPBITS = -102; // serial (half) stop bits not 2-8
|
||||
public static final int PI_MSG_TOOBIG = -103; // socket/pipe message too big
|
||||
public static final int PI_BAD_MALLOC_MODE = -104; // bad memory allocation mode
|
||||
public static final int PI_TOO_MANY_SEGS = -105; // too many I2C transaction parts
|
||||
public static final int PI_BAD_I2C_SEG = -106; // a combined I2C transaction failed
|
||||
public static final int PI_BAD_SMBUS_CMD = -107;
|
||||
public static final int PI_NOT_I2C_GPIO = -108;
|
||||
public static final int PI_BAD_I2C_WLEN = -109;
|
||||
public static final int PI_BAD_I2C_RLEN = -110;
|
||||
public static final int PI_BAD_I2C_CMD = -111;
|
||||
public static final int PI_BAD_I2C_BAUD = -112;
|
||||
public static final int PI_CHAIN_LOOP_CNT = -113;
|
||||
public static final int PI_BAD_CHAIN_LOOP = -114;
|
||||
public static final int PI_CHAIN_COUNTER = -115;
|
||||
public static final int PI_BAD_CHAIN_CMD = -116;
|
||||
public static final int PI_BAD_CHAIN_DELAY = -117;
|
||||
public static final int PI_CHAIN_NESTING = -118;
|
||||
public static final int PI_CHAIN_TOO_BIG = -119;
|
||||
public static final int PI_DEPRECATED = -120;
|
||||
public static final int PI_BAD_SER_INVERT = -121;
|
||||
public static final int PI_BAD_EDGE = -122;
|
||||
public static final int PI_BAD_ISR_INIT = -123;
|
||||
public static final int PI_BAD_FOREVER = -124;
|
||||
public static final int PI_BAD_FILTER = -125;
|
||||
|
||||
public static final int PI_PIGIF_ERR_0 = -2000;
|
||||
public static final int PI_PIGIF_ERR_99 = -2099;
|
||||
|
||||
public static final int PI_CUSTOM_ERR_0 = -3000;
|
||||
public static final int PI_CUSTOM_ERR_999 = -3999;
|
||||
|
||||
private static final HashMap<Integer, String> errorMessages = new HashMap<>();
|
||||
|
||||
static {
|
||||
errorMessages.put(PI_INIT_FAILED, "pigpio initialisation failed");
|
||||
errorMessages.put(PI_BAD_USER_GPIO, "GPIO not 0-31");
|
||||
errorMessages.put(PI_BAD_GPIO, "GPIO not 0-53");
|
||||
errorMessages.put(PI_BAD_MODE, "mode not 0-7");
|
||||
errorMessages.put(PI_BAD_LEVEL, "level not 0-1");
|
||||
errorMessages.put(PI_BAD_PUD, "pud not 0-2");
|
||||
errorMessages.put(PI_BAD_PULSEWIDTH, "pulsewidth not 0 or 500-2500");
|
||||
errorMessages.put(PI_BAD_DUTYCYCLE, "dutycycle not 0-range (default 255)");
|
||||
errorMessages.put(PI_BAD_TIMER, "timer not 0-9");
|
||||
errorMessages.put(PI_BAD_MS, "ms not 10-60000");
|
||||
errorMessages.put(PI_BAD_TIMETYPE, "timetype not 0-1");
|
||||
errorMessages.put(PI_BAD_SECONDS, "seconds < 0");
|
||||
errorMessages.put(PI_BAD_MICROS, "micros not 0-999999");
|
||||
errorMessages.put(PI_TIMER_FAILED, "gpioSetTimerFunc failed");
|
||||
errorMessages.put(PI_BAD_WDOG_TIMEOUT, "timeout not 0-60000");
|
||||
errorMessages.put(PI_NO_ALERT_FUNC, "DEPRECATED");
|
||||
errorMessages.put(PI_BAD_CLK_PERIPH, "clock peripheral not 0-1");
|
||||
errorMessages.put(PI_BAD_CLK_SOURCE, "DEPRECATED");
|
||||
errorMessages.put(PI_BAD_CLK_MICROS, "clock micros not 1, 2, 4, 5, 8, or 10");
|
||||
errorMessages.put(PI_BAD_BUF_MILLIS, "buf millis not 100-10000");
|
||||
errorMessages.put(PI_BAD_DUTYRANGE, "dutycycle range not 25-40000");
|
||||
errorMessages.put(PI_BAD_SIGNUM, "signum not 0-63");
|
||||
errorMessages.put(PI_BAD_PATHNAME, "can't open pathname");
|
||||
errorMessages.put(PI_NO_HANDLE, "no handle available");
|
||||
errorMessages.put(PI_BAD_HANDLE, "unknown handle");
|
||||
errorMessages.put(PI_BAD_IF_FLAGS, "ifFlags > 3");
|
||||
errorMessages.put(PI_BAD_CHANNEL, "DMA channel not 0-14");
|
||||
errorMessages.put(PI_BAD_SOCKET_PORT, "socket port not 1024-30000");
|
||||
errorMessages.put(PI_BAD_FIFO_COMMAND, "unknown fifo command");
|
||||
errorMessages.put(PI_BAD_SECO_CHANNEL, "DMA secondary channel not 0-14");
|
||||
errorMessages.put(PI_NOT_INITIALISED, "function called before gpioInitialise");
|
||||
errorMessages.put(PI_INITIALISED, "function called after gpioInitialise");
|
||||
errorMessages.put(PI_BAD_WAVE_MODE, "waveform mode not 0-1");
|
||||
errorMessages.put(PI_BAD_CFG_INTERNAL, "bad parameter in gpioCfgInternals call");
|
||||
errorMessages.put(PI_BAD_WAVE_BAUD, "baud rate not 50-250000(RX)/1000000(TX)");
|
||||
errorMessages.put(PI_TOO_MANY_PULSES, "waveform has too many pulses");
|
||||
errorMessages.put(PI_TOO_MANY_CHARS, "waveform has too many chars");
|
||||
errorMessages.put(PI_NOT_SERIAL_GPIO, "no bit bang serial read in progress on GPIO");
|
||||
errorMessages.put(PI_NOT_PERMITTED, "no permission to update GPIO");
|
||||
errorMessages.put(PI_SOME_PERMITTED, "no permission to update one or more GPIO");
|
||||
errorMessages.put(PI_BAD_WVSC_COMMND, "bad WVSC subcommand");
|
||||
errorMessages.put(PI_BAD_WVSM_COMMND, "bad WVSM subcommand");
|
||||
errorMessages.put(PI_BAD_WVSP_COMMND, "bad WVSP subcommand");
|
||||
errorMessages.put(PI_BAD_PULSELEN, "trigger pulse length not 1-100");
|
||||
errorMessages.put(PI_BAD_SCRIPT, "invalid script");
|
||||
errorMessages.put(PI_BAD_SCRIPT_ID, "unknown script id");
|
||||
errorMessages.put(PI_BAD_SER_OFFSET, "add serial data offset > 30 minute");
|
||||
errorMessages.put(PI_GPIO_IN_USE, "GPIO already in use");
|
||||
errorMessages.put(PI_BAD_SERIAL_COUNT, "must read at least a byte at a time");
|
||||
errorMessages.put(PI_BAD_PARAM_NUM, "script parameter id not 0-9");
|
||||
errorMessages.put(PI_DUP_TAG, "script has duplicate tag");
|
||||
errorMessages.put(PI_TOO_MANY_TAGS, "script has too many tags");
|
||||
errorMessages.put(PI_BAD_SCRIPT_CMD, "illegal script command");
|
||||
errorMessages.put(PI_BAD_VAR_NUM, "script variable id not 0-149");
|
||||
errorMessages.put(PI_NO_SCRIPT_ROOM, "no more room for scripts");
|
||||
errorMessages.put(PI_NO_MEMORY, "can't allocate temporary memory");
|
||||
errorMessages.put(PI_SOCK_READ_FAILED, "socket read failed");
|
||||
errorMessages.put(PI_SOCK_WRIT_FAILED, "socket write failed");
|
||||
errorMessages.put(PI_TOO_MANY_PARAM, "too many script parameters (> 10)");
|
||||
errorMessages.put(PI_NOT_HALTED, "script already running or failed");
|
||||
errorMessages.put(PI_BAD_TAG, "script has unresolved tag");
|
||||
errorMessages.put(PI_BAD_MICS_DELAY, "bad MICS delay (too large)");
|
||||
errorMessages.put(PI_BAD_MILS_DELAY, "bad MILS delay (too large)");
|
||||
errorMessages.put(PI_BAD_WAVE_ID, "non existent wave id");
|
||||
errorMessages.put(PI_TOO_MANY_CBS, "No more CBs for waveform");
|
||||
errorMessages.put(PI_TOO_MANY_OOL, "No more OOL for waveform");
|
||||
errorMessages.put(PI_EMPTY_WAVEFORM, "attempt to create an empty waveform");
|
||||
errorMessages.put(PI_NO_WAVEFORM_ID, "No more waveform ids");
|
||||
errorMessages.put(PI_I2C_OPEN_FAILED, "can't open I2C device");
|
||||
errorMessages.put(PI_SER_OPEN_FAILED, "can't open serial device");
|
||||
errorMessages.put(PI_SPI_OPEN_FAILED, "can't open SPI device");
|
||||
errorMessages.put(PI_BAD_I2C_BUS, "bad I2C bus");
|
||||
errorMessages.put(PI_BAD_I2C_ADDR, "bad I2C address");
|
||||
errorMessages.put(PI_BAD_SPI_CHANNEL, "bad SPI channel");
|
||||
errorMessages.put(PI_BAD_FLAGS, "bad i2c/spi/ser open flags");
|
||||
errorMessages.put(PI_BAD_SPI_SPEED, "bad SPI speed");
|
||||
errorMessages.put(PI_BAD_SER_DEVICE, "bad serial device name");
|
||||
errorMessages.put(PI_BAD_SER_SPEED, "bad serial baud rate");
|
||||
errorMessages.put(PI_BAD_PARAM, "bad i2c/spi/ser parameter");
|
||||
errorMessages.put(PI_I2C_WRITE_FAILED, "I2C write failed");
|
||||
errorMessages.put(PI_I2C_READ_FAILED, "I2C read failed");
|
||||
errorMessages.put(PI_BAD_SPI_COUNT, "bad SPI count");
|
||||
errorMessages.put(PI_SER_WRITE_FAILED, "ser write failed");
|
||||
errorMessages.put(PI_SER_READ_FAILED, "ser read failed");
|
||||
errorMessages.put(PI_SER_READ_NO_DATA, "ser read no data available");
|
||||
errorMessages.put(PI_UNKNOWN_COMMAND, "unknown command");
|
||||
errorMessages.put(PI_SPI_XFER_FAILED, "SPI xfer/read/write failed");
|
||||
errorMessages.put(PI_BAD_POINTER, "bad (NULL) pointer");
|
||||
errorMessages.put(PI_NO_AUX_SPI, "no auxiliary SPI on Pi A or B");
|
||||
errorMessages.put(PI_NOT_PWM_GPIO, "GPIO is not in use for PWM");
|
||||
errorMessages.put(PI_NOT_SERVO_GPIO, "GPIO is not in use for servo pulses");
|
||||
errorMessages.put(PI_NOT_HCLK_GPIO, "GPIO has no hardware clock");
|
||||
errorMessages.put(PI_NOT_HPWM_GPIO, "GPIO has no hardware PWM");
|
||||
errorMessages.put(PI_BAD_HPWM_FREQ, "hardware PWM frequency not 1-125M");
|
||||
errorMessages.put(PI_BAD_HPWM_DUTY, "hardware PWM dutycycle not 0-1M");
|
||||
errorMessages.put(PI_BAD_HCLK_FREQ, "hardware clock frequency not 4689-250M");
|
||||
errorMessages.put(PI_BAD_HCLK_PASS, "need password to use hardware clock 1");
|
||||
errorMessages.put(PI_HPWM_ILLEGAL, "illegal, PWM in use for main clock");
|
||||
errorMessages.put(PI_BAD_DATABITS, "serial data bits not 1-32");
|
||||
errorMessages.put(PI_BAD_STOPBITS, "serial (half) stop bits not 2-8");
|
||||
errorMessages.put(PI_MSG_TOOBIG, "socket/pipe message too big");
|
||||
errorMessages.put(PI_BAD_MALLOC_MODE, "bad memory allocation mode");
|
||||
errorMessages.put(PI_TOO_MANY_SEGS, "too many I2C transaction segments");
|
||||
errorMessages.put(PI_BAD_I2C_SEG, "an I2C transaction segment failed");
|
||||
errorMessages.put(PI_BAD_SMBUS_CMD, "SMBus command not supported");
|
||||
errorMessages.put(PI_NOT_I2C_GPIO, "no bit bang I2C in progress on GPIO");
|
||||
errorMessages.put(PI_BAD_I2C_WLEN, "bad I2C write length");
|
||||
errorMessages.put(PI_BAD_I2C_RLEN, "bad I2C read length");
|
||||
errorMessages.put(PI_BAD_I2C_CMD, "bad I2C command");
|
||||
errorMessages.put(PI_BAD_I2C_BAUD, "bad I2C baud rate, not 50-500k");
|
||||
errorMessages.put(PI_CHAIN_LOOP_CNT, "bad chain loop count");
|
||||
errorMessages.put(PI_BAD_CHAIN_LOOP, "empty chain loop");
|
||||
errorMessages.put(PI_CHAIN_COUNTER, "too many chain counters");
|
||||
errorMessages.put(PI_BAD_CHAIN_CMD, "bad chain command");
|
||||
errorMessages.put(PI_BAD_CHAIN_DELAY, "bad chain delay micros");
|
||||
errorMessages.put(PI_CHAIN_NESTING, "chain counters nested too deeply");
|
||||
errorMessages.put(PI_CHAIN_TOO_BIG, "chain is too long");
|
||||
errorMessages.put(PI_DEPRECATED, "deprecated function removed");
|
||||
errorMessages.put(PI_BAD_SER_INVERT, "bit bang serial invert not 0 or 1");
|
||||
errorMessages.put(PI_BAD_EDGE, "bad ISR edge value, not 0-2");
|
||||
errorMessages.put(PI_BAD_ISR_INIT, "bad ISR initialisation");
|
||||
errorMessages.put(PI_BAD_FOREVER, "loop forever must be last chain command");
|
||||
errorMessages.put(PI_BAD_FILTER, "bad filter parameter");
|
||||
}
|
||||
|
||||
public static String getMessageForError(int errorCode) {
|
||||
return errorMessages.get(errorCode);
|
||||
}
|
||||
}
|
||||
@@ -1,96 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import static org.photonvision.common.hardware.GPIO.pi.PigpioException.*;
|
||||
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class PigpioPin extends GPIOBase {
|
||||
|
||||
public static final Logger logger = new Logger(PigpioPin.class, LogGroup.General);
|
||||
private static final PigpioSocket piSocket = new PigpioSocket();
|
||||
|
||||
private final boolean isHardwarePWMPin;
|
||||
private final int pinNo;
|
||||
|
||||
private boolean hasFailedHardwarePWM;
|
||||
|
||||
public PigpioPin(int pinNo) {
|
||||
isHardwarePWMPin = pinNo == 12 || pinNo == 13 || pinNo == 17 || pinNo == 18;
|
||||
this.pinNo = pinNo;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getPinNumber() {
|
||||
return pinNo;
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void setStateImpl(boolean state) {
|
||||
try {
|
||||
piSocket.gpioWrite(pinNo, state);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("gpioWrite FAIL - " + e.getMessage());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean shutdown() {
|
||||
setState(false);
|
||||
return true;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getStateImpl() {
|
||||
try {
|
||||
return piSocket.gpioRead(pinNo);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("gpioRead FAIL - " + e.getMessage());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void blinkImpl(int pulseTimeMillis, int blinks) {
|
||||
try {
|
||||
piSocket.generateAndSendWaveform(pulseTimeMillis, blinks, pinNo);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Could not set blink - " + e.getMessage());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void setBrightnessImpl(int brightness) {
|
||||
if (isHardwarePWMPin) {
|
||||
try {
|
||||
piSocket.hardwarePWM(pinNo, 22000, (int) (1000000 * (brightness / 100.0)));
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Failed to hardPWM - " + e.getMessage());
|
||||
}
|
||||
} else if (!hasFailedHardwarePWM) {
|
||||
logger.warn(
|
||||
"Specified pin ("
|
||||
+ pinNo
|
||||
+ ") is not capable of hardware PWM - no action will be taken.");
|
||||
hasFailedHardwarePWM = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,39 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
public class PigpioPulse {
|
||||
int gpioOn;
|
||||
int gpioOff;
|
||||
int delayMicros;
|
||||
|
||||
/**
|
||||
* Initialises a pulse.
|
||||
*
|
||||
* @param gpioOn GPIO number to switch on at the start of the pulse. If zero, then no GPIO will be
|
||||
* switched on.
|
||||
* @param gpioOff GPIO number to switch off at the start of the pulse. If zero, then no GPIO will
|
||||
* be switched off.
|
||||
* @param delayMicros the delay in microseconds before the next pulse.
|
||||
*/
|
||||
public PigpioPulse(int gpioOn, int gpioOff, int delayMicros) {
|
||||
this.gpioOn = gpioOn != 0 ? 1 << gpioOn : 0;
|
||||
this.gpioOff = gpioOff != 0 ? 1 << gpioOff : 0;
|
||||
this.delayMicros = delayMicros;
|
||||
}
|
||||
}
|
||||
@@ -1,373 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import static org.photonvision.common.hardware.GPIO.pi.PigpioException.*;
|
||||
import static org.photonvision.common.hardware.GPIO.pi.PigpioException.PI_NO_WAVEFORM_ID;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import java.util.ArrayList;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
@SuppressWarnings({"SpellCheckingInspection", "unused"})
|
||||
public class PigpioSocket {
|
||||
private static final Logger logger = new Logger(PigpioSocket.class, LogGroup.General);
|
||||
private static final int PIGPIOD_MESSAGE_SIZE = 12;
|
||||
|
||||
private PigpioSocketLock commandSocket;
|
||||
private int activeWaveformID = -1;
|
||||
|
||||
/** Creates and starts a socket connection to a pigpio daemon on localhost */
|
||||
public PigpioSocket() {
|
||||
this("127.0.0.1", 8888);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates and starts a socket connection to a pigpio daemon on a remote host with the specified
|
||||
* address and port
|
||||
*
|
||||
* @param addr Address of remote pigpio daemon
|
||||
* @param port Port of remote pigpio daemon
|
||||
*/
|
||||
public PigpioSocket(String addr, int port) {
|
||||
try {
|
||||
commandSocket = new PigpioSocketLock(addr, port);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to create or connect to Pigpio Daemon socket", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Reconnects to the pigpio daemon
|
||||
*
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void reconnect() throws PigpioException {
|
||||
try {
|
||||
commandSocket.reconnect();
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to reconnect to Pigpio Daemon socket", e);
|
||||
throw new PigpioException("reconnect", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Terminates the connection to the pigpio daemon
|
||||
*
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void gpioTerminate() throws PigpioException {
|
||||
try {
|
||||
commandSocket.terminate();
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to terminate connection to Pigpio Daemon socket", e);
|
||||
throw new PigpioException("gpioTerminate", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the GPIO level
|
||||
*
|
||||
* @param pin Pin to read from
|
||||
* @return Value of the pin
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public boolean gpioRead(int pin) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_READ.value, pin);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode != 0;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to read GPIO pin: " + pin, e);
|
||||
throw new PigpioException("gpioRead", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Write the GPIO level
|
||||
*
|
||||
* @param pin Pin to write to
|
||||
* @param value Value to write
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void gpioWrite(int pin, boolean value) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WRITE.value, pin, value ? 1 : 0);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to write to GPIO pin: " + pin, e);
|
||||
throw new PigpioException("gpioWrite", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Clears all waveforms and any data added by calls to {@link #waveAddGeneric(ArrayList)}
|
||||
*
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void waveClear() throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVCLR.value);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to clear waveforms", e);
|
||||
throw new PigpioException("waveClear", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Adds a number of pulses to the current waveform
|
||||
*
|
||||
* @param pulses ArrayList of pulses to add
|
||||
* @return the new total number of pulses in the current waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
private int waveAddGeneric(ArrayList<PigpioPulse> pulses) throws PigpioException {
|
||||
// pigpio wave message format
|
||||
|
||||
// I p1 0
|
||||
// I p2 0
|
||||
// I p3 pulses * 12
|
||||
// ## extension ##
|
||||
// III on/off/delay * pulses
|
||||
|
||||
if (pulses == null || pulses.size() == 0) return 0;
|
||||
|
||||
try {
|
||||
ByteBuffer bb = ByteBuffer.allocate(pulses.size() * 12);
|
||||
bb.order(ByteOrder.LITTLE_ENDIAN);
|
||||
for (var pulse : pulses) {
|
||||
bb.putInt(pulse.gpioOn).putInt(pulse.gpioOff).putInt(pulse.delayMicros);
|
||||
}
|
||||
|
||||
int retCode =
|
||||
commandSocket.sendCmd(
|
||||
PigpioCommand.PCMD_WVAG.value,
|
||||
0,
|
||||
0,
|
||||
pulses.size() * PIGPIOD_MESSAGE_SIZE,
|
||||
bb.array());
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to add pulse(s) to waveform", e);
|
||||
throw new PigpioException("waveAddGeneric", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates pulses and adds them to the current waveform
|
||||
*
|
||||
* @param pulseTimeMillis Pulse length in milliseconds
|
||||
* @param blinks Number of times to pulse. -1 for repeat
|
||||
* @param pinNo Pin to pulse
|
||||
*/
|
||||
private void addBlinkPulsesToWaveform(int pulseTimeMillis, int blinks, int pinNo) {
|
||||
boolean repeat = blinks == -1;
|
||||
|
||||
if (blinks == 0) return;
|
||||
|
||||
if (repeat) {
|
||||
blinks = 1;
|
||||
}
|
||||
|
||||
try {
|
||||
ArrayList<PigpioPulse> pulses = new ArrayList<>();
|
||||
var startPulse = new PigpioPulse(pinNo, 0, pulseTimeMillis * 1000);
|
||||
var endPulse = new PigpioPulse(0, pinNo, pulseTimeMillis * 1000);
|
||||
|
||||
for (int i = 0; i < blinks; i++) {
|
||||
pulses.add(startPulse);
|
||||
pulses.add(endPulse);
|
||||
}
|
||||
|
||||
waveAddGeneric(pulses);
|
||||
pulses.clear();
|
||||
} catch (Exception e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Generates and sends a waveform to the given pins with the specified parameters.
|
||||
*
|
||||
* @param pulseTimeMillis Pulse length in milliseconds
|
||||
* @param blinks Number of times to pulse. -1 for repeat
|
||||
* @param pins Pins to pulse
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void generateAndSendWaveform(int pulseTimeMillis, int blinks, int... pins)
|
||||
throws PigpioException {
|
||||
if (pins.length == 0) return;
|
||||
boolean repeat = blinks == -1;
|
||||
if (blinks == 0) return;
|
||||
|
||||
// stop any active waves
|
||||
waveTxStop();
|
||||
waveClear();
|
||||
|
||||
if (activeWaveformID != -1) {
|
||||
waveDelete(activeWaveformID);
|
||||
activeWaveformID = -1;
|
||||
}
|
||||
|
||||
for (int pin : pins) {
|
||||
addBlinkPulsesToWaveform(pulseTimeMillis, blinks, pin);
|
||||
}
|
||||
|
||||
int waveformId = waveCreate();
|
||||
|
||||
if (waveformId >= 0) {
|
||||
if (repeat) {
|
||||
waveSendRepeat(waveformId);
|
||||
} else {
|
||||
waveSendOnce(waveformId);
|
||||
}
|
||||
} else {
|
||||
String error = "";
|
||||
switch (waveformId) {
|
||||
case PI_EMPTY_WAVEFORM:
|
||||
error = "Waveform empty";
|
||||
break;
|
||||
case PI_TOO_MANY_CBS:
|
||||
error = "Too many CBS";
|
||||
break;
|
||||
case PI_TOO_MANY_OOL:
|
||||
error = "Too many OOL";
|
||||
break;
|
||||
case PI_NO_WAVEFORM_ID:
|
||||
error = "No waveform ID";
|
||||
break;
|
||||
}
|
||||
logger.error("Failed to send wave: " + error);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Stops the transmission of the current waveform
|
||||
*
|
||||
* @return success
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public boolean waveTxStop() throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVHLT.value);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode == 0;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to stop waveform", e);
|
||||
throw new PigpioException("waveTxStop", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a waveform from the data provided by the prior calls to {@link
|
||||
* #waveAddGeneric(ArrayList)} Upon success a wave ID greater than or equal to 0 is returned
|
||||
*
|
||||
* @return ID of the created waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public int waveCreate() throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVCRE.value);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to create new waveform", e);
|
||||
throw new PigpioException("waveCreate", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Deletes the waveform with specified wave ID
|
||||
*
|
||||
* @param waveId ID of the waveform to delete
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void waveDelete(int waveId) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVDEL.value, waveId);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to delete wave: " + waveId, e);
|
||||
throw new PigpioException("waveDelete", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmits the waveform with specified wave ID. The waveform is sent once
|
||||
*
|
||||
* @param waveId ID of the waveform to transmit
|
||||
* @return The number of DMA control blocks in the waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public int waveSendOnce(int waveId) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVTX.value, waveId);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
throw new PigpioException("waveSendOnce", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmits the waveform with specified wave ID. The waveform cycles until cancelled (either by
|
||||
* the sending of a new waveform or {@link #waveTxStop()}
|
||||
*
|
||||
* @param waveId ID of the waveform to transmit
|
||||
* @return The number of DMA control blocks in the waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public int waveSendRepeat(int waveId) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVTXR.value, waveId);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
throw new PigpioException("waveSendRepeat", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Starts hardware PWM on a GPIO at the specified frequency and dutycycle
|
||||
*
|
||||
* @param pin GPIO pin to start PWM on
|
||||
* @param pwmFrequency Frequency to run at (1Hz-125MHz). Frequencies above 30MHz are unlikely to
|
||||
* work
|
||||
* @param pwmDuty Duty cycle to run at (0-1,000,000)
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void hardwarePWM(int pin, int pwmFrequency, int pwmDuty) throws PigpioException {
|
||||
try {
|
||||
ByteBuffer bb = ByteBuffer.allocate(4);
|
||||
bb.order(ByteOrder.LITTLE_ENDIAN);
|
||||
bb.putInt(pwmDuty);
|
||||
|
||||
int retCode =
|
||||
commandSocket.sendCmd(PigpioCommand.PCMD_HP.value, pin, pwmFrequency, 4, bb.array());
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
throw new PigpioException("hardwarePWM", e);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,147 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import java.io.DataInputStream;
|
||||
import java.io.DataOutputStream;
|
||||
import java.io.IOException;
|
||||
import java.net.Socket;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
/**
|
||||
* Credit to nkolban
|
||||
* https://github.com/nkolban/jpigpio/blob/master/JPigpio/src/jpigpio/SocketLock.java
|
||||
*/
|
||||
final class PigpioSocketLock {
|
||||
private static final int replyTimeoutMillis = 1000;
|
||||
|
||||
private final String addr;
|
||||
private final int port;
|
||||
|
||||
private Socket socket;
|
||||
private DataInputStream in;
|
||||
private DataOutputStream out;
|
||||
|
||||
public PigpioSocketLock(String addr, int port) throws IOException {
|
||||
this.addr = addr;
|
||||
this.port = port;
|
||||
reconnect();
|
||||
}
|
||||
|
||||
public void reconnect() throws IOException {
|
||||
socket = new Socket(addr, port);
|
||||
out = new DataOutputStream(socket.getOutputStream());
|
||||
in = new DataInputStream(socket.getInputStream());
|
||||
}
|
||||
|
||||
public void terminate() throws IOException {
|
||||
in.close();
|
||||
in = null;
|
||||
|
||||
out.flush();
|
||||
out.close();
|
||||
out = null;
|
||||
|
||||
socket.close();
|
||||
socket = null;
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, 0, 0, 0, b);
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd, int p1) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, p1, 0, 0, b);
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd, int p1, int p2) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, p1, p2, 0, b);
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd, int p1, int p2, int p3) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, p1, p2, p3, b);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send extended command to pigpiod and return result code
|
||||
*
|
||||
* @param cmd Command to send
|
||||
* @param p1 Command parameter 1
|
||||
* @param p2 Command parameter 2
|
||||
* @param p3 Command parameter 3 (usually length of extended data - see paramater ext)
|
||||
* @param ext Array of bytes containing extended data
|
||||
* @return Command result code
|
||||
* @throws IOException in case of network connection error
|
||||
*/
|
||||
@SuppressWarnings("UnusedAssignment")
|
||||
public synchronized int sendCmd(int cmd, int p1, int p2, int p3, byte[] ext) throws IOException {
|
||||
ByteBuffer bb = ByteBuffer.allocate(16 + ext.length);
|
||||
|
||||
bb.putInt(Integer.reverseBytes(cmd));
|
||||
bb.putInt(Integer.reverseBytes(p1));
|
||||
bb.putInt(Integer.reverseBytes(p2));
|
||||
bb.putInt(Integer.reverseBytes(p3));
|
||||
|
||||
if (ext.length > 0) {
|
||||
bb.put(ext);
|
||||
}
|
||||
|
||||
out.write(bb.array());
|
||||
out.flush();
|
||||
|
||||
int w = replyTimeoutMillis;
|
||||
int a = in.available();
|
||||
|
||||
// if by any chance there is no response from pigpiod, then wait up to
|
||||
// specified timeout
|
||||
while (w > 0 && a < 16) {
|
||||
w -= 10;
|
||||
try {
|
||||
Thread.sleep(10);
|
||||
} catch (InterruptedException ignored) {
|
||||
}
|
||||
a = in.available();
|
||||
}
|
||||
|
||||
// throw exception if response from pigpiod has not arrived yet
|
||||
if (in.available() < 16) {
|
||||
throw new IOException(
|
||||
"Timeout: No response from pigpio daemon within " + replyTimeoutMillis + " ms.");
|
||||
}
|
||||
|
||||
int resp = Integer.reverseBytes(in.readInt()); // ignore response
|
||||
resp = Integer.reverseBytes(in.readInt()); // ignore response
|
||||
resp = Integer.reverseBytes(in.readInt()); // ignore response
|
||||
resp = Integer.reverseBytes(in.readInt()); // contains error or response
|
||||
return resp;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read all remaining bytes coming from pigpiod
|
||||
*
|
||||
* @param data Array to store read bytes.
|
||||
* @throws IOException if unable to read from network
|
||||
*/
|
||||
public void readBytes(byte[] data) throws IOException {
|
||||
in.readFully(data);
|
||||
}
|
||||
}
|
||||
@@ -1,162 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import java.io.IOException;
|
||||
import org.photonvision.common.ProgramStatus;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.configuration.HardwareSettings;
|
||||
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.pi.PigpioSocket;
|
||||
import org.photonvision.common.hardware.VisionLED.VisionLEDMode;
|
||||
import org.photonvision.common.hardware.metrics.MetricsBase;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.ShellExec;
|
||||
|
||||
public class HardwareManager {
|
||||
private static HardwareManager instance;
|
||||
|
||||
private final ShellExec shellExec = new ShellExec(true, false);
|
||||
private final Logger logger = new Logger(HardwareManager.class, LogGroup.General);
|
||||
|
||||
private final HardwareConfig hardwareConfig;
|
||||
private final HardwareSettings hardwareSettings;
|
||||
|
||||
@SuppressWarnings({"FieldCanBeLocal", "unused"})
|
||||
private final StatusLED statusLED;
|
||||
|
||||
@SuppressWarnings("FieldCanBeLocal")
|
||||
private final NetworkTableEntry ledModeEntry;
|
||||
|
||||
@SuppressWarnings({"FieldCanBeLocal", "unused"})
|
||||
private final NTDataChangeListener ledModeListener;
|
||||
|
||||
public final VisionLED visionLED; // May be null if no LED is specified
|
||||
|
||||
private final PigpioSocket pigpioSocket; // will be null unless on Raspi
|
||||
|
||||
public static HardwareManager getInstance() {
|
||||
if (instance == null) {
|
||||
var conf = ConfigManager.getInstance().getConfig();
|
||||
instance = new HardwareManager(conf.getHardwareConfig(), conf.getHardwareSettings());
|
||||
}
|
||||
return instance;
|
||||
}
|
||||
|
||||
private HardwareManager(HardwareConfig hardwareConfig, HardwareSettings hardwareSettings) {
|
||||
this.hardwareConfig = hardwareConfig;
|
||||
this.hardwareSettings = hardwareSettings;
|
||||
CustomGPIO.setConfig(hardwareConfig);
|
||||
MetricsBase.setConfig(hardwareConfig);
|
||||
|
||||
if (Platform.isRaspberryPi()) {
|
||||
pigpioSocket = new PigpioSocket();
|
||||
} else {
|
||||
pigpioSocket = null;
|
||||
}
|
||||
|
||||
statusLED =
|
||||
hardwareConfig.statusRGBPins.size() == 3
|
||||
? new StatusLED(hardwareConfig.statusRGBPins)
|
||||
: null;
|
||||
|
||||
var hasBrightnessRange = hardwareConfig.ledBrightnessRange.size() == 2;
|
||||
visionLED =
|
||||
hardwareConfig.ledPins.isEmpty()
|
||||
? null
|
||||
: new VisionLED(
|
||||
hardwareConfig.ledPins,
|
||||
hasBrightnessRange ? hardwareConfig.ledBrightnessRange.get(0) : 0,
|
||||
hasBrightnessRange ? hardwareConfig.ledBrightnessRange.get(1) : 100,
|
||||
pigpioSocket);
|
||||
|
||||
ledModeEntry = NetworkTablesManager.getInstance().kRootTable.getEntry("ledMode");
|
||||
ledModeEntry.setNumber(VisionLEDMode.VLM_DEFAULT.value);
|
||||
ledModeListener =
|
||||
visionLED == null
|
||||
? null
|
||||
: new NTDataChangeListener(ledModeEntry, visionLED::onLedModeChange);
|
||||
|
||||
Runtime.getRuntime().addShutdownHook(new Thread(this::onJvmExit));
|
||||
|
||||
if (visionLED != null) {
|
||||
visionLED.setBrightness(hardwareSettings.ledBrightnessPercentage);
|
||||
visionLED.blink(85, 4); // bootup blink
|
||||
}
|
||||
|
||||
// Start hardware metrics thread (Disabled until implemented)
|
||||
// if (Platform.isLinux()) MetricsPublisher.getInstance().startTask();
|
||||
}
|
||||
|
||||
public void setBrightnessPercent(int percent) {
|
||||
if (percent != hardwareSettings.ledBrightnessPercentage) {
|
||||
hardwareSettings.ledBrightnessPercentage = percent;
|
||||
if (visionLED != null) visionLED.setBrightness(percent);
|
||||
ConfigManager.getInstance().requestSave();
|
||||
logger.info("Setting led brightness to " + percent + "%");
|
||||
}
|
||||
}
|
||||
|
||||
private void onJvmExit() {
|
||||
logger.info("Shutting down LEDs...");
|
||||
if (visionLED != null) 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) {
|
||||
logger.error("Could not restart device!", e);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
public void setStatus(ProgramStatus status) {
|
||||
switch (status) {
|
||||
case UHOH:
|
||||
// red flashing, green off
|
||||
break;
|
||||
case RUNNING:
|
||||
// red solid, green off
|
||||
break;
|
||||
case RUNNING_NT:
|
||||
// red off, green solid
|
||||
break;
|
||||
case RUNNING_NT_TARGET:
|
||||
// red off, green flashing
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
public HardwareConfig getConfig() {
|
||||
return hardwareConfig;
|
||||
}
|
||||
}
|
||||
@@ -1,118 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import edu.wpi.first.wpiutil.RuntimeDetector;
|
||||
import java.io.IOException;
|
||||
import org.photonvision.common.util.ShellExec;
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
public enum Platform {
|
||||
// WPILib Supported (JNI)
|
||||
WINDOWS_32("Windows x32"),
|
||||
WINDOWS_64("Windows x64"),
|
||||
LINUX_64("Linux x64"),
|
||||
LINUX_RASPBIAN("Linux Raspbian"), // Raspberry Pi 3/4
|
||||
LINUX_AARCH64BIONIC("Linux AARCH64 Bionic"), // Jetson Nano, Jetson TX2
|
||||
// PhotonVision Supported (Manual install)
|
||||
LINUX_ARM32("Linux ARM32"), // ODROID XU4, C1+
|
||||
LINUX_ARM64("Linux ARM64"), // ODROID C2, N2
|
||||
|
||||
// Completely unsupported
|
||||
UNSUPPORTED("Unsupported Platform");
|
||||
|
||||
private static final ShellExec shell = new ShellExec(true, false);
|
||||
public final String value;
|
||||
public static final boolean isRoot = checkForRoot();
|
||||
|
||||
Platform(String value) {
|
||||
this.value = value;
|
||||
}
|
||||
|
||||
private static final String OS_NAME = System.getProperty("os.name");
|
||||
private static final String OS_ARCH = System.getProperty("os.arch");
|
||||
public static final Platform CurrentPlatform = getCurrentPlatform();
|
||||
|
||||
private static String UnknownPlatformString =
|
||||
String.format("Unknown Platform. OS: %s, Architecture: %s", OS_NAME, OS_ARCH);
|
||||
|
||||
public boolean isWindows() {
|
||||
return this == WINDOWS_64 || this == WINDOWS_32;
|
||||
}
|
||||
|
||||
public static boolean isLinux() {
|
||||
return getCurrentPlatform() == LINUX_64
|
||||
|| getCurrentPlatform() == LINUX_RASPBIAN
|
||||
|| getCurrentPlatform() == LINUX_ARM64;
|
||||
}
|
||||
|
||||
public static boolean isRaspberryPi() {
|
||||
return CurrentPlatform.equals(LINUX_RASPBIAN);
|
||||
}
|
||||
|
||||
@SuppressWarnings("StatementWithEmptyBody")
|
||||
private static boolean checkForRoot() {
|
||||
if (isLinux()) {
|
||||
try {
|
||||
shell.executeBashCommand("id -u");
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
while (!shell.isOutputCompleted()) {
|
||||
// TODO: add timeout
|
||||
}
|
||||
|
||||
if (shell.getExitCode() == 0) {
|
||||
return shell.getOutput().split("\n")[0].equals("0");
|
||||
}
|
||||
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
public static Platform getCurrentPlatform() {
|
||||
if (RuntimeDetector.isWindows()) {
|
||||
if (RuntimeDetector.is32BitIntel()) return WINDOWS_32;
|
||||
if (RuntimeDetector.is64BitIntel()) return WINDOWS_64;
|
||||
}
|
||||
|
||||
if (RuntimeDetector.isMac()) {
|
||||
if (RuntimeDetector.is32BitIntel()) return UNSUPPORTED;
|
||||
}
|
||||
|
||||
if (RuntimeDetector.isLinux()) {
|
||||
if (RuntimeDetector.is32BitIntel()) return UNSUPPORTED;
|
||||
if (RuntimeDetector.is64BitIntel()) return LINUX_64;
|
||||
if (RuntimeDetector.isRaspbian()) return LINUX_RASPBIAN;
|
||||
}
|
||||
|
||||
System.out.println(UnknownPlatformString);
|
||||
return Platform.UNSUPPORTED;
|
||||
}
|
||||
|
||||
public String toString() {
|
||||
if (this.equals(UNSUPPORTED)) {
|
||||
return UnknownPlatformString;
|
||||
} else {
|
||||
return this.value;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,48 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import java.util.List;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioPin;
|
||||
|
||||
public class StatusLED {
|
||||
public final GPIOBase redLED;
|
||||
public final GPIOBase greenLED;
|
||||
public final GPIOBase blueLED;
|
||||
|
||||
public StatusLED(List<Integer> statusLedPins) {
|
||||
// fill unassigned pins with -1 to disable
|
||||
if (statusLedPins.size() != 3) {
|
||||
for (int i = 0; i < 3 - statusLedPins.size(); i++) {
|
||||
statusLedPins.add(-1);
|
||||
}
|
||||
}
|
||||
|
||||
if (Platform.isRaspberryPi()) {
|
||||
redLED = new PigpioPin(statusLedPins.get(0));
|
||||
greenLED = new PigpioPin(statusLedPins.get(1));
|
||||
blueLED = new PigpioPin(statusLedPins.get(2));
|
||||
} else {
|
||||
redLED = new CustomGPIO(statusLedPins.get(0));
|
||||
greenLED = new CustomGPIO(statusLedPins.get(1));
|
||||
blueLED = new CustomGPIO(statusLedPins.get(2));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,213 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import edu.wpi.first.networktables.EntryNotification;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioException;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioPin;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioSocket;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.TimedTaskManager;
|
||||
import org.photonvision.common.util.math.MathUtils;
|
||||
|
||||
public class VisionLED {
|
||||
private static final Logger logger = new Logger(VisionLED.class, LogGroup.VisionModule);
|
||||
|
||||
private final int[] ledPins;
|
||||
private final List<GPIOBase> visionLEDs = new ArrayList<>();
|
||||
private final int brightnessMin;
|
||||
private final int brightnessMax;
|
||||
private final PigpioSocket pigpioSocket;
|
||||
|
||||
private VisionLEDMode currentLedMode = VisionLEDMode.VLM_DEFAULT;
|
||||
private BooleanSupplier pipelineModeSupplier;
|
||||
|
||||
private int mappedBrightnessPercentage;
|
||||
|
||||
public VisionLED(
|
||||
List<Integer> ledPins, int brightnessMin, int brightnessMax, PigpioSocket pigpioSocket) {
|
||||
this.brightnessMin = brightnessMin;
|
||||
this.brightnessMax = brightnessMax;
|
||||
this.pigpioSocket = pigpioSocket;
|
||||
this.ledPins = ledPins.stream().mapToInt(i -> i).toArray();
|
||||
ledPins.forEach(
|
||||
pin -> {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
visionLEDs.add(new PigpioPin(pin));
|
||||
} else {
|
||||
visionLEDs.add(new CustomGPIO(pin));
|
||||
}
|
||||
});
|
||||
pipelineModeSupplier = () -> false;
|
||||
}
|
||||
|
||||
public void setPipelineModeSupplier(BooleanSupplier pipelineModeSupplier) {
|
||||
this.pipelineModeSupplier = pipelineModeSupplier;
|
||||
}
|
||||
|
||||
public void setBrightness(int percentage) {
|
||||
mappedBrightnessPercentage = MathUtils.map(percentage, 0, 100, brightnessMin, brightnessMax);
|
||||
setInternal(currentLedMode, false);
|
||||
}
|
||||
|
||||
public void blink(int pulseLengthMillis, int blinkCount) {
|
||||
blinkImpl(pulseLengthMillis, blinkCount);
|
||||
int blinkDuration = pulseLengthMillis * blinkCount * 2;
|
||||
TimedTaskManager.getInstance()
|
||||
.addOneShotTask(() -> setInternal(this.currentLedMode, false), blinkDuration + 150);
|
||||
}
|
||||
|
||||
private void blinkImpl(int pulseLengthMillis, int blinkCount) {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
try {
|
||||
setStateImpl(false); // hack to ensure hardware PWM has stopped before trying to blink
|
||||
pigpioSocket.generateAndSendWaveform(pulseLengthMillis, blinkCount, ledPins);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Failed to blink!", e);
|
||||
}
|
||||
} else {
|
||||
for (GPIOBase led : visionLEDs) {
|
||||
led.blink(pulseLengthMillis, blinkCount);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void setStateImpl(boolean state) {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
try {
|
||||
// stop any active blink
|
||||
pigpioSocket.waveTxStop();
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Failed to stop blink!", e);
|
||||
}
|
||||
}
|
||||
// if the user has set an LED brightness other than 100%, use that instead
|
||||
if (mappedBrightnessPercentage == 100 || !state) {
|
||||
visionLEDs.forEach((led) -> led.setState(state));
|
||||
} else {
|
||||
visionLEDs.forEach((led) -> led.setBrightness(mappedBrightnessPercentage));
|
||||
}
|
||||
}
|
||||
|
||||
public void setState(boolean on) {
|
||||
setInternal(on ? VisionLEDMode.VLM_ON : VisionLEDMode.VLM_OFF, false);
|
||||
}
|
||||
|
||||
void onLedModeChange(EntryNotification entryNotification) {
|
||||
var newLedModeRaw = (int) entryNotification.value.getDouble();
|
||||
if (newLedModeRaw != currentLedMode.value) {
|
||||
VisionLEDMode newLedMode;
|
||||
switch (newLedModeRaw) {
|
||||
case -1:
|
||||
newLedMode = VisionLEDMode.VLM_DEFAULT;
|
||||
break;
|
||||
case 0:
|
||||
newLedMode = VisionLEDMode.VLM_OFF;
|
||||
break;
|
||||
case 1:
|
||||
newLedMode = VisionLEDMode.VLM_ON;
|
||||
break;
|
||||
case 2:
|
||||
newLedMode = VisionLEDMode.VLM_BLINK;
|
||||
break;
|
||||
default:
|
||||
logger.warn("User supplied invalid LED mode, falling back to Default");
|
||||
newLedMode = VisionLEDMode.VLM_DEFAULT;
|
||||
break;
|
||||
}
|
||||
setInternal(newLedMode, true);
|
||||
}
|
||||
}
|
||||
|
||||
private void setInternal(VisionLEDMode newLedMode, boolean fromNT) {
|
||||
var lastLedMode = currentLedMode;
|
||||
|
||||
if (fromNT) {
|
||||
switch (newLedMode) {
|
||||
case VLM_DEFAULT:
|
||||
setStateImpl(pipelineModeSupplier.getAsBoolean());
|
||||
break;
|
||||
case VLM_OFF:
|
||||
setStateImpl(false);
|
||||
break;
|
||||
case VLM_ON:
|
||||
setStateImpl(true);
|
||||
break;
|
||||
case VLM_BLINK:
|
||||
blinkImpl(85, -1);
|
||||
break;
|
||||
}
|
||||
currentLedMode = newLedMode;
|
||||
logger.info(
|
||||
"Changing LED mode from \""
|
||||
+ lastLedMode.toString()
|
||||
+ "\" to \""
|
||||
+ newLedMode.toString()
|
||||
+ "\"");
|
||||
} else {
|
||||
if (currentLedMode == VisionLEDMode.VLM_DEFAULT) {
|
||||
switch (newLedMode) {
|
||||
case VLM_DEFAULT:
|
||||
setStateImpl(pipelineModeSupplier.getAsBoolean());
|
||||
break;
|
||||
case VLM_OFF:
|
||||
setStateImpl(false);
|
||||
break;
|
||||
case VLM_ON:
|
||||
setStateImpl(true);
|
||||
break;
|
||||
}
|
||||
}
|
||||
logger.info("Changing LED internal state to " + newLedMode.toString());
|
||||
}
|
||||
}
|
||||
|
||||
public enum VisionLEDMode {
|
||||
VLM_DEFAULT(-1),
|
||||
VLM_OFF(0),
|
||||
VLM_ON(1),
|
||||
VLM_BLINK(2);
|
||||
|
||||
public final int value;
|
||||
|
||||
VisionLEDMode(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
switch (this) {
|
||||
case VLM_DEFAULT:
|
||||
return "Default";
|
||||
case VLM_OFF:
|
||||
return "Off";
|
||||
case VLM_ON:
|
||||
return "On";
|
||||
case VLM_BLINK:
|
||||
return "Blink";
|
||||
}
|
||||
return "";
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,44 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
public class CPUMetrics extends MetricsBase {
|
||||
|
||||
private String cpuMemSplit = null;
|
||||
|
||||
public String getMemory() {
|
||||
if (cpuMemoryCommand.isEmpty()) return "";
|
||||
if (cpuMemSplit == null) {
|
||||
cpuMemSplit = execute(cpuMemoryCommand);
|
||||
}
|
||||
return cpuMemSplit;
|
||||
}
|
||||
|
||||
public String getTemp() {
|
||||
if (cpuTemperatureCommand.isEmpty()) return "";
|
||||
try {
|
||||
return execute(cpuTemperatureCommand);
|
||||
} catch (Exception e) {
|
||||
return "N/A";
|
||||
}
|
||||
}
|
||||
|
||||
public String getUtilization() {
|
||||
return execute(cpuUtilizationCommand);
|
||||
}
|
||||
}
|
||||
@@ -1,25 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
public class DiskMetrics extends MetricsBase {
|
||||
public String getUsedDiskPct() {
|
||||
if (diskUsageCommand.isEmpty()) return "";
|
||||
return execute(diskUsageCommand);
|
||||
}
|
||||
}
|
||||
@@ -1,33 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
public class GPUMetrics extends MetricsBase {
|
||||
private String gpuMemSplit = null;
|
||||
|
||||
public String getGPUMemorySplit() {
|
||||
if (gpuMemSplit == null) {
|
||||
gpuMemSplit = execute(gpuMemoryCommand);
|
||||
}
|
||||
return gpuMemSplit;
|
||||
}
|
||||
|
||||
public String getMallocedMemory() {
|
||||
return execute(gpuMemUsageCommand);
|
||||
}
|
||||
}
|
||||
@@ -1,92 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
import java.io.PrintWriter;
|
||||
import java.io.StringWriter;
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
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 abstract class MetricsBase {
|
||||
private static final Logger logger = new Logger(MetricsBase.class, LogGroup.General);
|
||||
// CPU
|
||||
public static String cpuMemoryCommand = "vcgencmd get_mem arm | grep -Eo '[0-9]+'";
|
||||
public static String cpuTemperatureCommand =
|
||||
"sed 's/.\\{3\\}$/.&/' <<< cat /sys/class/thermal/thermal_zone0/temp";
|
||||
public static String cpuUtilizationCommand =
|
||||
"top -bn1 | grep \"Cpu(s)\" | sed \"s/.*, *\\([0-9.]*\\)%* id.*/\\1/\" | awk '{print 100 - $1}'";
|
||||
|
||||
// GPU
|
||||
public static String gpuMemoryCommand = "vcgencmd get_mem gpu | grep -Eo '[0-9]+'";
|
||||
public static String gpuMemUsageCommand = "vcgencmd get_mem malloc | grep -Eo '[0-9]+'";
|
||||
|
||||
// RAM
|
||||
public static String ramUsageCommand = "free --mega | awk -v i=2 -v j=3 'FNR == i {print $j}'";
|
||||
|
||||
// Disk
|
||||
public static String diskUsageCommand = "df ./ --output=pcent | tail -n +2";
|
||||
|
||||
private static ShellExec runCommand = new ShellExec(true, true);
|
||||
|
||||
public static void setConfig(HardwareConfig config) {
|
||||
if (Platform.isRaspberryPi()) return;
|
||||
cpuMemoryCommand = config.cpuMemoryCommand;
|
||||
cpuTemperatureCommand = config.cpuTempCommand;
|
||||
cpuUtilizationCommand = config.cpuUtilCommand;
|
||||
|
||||
gpuMemoryCommand = config.gpuMemoryCommand;
|
||||
gpuMemUsageCommand = config.gpuMemUsageCommand;
|
||||
|
||||
diskUsageCommand = config.diskUsageCommand;
|
||||
|
||||
ramUsageCommand = config.ramUtilCommand;
|
||||
}
|
||||
|
||||
public static synchronized String execute(String command) {
|
||||
try {
|
||||
runCommand.executeBashCommand(command);
|
||||
return runCommand.getOutput();
|
||||
} catch (Exception e) {
|
||||
StringWriter sw = new StringWriter();
|
||||
PrintWriter pw = new PrintWriter(sw);
|
||||
e.printStackTrace(pw);
|
||||
|
||||
logger.error(
|
||||
"Command: \""
|
||||
+ command
|
||||
+ "\" returned an error!"
|
||||
+ "\nOutput Received: "
|
||||
+ runCommand.getOutput()
|
||||
+ "\nStandard Error: "
|
||||
+ runCommand.getError()
|
||||
+ "\nCommand completed: "
|
||||
+ runCommand.isOutputCompleted()
|
||||
+ "\nError completed: "
|
||||
+ runCommand.isErrorCompleted()
|
||||
+ "\nExit code: "
|
||||
+ runCommand.getExitCode()
|
||||
+ "\n Exception: "
|
||||
+ e.toString()
|
||||
+ sw.toString());
|
||||
return "";
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,81 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
import com.fasterxml.jackson.core.JsonProcessingException;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.TimedTaskManager;
|
||||
import org.photonvision.server.SocketHandler;
|
||||
|
||||
public class MetricsPublisher {
|
||||
private static final Logger logger = new Logger(MetricsPublisher.class, LogGroup.General);
|
||||
private static CPUMetrics cpuMetrics;
|
||||
private static GPUMetrics gpuMetrics;
|
||||
private static RAMMetrics ramMetrics;
|
||||
private static DiskMetrics diskMetrics;
|
||||
|
||||
public static MetricsPublisher getInstance() {
|
||||
return Singleton.INSTANCE;
|
||||
}
|
||||
|
||||
private MetricsPublisher() {
|
||||
cpuMetrics = new CPUMetrics();
|
||||
gpuMetrics = new GPUMetrics();
|
||||
ramMetrics = new RAMMetrics();
|
||||
diskMetrics = new DiskMetrics();
|
||||
}
|
||||
|
||||
public void stopTask() {
|
||||
TimedTaskManager.getInstance().cancelTask("Metrics");
|
||||
logger.info("This device does not support running bash commands. Stopped metrics thread.");
|
||||
}
|
||||
|
||||
public void publish() {
|
||||
if (!Platform.isRaspberryPi()) {
|
||||
logger.debug("Ignoring metrics on non-Pi devices");
|
||||
return;
|
||||
}
|
||||
|
||||
logger.debug("Publishing Metrics...");
|
||||
final var metrics = new HashMap<String, String>();
|
||||
|
||||
metrics.put("cpuTemp", cpuMetrics.getTemp());
|
||||
metrics.put("cpuUtil", cpuMetrics.getUtilization());
|
||||
metrics.put("cpuMem", cpuMetrics.getMemory());
|
||||
metrics.put("gpuMem", gpuMetrics.getGPUMemorySplit());
|
||||
metrics.put("ramUtil", ramMetrics.getUsedRam());
|
||||
metrics.put("gpuMemUtil", gpuMetrics.getMallocedMemory());
|
||||
metrics.put("diskUtilPct", diskMetrics.getUsedDiskPct());
|
||||
|
||||
var retMap = new HashMap<String, Object>();
|
||||
retMap.put("metrics", metrics);
|
||||
|
||||
try {
|
||||
SocketHandler.getInstance().broadcastMessage(retMap, null);
|
||||
} catch (JsonProcessingException e) {
|
||||
logger.error("Exception while sending metrics!", e);
|
||||
}
|
||||
}
|
||||
|
||||
private static class Singleton {
|
||||
public static final MetricsPublisher INSTANCE = new MetricsPublisher();
|
||||
}
|
||||
}
|
||||
@@ -1,26 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.metrics;
|
||||
|
||||
public class RAMMetrics extends MetricsBase {
|
||||
// TODO: Output in MBs for consistency
|
||||
public String getUsedRam() {
|
||||
if (ramUsageCommand.isEmpty()) return "";
|
||||
return execute(ramUsageCommand);
|
||||
}
|
||||
}
|
||||
@@ -1,26 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.logging;
|
||||
|
||||
public enum LogGroup {
|
||||
Camera,
|
||||
WebServer,
|
||||
VisionModule,
|
||||
Data,
|
||||
General
|
||||
}
|
||||
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.logging;
|
||||
|
||||
public enum LogLevel {
|
||||
ERROR(0, Logger.ANSI_RED),
|
||||
WARN(1, Logger.ANSI_YELLOW),
|
||||
INFO(2, Logger.ANSI_GREEN),
|
||||
DEBUG(3, Logger.ANSI_WHITE),
|
||||
TRACE(4, Logger.ANSI_CYAN);
|
||||
|
||||
public final String colorCode;
|
||||
public final int code;
|
||||
|
||||
LogLevel(int code, String colorCode) {
|
||||
this.code = code;
|
||||
this.colorCode = colorCode;
|
||||
}
|
||||
}
|
||||
@@ -1,351 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.logging;
|
||||
|
||||
import java.io.*;
|
||||
import java.nio.file.Path;
|
||||
import java.text.ParseException;
|
||||
import java.text.SimpleDateFormat;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.Date;
|
||||
import java.util.HashMap;
|
||||
import java.util.LinkedList;
|
||||
import java.util.List;
|
||||
import java.util.function.Supplier;
|
||||
import org.apache.commons.lang3.tuple.Pair;
|
||||
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;
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
public class Logger {
|
||||
|
||||
public static final String ANSI_RESET = "\u001B[0m";
|
||||
public static final String ANSI_BLACK = "\u001B[30m";
|
||||
public static final String ANSI_RED = "\u001B[31m";
|
||||
public static final String ANSI_GREEN = "\u001B[32m";
|
||||
public static final String ANSI_YELLOW = "\u001B[33m";
|
||||
public static final String ANSI_BLUE = "\u001B[34m";
|
||||
public static final String ANSI_PURPLE = "\u001B[35m";
|
||||
public static final String ANSI_CYAN = "\u001B[36m";
|
||||
public static final String ANSI_WHITE = "\u001B[37m";
|
||||
|
||||
public static final int MAX_LOGS_TO_KEEP = 100;
|
||||
|
||||
private static final SimpleDateFormat simpleDateFormat =
|
||||
new SimpleDateFormat("yyyy-MM-dd HH:mm:ss");
|
||||
|
||||
private static final List<Pair<String, LogLevel>> uiBacklog = new ArrayList<>();
|
||||
private static boolean connected = false;
|
||||
|
||||
private static UILogAppender uiLogAppender = new UILogAppender();
|
||||
|
||||
private final String className;
|
||||
private final LogGroup group;
|
||||
|
||||
public Logger(Class<?> clazz, LogGroup group) {
|
||||
this.className = clazz.getSimpleName();
|
||||
this.group = group;
|
||||
}
|
||||
|
||||
public Logger(Class<?> clazz, String suffix, LogGroup group) {
|
||||
this.className = clazz.getSimpleName() + " - " + suffix;
|
||||
this.group = group;
|
||||
}
|
||||
|
||||
public static String getDate() {
|
||||
return simpleDateFormat.format(new Date());
|
||||
}
|
||||
|
||||
public static String format(
|
||||
String logMessage, LogLevel level, LogGroup group, String clazz, boolean color) {
|
||||
var date = getDate();
|
||||
var builder = new StringBuilder();
|
||||
if (color) builder.append(level.colorCode);
|
||||
builder
|
||||
.append("[")
|
||||
.append(date)
|
||||
.append("] [")
|
||||
.append(group)
|
||||
.append(" - ")
|
||||
.append(clazz)
|
||||
.append("] [")
|
||||
.append(level.name())
|
||||
.append("] ")
|
||||
.append(logMessage);
|
||||
if (color) builder.append(ANSI_RESET);
|
||||
return builder.toString();
|
||||
}
|
||||
|
||||
private static final HashMap<LogGroup, LogLevel> levelMap = new HashMap<>();
|
||||
private static final List<LogAppender> currentAppenders = new ArrayList<>();
|
||||
|
||||
static {
|
||||
levelMap.put(LogGroup.Camera, LogLevel.INFO);
|
||||
levelMap.put(LogGroup.General, LogLevel.INFO);
|
||||
levelMap.put(LogGroup.WebServer, LogLevel.INFO);
|
||||
levelMap.put(LogGroup.Data, LogLevel.INFO);
|
||||
levelMap.put(LogGroup.VisionModule, LogLevel.INFO);
|
||||
}
|
||||
|
||||
static {
|
||||
currentAppenders.add(new ConsoleLogAppender());
|
||||
currentAppenders.add(uiLogAppender);
|
||||
addFileAppender(ConfigManager.getInstance().getLogPath());
|
||||
cleanLogs(ConfigManager.getInstance().getLogsDir());
|
||||
}
|
||||
|
||||
@SuppressWarnings("ResultOfMethodCallIgnored")
|
||||
public static void addFileAppender(Path logFilePath) {
|
||||
var file = logFilePath.toFile();
|
||||
if (!file.exists()) {
|
||||
try {
|
||||
file.getParentFile().mkdirs();
|
||||
file.createNewFile();
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
currentAppenders.add(new FileLogAppender(logFilePath));
|
||||
}
|
||||
|
||||
public static void cleanLogs(Path folderToClean) {
|
||||
|
||||
LinkedList<File> logFileList =
|
||||
new LinkedList<>(Arrays.asList(folderToClean.toFile().listFiles()));
|
||||
HashMap<File, Date> logFileStartDateMap = new HashMap<>();
|
||||
|
||||
// Remove any files from the list for which we can't parse a start date from their name.
|
||||
// Simultaneously populate our HashMap with Date objects repeseting the file-name
|
||||
// indicated log start time.
|
||||
logFileList.removeIf(
|
||||
(File arg0) -> {
|
||||
try {
|
||||
logFileStartDateMap.put(
|
||||
arg0, ConfigManager.getInstance().logFnameToDate(arg0.getName()));
|
||||
return false;
|
||||
} catch (ParseException e) {
|
||||
return true;
|
||||
}
|
||||
});
|
||||
|
||||
// Execute a sort on the log file list by date in the filename.
|
||||
logFileList.sort(
|
||||
(File arg0, File arg1) -> {
|
||||
Date date0 = logFileStartDateMap.get(arg0);
|
||||
Date date1 = logFileStartDateMap.get(arg1);
|
||||
return date1.compareTo(date0);
|
||||
});
|
||||
|
||||
int logCounter = 0;
|
||||
for (File file : logFileList) {
|
||||
// Due to filtering above, everything in logFileList should be a log file
|
||||
if (logCounter < MAX_LOGS_TO_KEEP) {
|
||||
// Skip over the first MAX_LOGS_TO_KEEP files
|
||||
logCounter++;
|
||||
continue;
|
||||
} else {
|
||||
// Delete this file.
|
||||
file.delete();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static void setLevel(LogGroup group, LogLevel newLevel) {
|
||||
levelMap.put(group, newLevel);
|
||||
}
|
||||
|
||||
// TODO: profile
|
||||
private static void log(String message, LogLevel level, LogGroup group, String clazz) {
|
||||
for (var a : currentAppenders) {
|
||||
var shouldColor = a instanceof ConsoleLogAppender;
|
||||
var formattedMessage = format(message, level, group, clazz, shouldColor);
|
||||
a.log(formattedMessage, level);
|
||||
}
|
||||
if (!connected) {
|
||||
synchronized (uiBacklog) {
|
||||
uiBacklog.add(Pair.of(format(message, level, group, clazz, false), level));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static void sendConnectedBacklog() {
|
||||
connected = true;
|
||||
synchronized (uiBacklog) {
|
||||
for (var message : uiBacklog) {
|
||||
uiLogAppender.log(message.getLeft(), message.getRight());
|
||||
}
|
||||
uiBacklog.clear();
|
||||
}
|
||||
}
|
||||
|
||||
public boolean shouldLog(LogLevel logLevel) {
|
||||
return logLevel.code <= levelMap.get(group).code;
|
||||
}
|
||||
|
||||
private void log(String message, LogLevel level) {
|
||||
if (shouldLog(level)) {
|
||||
log(message, level, group, className);
|
||||
}
|
||||
}
|
||||
|
||||
private void log(String message, LogLevel messageLevel, LogLevel conditionalLevel) {
|
||||
if (shouldLog(conditionalLevel)) {
|
||||
log(message, messageLevel, group, className);
|
||||
}
|
||||
}
|
||||
|
||||
private void log(Supplier<String> messageSupplier, LogLevel level) {
|
||||
if (shouldLog(level)) {
|
||||
log(messageSupplier.get(), level, group, className);
|
||||
}
|
||||
}
|
||||
|
||||
private void log(
|
||||
Supplier<String> messageSupplier, LogLevel messageLevel, LogLevel conditionalLevel) {
|
||||
if (shouldLog(conditionalLevel)) {
|
||||
log(messageSupplier.get(), messageLevel, group, className);
|
||||
}
|
||||
}
|
||||
|
||||
public void error(Supplier<String> messageSupplier) {
|
||||
log(messageSupplier, LogLevel.ERROR);
|
||||
}
|
||||
|
||||
public void error(String message) {
|
||||
log(message, LogLevel.ERROR);
|
||||
}
|
||||
|
||||
/**
|
||||
* Logs an error message with the stack trace of a Throwable. The stacktrace will only be printed
|
||||
* if the current LogLevel is TRACE
|
||||
*
|
||||
* @param message
|
||||
* @param t
|
||||
*/
|
||||
public void error(String message, Throwable t) {
|
||||
log(message, LogLevel.ERROR);
|
||||
log(convertStackTraceToString(t), LogLevel.ERROR, LogLevel.DEBUG);
|
||||
}
|
||||
|
||||
public void warn(Supplier<String> messageSupplier) {
|
||||
log(messageSupplier, LogLevel.WARN);
|
||||
}
|
||||
|
||||
public void warn(String message) {
|
||||
log(message, LogLevel.WARN);
|
||||
}
|
||||
|
||||
public void info(Supplier<String> messageSupplier) {
|
||||
log(messageSupplier, LogLevel.INFO);
|
||||
}
|
||||
|
||||
public void info(String message) {
|
||||
log(message, LogLevel.INFO);
|
||||
}
|
||||
|
||||
public void debug(Supplier<String> messageSupplier) {
|
||||
log(messageSupplier, LogLevel.DEBUG);
|
||||
}
|
||||
|
||||
public void debug(String message) {
|
||||
log(message, LogLevel.DEBUG);
|
||||
}
|
||||
|
||||
public void trace(Supplier<String> messageSupplier) {
|
||||
log(messageSupplier, LogLevel.TRACE);
|
||||
}
|
||||
|
||||
public void trace(String message) {
|
||||
log(message, LogLevel.TRACE);
|
||||
}
|
||||
|
||||
private static String convertStackTraceToString(Throwable throwable) {
|
||||
try (StringWriter sw = new StringWriter();
|
||||
PrintWriter pw = new PrintWriter(sw)) {
|
||||
throwable.printStackTrace(pw);
|
||||
return sw.toString();
|
||||
} catch (IOException ioe) {
|
||||
throw new IllegalStateException(ioe);
|
||||
}
|
||||
}
|
||||
|
||||
private interface LogAppender {
|
||||
void log(String message, LogLevel level);
|
||||
}
|
||||
|
||||
private static class ConsoleLogAppender implements LogAppender {
|
||||
@Override
|
||||
public void log(String message, LogLevel level) {
|
||||
System.out.println(message);
|
||||
}
|
||||
}
|
||||
|
||||
private static class UILogAppender implements LogAppender {
|
||||
@Override
|
||||
public void log(String message, LogLevel level) {
|
||||
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<>("log", superMap));
|
||||
}
|
||||
}
|
||||
|
||||
private static class FileLogAppender implements LogAppender {
|
||||
private OutputStream out;
|
||||
private boolean wantsFlush;
|
||||
|
||||
public FileLogAppender(Path logFilePath) {
|
||||
try {
|
||||
this.out = new FileOutputStream(logFilePath.toFile());
|
||||
TimedTaskManager.getInstance()
|
||||
.addTask(
|
||||
"FileLogAppender",
|
||||
() -> {
|
||||
try {
|
||||
if (wantsFlush) {
|
||||
out.flush();
|
||||
wantsFlush = false;
|
||||
}
|
||||
} catch (IOException ignored) {
|
||||
}
|
||||
},
|
||||
3000L);
|
||||
} catch (FileNotFoundException e) {
|
||||
out = null;
|
||||
System.err.println("Unable to log to file " + logFilePath.toString());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void log(String message, LogLevel level) {
|
||||
message += "\n";
|
||||
try {
|
||||
out.write(message.getBytes());
|
||||
wantsFlush = true;
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,78 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.networking;
|
||||
|
||||
import java.net.InterfaceAddress;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
@SuppressWarnings("WeakerAccess")
|
||||
public class NetworkInterface {
|
||||
private static final Logger logger = new Logger(NetworkInterface.class, LogGroup.General);
|
||||
|
||||
public final String name;
|
||||
public final String displayName;
|
||||
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);
|
||||
|
||||
// TODO: (low) hack to "get" gateway, this is gross and bad, pls fix
|
||||
var splitIPAddr = ipAddress.split("\\.");
|
||||
splitIPAddr[3] = "1";
|
||||
splitIPAddr[3] = "255";
|
||||
broadcast = String.join(".", splitIPAddr);
|
||||
}
|
||||
|
||||
private static String getIPv4LocalNetMask(InterfaceAddress interfaceAddress) {
|
||||
var netPrefix = interfaceAddress.getNetworkPrefixLength();
|
||||
try {
|
||||
// Since this is for IPv4, it's 32 bits, so set the sign value of
|
||||
// the int to "negative"...
|
||||
int shiftby = (1 << 31);
|
||||
// For the number of bits of the prefix -1 (we already set the sign bit)
|
||||
for (int i = netPrefix - 1; i > 0; i--) {
|
||||
// Shift the sign right... Java makes the sign bit sticky on a shift...
|
||||
// So no need to "set it back up"...
|
||||
shiftby = (shiftby >> 1);
|
||||
}
|
||||
// Transform the resulting value in xxx.xxx.xxx.xxx format, like if
|
||||
/// it was a standard address...
|
||||
// Return the address thus created...
|
||||
return ((shiftby >> 24) & 255)
|
||||
+ "."
|
||||
+ ((shiftby >> 16) & 255)
|
||||
+ "."
|
||||
+ ((shiftby >> 8) & 255)
|
||||
+ "."
|
||||
+ (shiftby & 255);
|
||||
// return InetAddress.getByName(maskString);
|
||||
} catch (Exception e) {
|
||||
logger.error("Failed to get netmask!", e);
|
||||
}
|
||||
// Something went wrong here...
|
||||
return null;
|
||||
}
|
||||
}
|
||||
@@ -1,127 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.networking;
|
||||
|
||||
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 {
|
||||
private static final NetworkManager INSTANCE = new NetworkManager();
|
||||
}
|
||||
|
||||
public static NetworkManager getInstance() {
|
||||
return SingletonHolder.INSTANCE;
|
||||
}
|
||||
|
||||
private boolean isManaged = false;
|
||||
|
||||
public void initialize(boolean shouldManage) {
|
||||
isManaged = shouldManage;
|
||||
if (!isManaged) {
|
||||
return;
|
||||
}
|
||||
|
||||
var config = ConfigManager.getInstance().getConfig().getNetworkConfig();
|
||||
logger.info("Setting " + config.connectionType + " with team team " + config.teamNumber);
|
||||
if (Platform.isLinux()) {
|
||||
if (!Platform.isRoot) {
|
||||
logger.error("Cannot manage network without root!");
|
||||
return;
|
||||
}
|
||||
|
||||
// always set hostname
|
||||
if (config.hostname.length() > 0) {
|
||||
try {
|
||||
var shell = new ShellExec(true, false);
|
||||
shell.executeBashCommand("cat /etc/hostname | tr -d \" \\t\\n\\r\"");
|
||||
var oldHostname = shell.getOutput().replace("\n", "");
|
||||
|
||||
var setHostnameRetCode =
|
||||
shell.executeBashCommand(
|
||||
"echo $NEW_HOSTNAME > /etc/hostname".replace("$NEW_HOSTNAME", config.hostname));
|
||||
setHostnameRetCode =
|
||||
shell.executeBashCommand("hostnamectl set-hostname " + config.hostname);
|
||||
|
||||
// Add to /etc/hosts
|
||||
var addHostRetCode =
|
||||
shell.executeBashCommand(
|
||||
String.format(
|
||||
"sed -i \"s/127.0.1.1.*%s/127.0.1.1\\t%s/g\" /etc/hosts",
|
||||
oldHostname, config.hostname));
|
||||
|
||||
shell.executeBashCommand("sudo service avahi-daemon restart");
|
||||
|
||||
var success = setHostnameRetCode == 0 && addHostRetCode == 0;
|
||||
if (!success) {
|
||||
logger.error(
|
||||
"Setting hostname returned non-zero codes (hostname/hosts) "
|
||||
+ setHostnameRetCode
|
||||
+ "|"
|
||||
+ addHostRetCode
|
||||
+ "!");
|
||||
} else {
|
||||
logger.info("Set hostname to " + config.hostname);
|
||||
}
|
||||
} catch (Exception e) {
|
||||
logger.error("Failed to set hostname!", e);
|
||||
}
|
||||
|
||||
} else {
|
||||
logger.warn("Got empty hostname?");
|
||||
}
|
||||
|
||||
if (config.connectionType == NetworkMode.DHCP) {
|
||||
var shell = new ShellExec();
|
||||
try {
|
||||
if (!config.staticIp.equals("")) {
|
||||
shell.executeBashCommand("ip addr del " + config.staticIp + "/8 dev eth0");
|
||||
}
|
||||
shell.executeBashCommand("dhclient eth0", false);
|
||||
} catch (Exception e) {
|
||||
logger.error("Exception while setting DHCP!");
|
||||
}
|
||||
} else if (config.connectionType == NetworkMode.STATIC) {
|
||||
var shell = new ShellExec();
|
||||
if (config.staticIp.length() > 0) {
|
||||
try {
|
||||
shell.executeBashCommand("ip addr add " + config.staticIp + "/8" + " dev eth0");
|
||||
} catch (Exception e) {
|
||||
logger.error("Error while setting static IP!", e);
|
||||
}
|
||||
} else {
|
||||
logger.warn("Got empty static IP?");
|
||||
}
|
||||
}
|
||||
} else {
|
||||
logger.info("Not managing network on non-Linux platforms");
|
||||
}
|
||||
}
|
||||
|
||||
public void reinitialize() {
|
||||
initialize(ConfigManager.getInstance().getConfig().getNetworkConfig().shouldManage());
|
||||
}
|
||||
}
|
||||
@@ -1,23 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.networking;
|
||||
|
||||
public enum NetworkMode {
|
||||
DHCP,
|
||||
STATIC
|
||||
}
|
||||
@@ -1,31 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.scripting;
|
||||
|
||||
public enum ScriptCommandType {
|
||||
kDefault(""),
|
||||
kBashScript("bash"),
|
||||
kPythonScript("python"),
|
||||
kPython3Script("python3");
|
||||
|
||||
public final String value;
|
||||
|
||||
ScriptCommandType(String value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
@@ -1,39 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.scripting;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonCreator;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
|
||||
public class ScriptConfig {
|
||||
public final ScriptEventType eventType;
|
||||
public final String command;
|
||||
|
||||
public ScriptConfig(ScriptEventType eventType) {
|
||||
this.eventType = eventType;
|
||||
this.command = "";
|
||||
}
|
||||
|
||||
@JsonCreator
|
||||
public ScriptConfig(
|
||||
@JsonProperty("eventType") ScriptEventType eventType,
|
||||
@JsonProperty("command") String command) {
|
||||
this.eventType = eventType;
|
||||
this.command = command;
|
||||
}
|
||||
}
|
||||
@@ -1,54 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.scripting;
|
||||
|
||||
import java.io.IOException;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.ShellExec;
|
||||
|
||||
public class ScriptEvent {
|
||||
private static final ShellExec executor = new ShellExec(true, true);
|
||||
|
||||
public final ScriptConfig config;
|
||||
private final Logger logger = new Logger(ScriptEvent.class, LogGroup.General);
|
||||
|
||||
public ScriptEvent(ScriptConfig config) {
|
||||
this.config = config;
|
||||
}
|
||||
|
||||
public int run() throws IOException {
|
||||
int retVal = executor.executeBashCommand(config.command);
|
||||
|
||||
String output = executor.getOutput();
|
||||
String error = executor.getError();
|
||||
|
||||
if (!error.isEmpty()) {
|
||||
logger.error("Error when running \"" + config.eventType.name() + "\" script: " + error);
|
||||
} else if (!output.isEmpty()) {
|
||||
logger.info(
|
||||
String.format("Output from \"%s\" script: %s\n", config.eventType.name(), output));
|
||||
}
|
||||
logger.info(
|
||||
String.format(
|
||||
"Script for %s ran with command line: \"%s\", exit code: %d, output: %s, "
|
||||
+ "error: %s\n",
|
||||
config.eventType.name(), config.command, retVal, output, error));
|
||||
return retVal;
|
||||
}
|
||||
}
|
||||
@@ -1,38 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.scripting;
|
||||
|
||||
public enum ScriptEventType {
|
||||
kProgramInit("Program Init"),
|
||||
kProgramExit("Program Exit"),
|
||||
kNTConnected("NT Connected"),
|
||||
kLEDOn("LED On"),
|
||||
kLEDOff("LED Off"),
|
||||
kEnterDriverMode("Enter Driver Mode"),
|
||||
kExitDriverMode("Exit Driver Mode"),
|
||||
kFoundTarget("Found Target"),
|
||||
kFoundMultipleTarget("Found Multiple Target"),
|
||||
kLostTarget("Lost Target"),
|
||||
kPipelineLag("Pipeline Lag");
|
||||
|
||||
public final String value;
|
||||
|
||||
ScriptEventType(String value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
@@ -1,143 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.scripting;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Files;
|
||||
import java.nio.file.Path;
|
||||
import java.nio.file.Paths;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.concurrent.LinkedBlockingDeque;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.TimedTaskManager;
|
||||
import org.photonvision.common.util.file.JacksonUtils;
|
||||
|
||||
public class ScriptManager {
|
||||
|
||||
private static final Logger logger = new Logger(ScriptManager.class, LogGroup.General);
|
||||
|
||||
private ScriptManager() {}
|
||||
|
||||
private static final List<ScriptEvent> events = new ArrayList<>();
|
||||
private static final LinkedBlockingDeque<ScriptEventType> queuedEvents =
|
||||
new LinkedBlockingDeque<>(25);
|
||||
|
||||
public static void initialize() {
|
||||
ScriptConfigManager.initialize();
|
||||
if (ScriptConfigManager.fileExists()) {
|
||||
for (ScriptConfig scriptConfig : ScriptConfigManager.loadConfig()) {
|
||||
ScriptEvent scriptEvent = new ScriptEvent(scriptConfig);
|
||||
events.add(scriptEvent);
|
||||
}
|
||||
|
||||
TimedTaskManager.getInstance().addTask("ScriptRunner", new ScriptRunner(), 10);
|
||||
|
||||
} else {
|
||||
logger.error("Something went wrong initializing scripts! Events will not run.");
|
||||
}
|
||||
}
|
||||
|
||||
private static class ScriptRunner implements Runnable {
|
||||
@Override
|
||||
public void run() {
|
||||
try {
|
||||
handleEvent(queuedEvents.takeFirst());
|
||||
} catch (InterruptedException e) {
|
||||
logger.error("ScriptRunner queue interrupted!", e);
|
||||
}
|
||||
}
|
||||
|
||||
private void handleEvent(ScriptEventType eventType) {
|
||||
var toRun =
|
||||
events
|
||||
.parallelStream()
|
||||
.filter(e -> e.config.eventType == eventType)
|
||||
.findFirst()
|
||||
.orElse(null);
|
||||
if (toRun != null) {
|
||||
try {
|
||||
toRun.run();
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to run script for event \"" + eventType.name() + "\"", e);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
protected static class ScriptConfigManager {
|
||||
|
||||
// protected static final Path scriptConfigPath =
|
||||
// Paths.get(ConfigManager.SettingsPath.toString(), "scripts.json");
|
||||
static final Path scriptConfigPath = Paths.get(""); // TODO: Waiting on config
|
||||
|
||||
private ScriptConfigManager() {}
|
||||
|
||||
static boolean fileExists() {
|
||||
return Files.exists(scriptConfigPath);
|
||||
}
|
||||
|
||||
public static void initialize() {
|
||||
if (!fileExists()) {
|
||||
List<ScriptConfig> eventsConfig = new ArrayList<>();
|
||||
for (var eventType : ScriptEventType.values()) {
|
||||
eventsConfig.add(new ScriptConfig(eventType));
|
||||
}
|
||||
|
||||
try {
|
||||
JacksonUtils.serialize(scriptConfigPath, eventsConfig.toArray(new ScriptConfig[0]), true);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to initialize!", e);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static List<ScriptConfig> loadConfig() {
|
||||
try {
|
||||
var raw = JacksonUtils.deserialize(scriptConfigPath, ScriptConfig[].class);
|
||||
if (raw != null) {
|
||||
return List.of(raw);
|
||||
}
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to load scripting config!", e);
|
||||
}
|
||||
return new ArrayList<>();
|
||||
}
|
||||
|
||||
protected static void deleteConfig() {
|
||||
try {
|
||||
Files.delete(scriptConfigPath);
|
||||
} catch (IOException e) {
|
||||
//
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static void queueEvent(ScriptEventType eventType) {
|
||||
if (!Platform.CurrentPlatform.isWindows()) {
|
||||
try {
|
||||
queuedEvents.putLast(eventType);
|
||||
logger.info("Queued event: " + eventType.name());
|
||||
} catch (InterruptedException e) {
|
||||
logger.error("Failed to add event to queue: " + eventType.name(), e);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,27 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util;
|
||||
|
||||
import java.awt.*;
|
||||
import org.opencv.core.Scalar;
|
||||
|
||||
public class ColorHelper {
|
||||
public static Scalar colorToScalar(Color color) {
|
||||
return new Scalar(color.getBlue(), color.getGreen(), color.getRed());
|
||||
}
|
||||
}
|
||||
@@ -1,85 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util;
|
||||
|
||||
public class MemoryManager {
|
||||
|
||||
private static final long MEGABYTE_FACTOR = 1024L * 1024L;
|
||||
|
||||
private int collectionThreshold;
|
||||
private long collectionPeriodMillis = -1;
|
||||
|
||||
private double lastUsedMb = 0;
|
||||
private long lastCollectionMillis = 0;
|
||||
|
||||
public MemoryManager(int collectionThreshold) {
|
||||
this.collectionThreshold = collectionThreshold;
|
||||
}
|
||||
|
||||
public MemoryManager(int collectionThreshold, long collectionPeriodMillis) {
|
||||
this.collectionThreshold = collectionThreshold;
|
||||
this.collectionPeriodMillis = collectionPeriodMillis;
|
||||
}
|
||||
|
||||
public void setCollectionThreshold(int collectionThreshold) {
|
||||
this.collectionThreshold = collectionThreshold;
|
||||
}
|
||||
|
||||
public void setCollectionPeriodMillis(long collectionPeriodMillis) {
|
||||
this.collectionPeriodMillis = collectionPeriodMillis;
|
||||
}
|
||||
|
||||
private static long getUsedMemory() {
|
||||
return Runtime.getRuntime().totalMemory() - Runtime.getRuntime().freeMemory();
|
||||
}
|
||||
|
||||
private static double getUsedMemoryMB() {
|
||||
return ((double) getUsedMemory() / MEGABYTE_FACTOR);
|
||||
}
|
||||
|
||||
private void collect() {
|
||||
System.gc();
|
||||
System.runFinalization();
|
||||
}
|
||||
|
||||
public void run() {
|
||||
run(false);
|
||||
}
|
||||
|
||||
public void run(boolean print) {
|
||||
var usedMem = getUsedMemoryMB();
|
||||
|
||||
if (usedMem != lastUsedMb) {
|
||||
lastUsedMb = usedMem;
|
||||
if (print) System.out.printf("Memory usage: %.2fMB\n", usedMem);
|
||||
}
|
||||
|
||||
boolean collectionThresholdPassed = usedMem >= collectionThreshold;
|
||||
boolean collectionPeriodPassed =
|
||||
collectionPeriodMillis != -1
|
||||
&& (System.currentTimeMillis() - lastCollectionMillis >= collectionPeriodMillis);
|
||||
|
||||
if (collectionThresholdPassed || collectionPeriodPassed) {
|
||||
collect();
|
||||
lastCollectionMillis = System.currentTimeMillis();
|
||||
if (print) {
|
||||
System.out.printf("Garbage collected at %.2fMB\n", usedMem);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,59 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util;
|
||||
|
||||
public class ReflectionUtils {
|
||||
|
||||
public static StackTraceElement[] getFullStackTrace() {
|
||||
return Thread.currentThread().getStackTrace();
|
||||
}
|
||||
|
||||
public static StackTraceElement getNthCaller(int n) {
|
||||
if (n < 0) n = 0;
|
||||
return Thread.currentThread().getStackTrace()[n];
|
||||
}
|
||||
|
||||
public static String getCallerClassName() {
|
||||
StackTraceElement[] stElements = Thread.currentThread().getStackTrace();
|
||||
for (int i = 1; i < stElements.length; i++) {
|
||||
StackTraceElement ste = stElements[i];
|
||||
if (!ste.getClassName().equals(ReflectionUtils.class.getName())
|
||||
&& ste.getClassName().indexOf("java.lang.Thread") != 0) {
|
||||
return ste.getClassName();
|
||||
}
|
||||
}
|
||||
return null;
|
||||
}
|
||||
|
||||
public static String getCallerCallerClassName() {
|
||||
StackTraceElement[] stElements = Thread.currentThread().getStackTrace();
|
||||
String callerClassName = null;
|
||||
for (int i = 1; i < stElements.length; i++) {
|
||||
StackTraceElement ste = stElements[i];
|
||||
if (!ste.getClassName().equals(ReflectionUtils.class.getName())
|
||||
&& ste.getClassName().indexOf("java.lang.Thread") != 0) {
|
||||
if (callerClassName == null) {
|
||||
callerClassName = ste.getClassName();
|
||||
} else if (!callerClassName.equals(ste.getClassName())) {
|
||||
return ste.getClassName();
|
||||
}
|
||||
}
|
||||
}
|
||||
return null;
|
||||
}
|
||||
}
|
||||
@@ -1,46 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util;
|
||||
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public final class SerializationUtils {
|
||||
private static final Logger logger = new Logger(SerializationUtils.class, LogGroup.General);
|
||||
|
||||
public static HashMap<String, Object> objectToHashMap(Object src) {
|
||||
var ret = new HashMap<String, Object>();
|
||||
for (var field : src.getClass().getFields()) {
|
||||
try {
|
||||
field.setAccessible(true);
|
||||
if (!field
|
||||
.getType()
|
||||
.isEnum()) { // if the field is not an enum, get it based on the current pipeline
|
||||
ret.put(field.getName(), field.get(src));
|
||||
} else {
|
||||
var ordinal = (Enum) field.get(src);
|
||||
ret.put(field.getName(), ordinal.ordinal());
|
||||
}
|
||||
} catch (IllegalArgumentException | IllegalAccessException e) {
|
||||
logger.error("Could not serialize " + src.getClass().getSimpleName(), e);
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
@@ -1,207 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util;
|
||||
|
||||
import java.io.*;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
/** Execute external process and optionally read output buffer. */
|
||||
@SuppressWarnings({"unused", "ConstantConditions"})
|
||||
public class ShellExec {
|
||||
private static final Logger logger = new Logger(ShellExec.class, LogGroup.General);
|
||||
|
||||
private int exitCode;
|
||||
private boolean readOutput, readError;
|
||||
private StreamGobbler errorGobbler, outputGobbler;
|
||||
|
||||
public ShellExec() {
|
||||
this(false, false);
|
||||
}
|
||||
|
||||
public ShellExec(boolean readOutput, boolean readError) {
|
||||
this.readOutput = readOutput;
|
||||
this.readError = readError;
|
||||
}
|
||||
|
||||
public int executeBashCommand(String command) throws IOException {
|
||||
return executeBashCommand(command, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute a bash command. We can handle complex bash commands including multiple executions (; |
|
||||
* and ||), quotes, expansions ($), escapes (\), e.g.: "cd /abc/def; mv ghi 'older ghi '$(whoami)"
|
||||
*
|
||||
* @param command Bash command to execute
|
||||
* @return true if bash got started, but your command may have failed.
|
||||
*/
|
||||
public int executeBashCommand(String command, boolean wait) throws IOException {
|
||||
logger.debug("Executing \"" + command + "\"");
|
||||
|
||||
boolean success = false;
|
||||
Runtime r = Runtime.getRuntime();
|
||||
// Use bash -c so we can handle things like multi commands separated by ; and
|
||||
// things like quotes, $, |, and \. My tests show that command comes as
|
||||
// one argument to bash, so we do not need to quote it to make it one thing.
|
||||
// Also, exec may object if it does not have an executable file as the first thing,
|
||||
// so having bash here makes it happy provided bash is installed and in path.
|
||||
String[] commands = {"bash", "-c", command};
|
||||
|
||||
Process process = r.exec(commands);
|
||||
|
||||
// Consume streams, older jvm's had a memory leak if streams were not read,
|
||||
// some other jvm+OS combinations may block unless streams are consumed.
|
||||
int retcode = doProcess(wait, process);
|
||||
logger.debug("Got exit code " + retcode);
|
||||
return retcode;
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute a command in current folder, and wait for process to end
|
||||
*
|
||||
* @param command command ("c:/some/folder/script.bat" or "some/folder/script.sh")
|
||||
* @param args 0..n command line arguments
|
||||
* @return process exit code
|
||||
*/
|
||||
public int execute(String command, String... args) throws IOException {
|
||||
return execute(command, null, true, args);
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute a command.
|
||||
*
|
||||
* @param command command ("c:/some/folder/script.bat" or "some/folder/script.sh")
|
||||
* @param workdir working directory or NULL to use command folder
|
||||
* @param wait wait for process to end
|
||||
* @param args 0..n command line arguments
|
||||
* @return process exit code
|
||||
*/
|
||||
public int execute(String command, String workdir, boolean wait, String... args)
|
||||
throws IOException {
|
||||
String[] cmdArr;
|
||||
if (args != null && args.length > 0) {
|
||||
cmdArr = new String[1 + args.length];
|
||||
cmdArr[0] = command;
|
||||
System.arraycopy(args, 0, cmdArr, 1, args.length);
|
||||
} else {
|
||||
cmdArr = new String[] {command};
|
||||
}
|
||||
|
||||
ProcessBuilder pb = new ProcessBuilder(cmdArr);
|
||||
File workingDir = (workdir == null ? new File(command).getParentFile() : new File(workdir));
|
||||
pb.directory(workingDir);
|
||||
|
||||
Process process = pb.start();
|
||||
|
||||
// Consume streams, older jvm's had a memory leak if streams were not read,
|
||||
// some other jvm+OS combinations may block unless streams are consumed.
|
||||
return doProcess(wait, process);
|
||||
}
|
||||
|
||||
private int doProcess(boolean wait, Process process) {
|
||||
errorGobbler = new StreamGobbler(process.getErrorStream(), readError);
|
||||
outputGobbler = new StreamGobbler(process.getInputStream(), readOutput);
|
||||
errorGobbler.start();
|
||||
outputGobbler.start();
|
||||
|
||||
exitCode = 0;
|
||||
if (wait) {
|
||||
try {
|
||||
process.waitFor();
|
||||
exitCode = process.exitValue();
|
||||
} catch (InterruptedException ignored) {
|
||||
}
|
||||
}
|
||||
return exitCode;
|
||||
}
|
||||
|
||||
public int getExitCode() {
|
||||
return exitCode;
|
||||
}
|
||||
|
||||
public boolean isOutputCompleted() {
|
||||
return (outputGobbler != null && outputGobbler.isCompleted());
|
||||
}
|
||||
|
||||
public boolean isErrorCompleted() {
|
||||
return (errorGobbler != null && errorGobbler.isCompleted());
|
||||
}
|
||||
|
||||
public String getOutput() {
|
||||
return (outputGobbler != null ? outputGobbler.getOutput() : null);
|
||||
}
|
||||
|
||||
public String getError() {
|
||||
return (errorGobbler != null ? errorGobbler.getOutput() : null);
|
||||
}
|
||||
|
||||
// ********************************************
|
||||
// ********************************************
|
||||
|
||||
/**
|
||||
* StreamGobbler reads inputstream to "gobble" it. This is used by Executor class when running a
|
||||
* commandline applications. Gobblers must read/purge INSTR and ERRSTR process streams.
|
||||
* http://www.javaworld.com/javaworld/jw-12-2000/jw-1229-traps.html?page=4
|
||||
*/
|
||||
@SuppressWarnings("WeakerAccess")
|
||||
private static class StreamGobbler extends Thread {
|
||||
private InputStream is;
|
||||
private StringBuilder output;
|
||||
private volatile boolean completed; // mark volatile to guarantee a thread safety
|
||||
|
||||
public StreamGobbler(InputStream is, boolean readStream) {
|
||||
this.is = is;
|
||||
this.output = (readStream ? new StringBuilder(256) : null);
|
||||
}
|
||||
|
||||
public void run() {
|
||||
completed = false;
|
||||
try {
|
||||
String NL = System.getProperty("line.separator", "\r\n");
|
||||
|
||||
InputStreamReader isr = new InputStreamReader(is);
|
||||
BufferedReader br = new BufferedReader(isr);
|
||||
String line;
|
||||
while ((line = br.readLine()) != null) {
|
||||
if (output != null) output.append(line).append(NL);
|
||||
}
|
||||
} catch (IOException ex) {
|
||||
// ex.printStackTrace();
|
||||
}
|
||||
completed = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get inputstream buffer or null if stream was not consumed.
|
||||
*
|
||||
* @return Output stream
|
||||
*/
|
||||
public String getOutput() {
|
||||
return (output != null ? output.toString() : null);
|
||||
}
|
||||
|
||||
/**
|
||||
* Is input stream completed.
|
||||
*
|
||||
* @return if input stream is completed
|
||||
*/
|
||||
public boolean isCompleted() {
|
||||
return completed;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,250 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util;
|
||||
|
||||
import com.fasterxml.jackson.databind.ObjectMapper;
|
||||
import edu.wpi.cscore.CameraServerCvJNI;
|
||||
import java.awt.*;
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Path;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.highgui.HighGui;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
|
||||
public class TestUtils {
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
public enum WPI2019Image {
|
||||
kCargoAngledDark48in(1.2192),
|
||||
kCargoSideStraightDark36in(0.9144),
|
||||
kCargoSideStraightDark60in(1.524),
|
||||
kCargoSideStraightDark72in(1.8288),
|
||||
kCargoSideStraightPanelDark36in(0.9144),
|
||||
kCargoStraightDark19in(0.4826),
|
||||
kCargoStraightDark24in(0.6096),
|
||||
kCargoStraightDark48in(1.2192),
|
||||
kCargoStraightDark72in(1.8288),
|
||||
kCargoStraightDark72in_HighRes(1.8288),
|
||||
kCargoStraightDark90in(2.286),
|
||||
kRocketPanelAngleDark48in(1.2192),
|
||||
kRocketPanelAngleDark60in(1.524);
|
||||
|
||||
public static double FOV = 68.5;
|
||||
|
||||
public final double distanceMeters;
|
||||
public final Path path;
|
||||
|
||||
Path getPath() {
|
||||
var filename = this.toString().substring(1);
|
||||
return Path.of("2019", "WPI", filename + ".jpg");
|
||||
}
|
||||
|
||||
WPI2019Image(double distanceMeters) {
|
||||
this.distanceMeters = distanceMeters;
|
||||
this.path = getPath();
|
||||
}
|
||||
}
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
public enum WPI2020Image {
|
||||
kBlueGoal_060in_Center(1.524),
|
||||
kBlueGoal_084in_Center(2.1336),
|
||||
kBlueGoal_084in_Center_720p(2.1336),
|
||||
kBlueGoal_108in_Center(2.7432),
|
||||
kBlueGoal_132in_Center(3.3528),
|
||||
kBlueGoal_156in_Center(3.9624),
|
||||
kBlueGoal_180in_Center(4.572),
|
||||
kBlueGoal_156in_Left(3.9624),
|
||||
kBlueGoal_224in_Left(5.6896),
|
||||
kBlueGoal_228in_ProtectedZone(5.7912),
|
||||
kBlueGoal_330in_ProtectedZone(8.382),
|
||||
kBlueGoal_Far_ProtectedZone(10.668), // TODO: find a more accurate distance
|
||||
kRedLoading_016in_Down(0.4064),
|
||||
kRedLoading_030in_Down(0.762),
|
||||
kRedLoading_048in_Down(1.2192),
|
||||
kRedLoading_048in(1.2192),
|
||||
kRedLoading_060in(1.524),
|
||||
kRedLoading_084in(2.1336),
|
||||
kRedLoading_108in(2.7432);
|
||||
|
||||
public static double FOV = 68.5;
|
||||
|
||||
public final double distanceMeters;
|
||||
public final Path path;
|
||||
|
||||
Path getPath() {
|
||||
var filename = this.toString().substring(1).replace('_', '-');
|
||||
return Path.of("2020", "WPI", filename + ".jpg");
|
||||
}
|
||||
|
||||
WPI2020Image(double distanceMeters) {
|
||||
this.distanceMeters = distanceMeters;
|
||||
this.path = getPath();
|
||||
}
|
||||
}
|
||||
|
||||
public enum PolygonTestImages {
|
||||
kPolygons;
|
||||
|
||||
public final Path path;
|
||||
|
||||
Path getPath() {
|
||||
var filename = this.toString().substring(1).toLowerCase();
|
||||
return Path.of("polygons", filename + ".png");
|
||||
}
|
||||
|
||||
PolygonTestImages() {
|
||||
this.path = getPath();
|
||||
}
|
||||
}
|
||||
|
||||
public enum PowercellTestImages {
|
||||
kPowercell_test_1,
|
||||
kPowercell_test_2,
|
||||
kPowercell_test_3,
|
||||
kPowercell_test_4,
|
||||
kPowercell_test_5,
|
||||
kPowercell_test_6;
|
||||
|
||||
public final Path path;
|
||||
|
||||
Path getPath() {
|
||||
var filename = this.toString().substring(1).toLowerCase();
|
||||
return Path.of(filename + ".png");
|
||||
}
|
||||
|
||||
PowercellTestImages() {
|
||||
this.path = getPath();
|
||||
}
|
||||
}
|
||||
|
||||
private static Path getResourcesFolderPath(boolean testMode) {
|
||||
return Path.of("src", (testMode ? "main" : "test"), "resources").toAbsolutePath();
|
||||
}
|
||||
|
||||
public static Path getTestMode2019ImagePath() {
|
||||
return getResourcesFolderPath(true)
|
||||
.resolve("testimages")
|
||||
.resolve(WPI2019Image.kRocketPanelAngleDark60in.path);
|
||||
}
|
||||
|
||||
public static Path getTestMode2020ImagePath() {
|
||||
return getResourcesFolderPath(true)
|
||||
.resolve("testimages")
|
||||
.resolve(WPI2020Image.kBlueGoal_108in_Center.path);
|
||||
}
|
||||
|
||||
public static Path getTestImagesPath(boolean testMode) {
|
||||
return getResourcesFolderPath(testMode).resolve("testimages");
|
||||
}
|
||||
|
||||
public static Path getCalibrationPath(boolean testMode) {
|
||||
return getResourcesFolderPath(testMode).resolve("calibration");
|
||||
}
|
||||
|
||||
public static Path getPowercellPath(boolean testMode) {
|
||||
return getTestImagesPath(testMode).resolve("polygons").resolve("powercells");
|
||||
}
|
||||
|
||||
public static Path getWPIImagePath(WPI2020Image image, boolean testMode) {
|
||||
return getTestImagesPath(testMode).resolve(image.path);
|
||||
}
|
||||
|
||||
public static Path getWPIImagePath(WPI2019Image image, boolean testMode) {
|
||||
return getTestImagesPath(testMode).resolve(image.path);
|
||||
}
|
||||
|
||||
public static Path getPolygonImagePath(PolygonTestImages image, boolean testMode) {
|
||||
return getTestImagesPath(testMode).resolve(image.path);
|
||||
}
|
||||
|
||||
public static Path getPowercellImagePath(PowercellTestImages image, boolean testMode) {
|
||||
return getPowercellPath(testMode).resolve(image.path);
|
||||
}
|
||||
|
||||
public static Path getDotBoardImagesPath() {
|
||||
return getResourcesFolderPath(false).resolve("calibrationBoardImages");
|
||||
}
|
||||
|
||||
public static Path getSquaresBoardImagesPath() {
|
||||
return getResourcesFolderPath(false).resolve("calibrationSquaresImg");
|
||||
}
|
||||
|
||||
public static File getHardwareConfigJson() {
|
||||
return getResourcesFolderPath(false)
|
||||
.resolve("hardware")
|
||||
.resolve("HardwareConfig.json")
|
||||
.toFile();
|
||||
}
|
||||
|
||||
private static final String LIFECAM_240P_CAL_FILE = "lifecam240p.json";
|
||||
private static final String LIFECAM_480P_CAL_FILE = "lifecam480p.json";
|
||||
|
||||
public static CameraCalibrationCoefficients getCoeffs(String filename, boolean testMode) {
|
||||
try {
|
||||
return new ObjectMapper()
|
||||
.readValue(
|
||||
(Path.of(getCalibrationPath(testMode).toString(), filename).toFile()),
|
||||
CameraCalibrationCoefficients.class);
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
return null;
|
||||
}
|
||||
}
|
||||
|
||||
public static CameraCalibrationCoefficients get2019LifeCamCoeffs(boolean testMode) {
|
||||
return getCoeffs(LIFECAM_240P_CAL_FILE, testMode);
|
||||
}
|
||||
|
||||
public static CameraCalibrationCoefficients get2020LifeCamCoeffs(boolean testMode) {
|
||||
return getCoeffs(LIFECAM_480P_CAL_FILE, testMode);
|
||||
}
|
||||
|
||||
public static void loadLibraries() {
|
||||
try {
|
||||
CameraServerCvJNI.forceLoad();
|
||||
} catch (IOException e) {
|
||||
// ignored
|
||||
}
|
||||
}
|
||||
|
||||
private static int DefaultTimeoutMillis = 5000;
|
||||
|
||||
public static void showImage(Mat frame, String title, int timeoutMs) {
|
||||
try {
|
||||
HighGui.imshow(title, frame);
|
||||
HighGui.waitKey(timeoutMs);
|
||||
HighGui.destroyAllWindows();
|
||||
} catch (HeadlessException ignored) {
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
public static void showImage(Mat frame, int timeoutMs) {
|
||||
showImage(frame, "", timeoutMs);
|
||||
}
|
||||
|
||||
public static void showImage(Mat frame, String title) {
|
||||
showImage(frame, title, DefaultTimeoutMillis);
|
||||
}
|
||||
|
||||
public static void showImage(Mat frame) {
|
||||
showImage(frame, DefaultTimeoutMillis);
|
||||
}
|
||||
}
|
||||
@@ -1,85 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util;
|
||||
|
||||
import java.util.concurrent.*;
|
||||
import org.jetbrains.annotations.NotNull;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class TimedTaskManager {
|
||||
|
||||
private static final Logger logger = new Logger(TimedTaskManager.class, LogGroup.General);
|
||||
|
||||
private static class Singleton {
|
||||
public static final TimedTaskManager INSTANCE = new TimedTaskManager();
|
||||
}
|
||||
|
||||
public static TimedTaskManager getInstance() {
|
||||
return Singleton.INSTANCE;
|
||||
}
|
||||
|
||||
private static class CaughtThreadFactory implements ThreadFactory {
|
||||
private static final ThreadFactory defaultThreadFactory = Executors.defaultThreadFactory();
|
||||
|
||||
@Override
|
||||
public Thread newThread(@NotNull Runnable r) {
|
||||
Thread thread = defaultThreadFactory.newThread(r);
|
||||
thread.setUncaughtExceptionHandler(
|
||||
(t, e) -> {
|
||||
logger.error("TimedTask threw uncaught exception!", e);
|
||||
});
|
||||
return thread;
|
||||
}
|
||||
}
|
||||
|
||||
private final ScheduledExecutorService timedTaskExecutorPool =
|
||||
new ScheduledThreadPoolExecutor(2, new CaughtThreadFactory());
|
||||
private final ConcurrentHashMap<String, Future<?>> activeTasks = new ConcurrentHashMap<>();
|
||||
|
||||
public void addTask(String identifier, Runnable runnable, long millisInterval) {
|
||||
if (!activeTasks.containsKey(identifier)) {
|
||||
var future =
|
||||
timedTaskExecutorPool.scheduleAtFixedRate(
|
||||
runnable, 0, millisInterval, TimeUnit.MILLISECONDS);
|
||||
activeTasks.put(identifier, future);
|
||||
}
|
||||
}
|
||||
|
||||
public void addTask(
|
||||
String identifier, Runnable runnable, long millisStartDelay, long millisInterval) {
|
||||
if (!activeTasks.containsKey(identifier)) {
|
||||
var future =
|
||||
timedTaskExecutorPool.scheduleAtFixedRate(
|
||||
runnable, millisStartDelay, millisInterval, TimeUnit.MILLISECONDS);
|
||||
activeTasks.put(identifier, future);
|
||||
}
|
||||
}
|
||||
|
||||
public void addOneShotTask(Runnable runnable, long millisStartDelay) {
|
||||
timedTaskExecutorPool.schedule(runnable, millisStartDelay, TimeUnit.MILLISECONDS);
|
||||
}
|
||||
|
||||
public void cancelTask(String identifier) {
|
||||
var future = activeTasks.getOrDefault(identifier, null);
|
||||
if (future != null) {
|
||||
future.cancel(true);
|
||||
activeTasks.remove(identifier);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,108 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.file;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Files;
|
||||
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;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class FileUtils {
|
||||
|
||||
private FileUtils() {}
|
||||
|
||||
private static Logger logger = new Logger(FileUtils.class, LogGroup.General);
|
||||
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 deleteFile(Path path) {
|
||||
try {
|
||||
Files.delete(path);
|
||||
} catch (IOException e) {
|
||||
logger.error("Exception deleting file " + path + "!", e);
|
||||
}
|
||||
}
|
||||
|
||||
public static void copyFile(Path src, Path dst) {
|
||||
try {
|
||||
Files.copy(src, dst);
|
||||
} catch (IOException e) {
|
||||
logger.error("Exception copying file " + src + " to " + dst + "!", e);
|
||||
}
|
||||
}
|
||||
|
||||
public static void setFilePerms(Path path) throws IOException {
|
||||
if (!Platform.CurrentPlatform.isWindows()) {
|
||||
File thisFile = path.toFile();
|
||||
Set<PosixFilePermission> perms =
|
||||
Files.readAttributes(path, PosixFileAttributes.class).permissions();
|
||||
if (!perms.equals(allReadWriteExecutePerms)) {
|
||||
logger.info("Setting perms on" + path.toString());
|
||||
Files.setPosixFilePermissions(path, perms);
|
||||
if (thisFile.isDirectory()) {
|
||||
for (File subfile : thisFile.listFiles()) {
|
||||
setFilePerms(subfile.toPath());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static void setAllPerms(Path path) {
|
||||
if (!Platform.CurrentPlatform.isWindows()) {
|
||||
String command = String.format("chmod 777 -R %s", path.toString());
|
||||
try {
|
||||
Process p = Runtime.getRuntime().exec(command);
|
||||
p.waitFor();
|
||||
|
||||
} catch (Exception e) {
|
||||
logger.error("Setting perms failed!", e);
|
||||
}
|
||||
} else {
|
||||
logger.info("Cannot set directory permissions on Windows!");
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,117 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
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;
|
||||
import com.fasterxml.jackson.databind.jsontype.BasicPolymorphicTypeValidator;
|
||||
import com.fasterxml.jackson.databind.jsontype.PolymorphicTypeValidator;
|
||||
import com.fasterxml.jackson.databind.module.SimpleModule;
|
||||
import com.fasterxml.jackson.databind.ser.std.StdSerializer;
|
||||
import java.io.File;
|
||||
import java.io.FileDescriptor;
|
||||
import java.io.FileOutputStream;
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Path;
|
||||
|
||||
public class JacksonUtils {
|
||||
public static <T> void serialize(Path path, T object) throws IOException {
|
||||
serialize(path, object, false);
|
||||
}
|
||||
|
||||
public static <T> void serialize(Path path, T object, boolean forceSync) throws IOException {
|
||||
PolymorphicTypeValidator ptv =
|
||||
BasicPolymorphicTypeValidator.builder().allowIfBaseType(object.getClass()).build();
|
||||
ObjectMapper objectMapper =
|
||||
JsonMapper.builder()
|
||||
.activateDefaultTyping(ptv, ObjectMapper.DefaultTyping.JAVA_LANG_OBJECT)
|
||||
.build();
|
||||
String json = objectMapper.writerWithDefaultPrettyPrinter().writeValueAsString(object);
|
||||
saveJsonString(json, path, forceSync);
|
||||
}
|
||||
|
||||
public static <T> T deserialize(Path path, Class<T> ref) throws IOException {
|
||||
PolymorphicTypeValidator ptv =
|
||||
BasicPolymorphicTypeValidator.builder().allowIfBaseType(ref).build();
|
||||
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());
|
||||
if (jsonFile.exists() && jsonFile.length() > 0) {
|
||||
return objectMapper.readValue(jsonFile, ref);
|
||||
}
|
||||
return null;
|
||||
}
|
||||
|
||||
public static <T> T deserialize(Path path, Class<T> ref, StdDeserializer<T> deserializer)
|
||||
throws IOException {
|
||||
ObjectMapper objectMapper = new ObjectMapper();
|
||||
SimpleModule module = new SimpleModule();
|
||||
module.addDeserializer(ref, deserializer);
|
||||
objectMapper.registerModule(module);
|
||||
|
||||
File jsonFile = new File(path.toString());
|
||||
if (jsonFile.exists() && jsonFile.length() > 0) {
|
||||
return objectMapper.readValue(jsonFile, ref);
|
||||
}
|
||||
return null;
|
||||
}
|
||||
|
||||
public static <T> void serialize(Path path, T object, Class<T> ref, StdSerializer<T> serializer)
|
||||
throws IOException {
|
||||
serialize(path, object, ref, serializer, false);
|
||||
}
|
||||
|
||||
public static <T> void serialize(
|
||||
Path path, T object, Class<T> ref, StdSerializer<T> serializer, boolean forceSync)
|
||||
throws IOException {
|
||||
ObjectMapper objectMapper = new ObjectMapper();
|
||||
SimpleModule module = new SimpleModule();
|
||||
module.addSerializer(ref, serializer);
|
||||
objectMapper.registerModule(module);
|
||||
String json = objectMapper.writerWithDefaultPrettyPrinter().writeValueAsString(object);
|
||||
saveJsonString(json, path, forceSync);
|
||||
}
|
||||
|
||||
private static void saveJsonString(String json, Path path, boolean forceSync) throws IOException {
|
||||
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) {
|
||||
FileDescriptor fileDescriptor = fileOutputStream.getFD();
|
||||
fileDescriptor.sync();
|
||||
}
|
||||
fileOutputStream.close();
|
||||
}
|
||||
}
|
||||
@@ -1,22 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.java;
|
||||
|
||||
public interface TriConsumer<T, U, V> {
|
||||
void accept(T t, U u, V v);
|
||||
}
|
||||
@@ -1,56 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.math;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
public class IPUtils {
|
||||
public static boolean isValidIPV4(final String ip) {
|
||||
String PATTERN =
|
||||
"^((0|1\\d?\\d?|2[0-4]?\\d?|25[0-5]?|[3-9]\\d?)\\.){3}(0|1\\d?\\d?|2[0-4]?\\d?|25[0-5]?|[3-9]\\d?)$";
|
||||
|
||||
return ip.matches(PATTERN);
|
||||
}
|
||||
|
||||
public static List<Byte> getDigitBytes(int num) {
|
||||
List<Byte> digits = new ArrayList<>();
|
||||
collectDigitBytes(num, digits);
|
||||
return digits;
|
||||
}
|
||||
|
||||
private static void collectDigitBytes(int num, List<Byte> digits) {
|
||||
if (num / 10 > 0) {
|
||||
collectDigitBytes(num / 10, digits);
|
||||
}
|
||||
digits.add((byte) (num % 10));
|
||||
}
|
||||
|
||||
public static List<Integer> getDigits(int num) {
|
||||
List<Integer> digits = new ArrayList<>();
|
||||
collectDigits(num, digits);
|
||||
return digits;
|
||||
}
|
||||
|
||||
private static void collectDigits(int num, List<Integer> digits) {
|
||||
if (num / 10 > 0) {
|
||||
collectDigits(num / 10, digits);
|
||||
}
|
||||
digits.add(num % 10);
|
||||
}
|
||||
}
|
||||
@@ -1,62 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.math;
|
||||
|
||||
import org.apache.commons.math3.util.FastMath;
|
||||
|
||||
public class MathUtils {
|
||||
MathUtils() {}
|
||||
|
||||
public static double toSlope(Number angle) {
|
||||
return FastMath.atan(FastMath.toRadians(angle.doubleValue() - 90));
|
||||
}
|
||||
|
||||
public static int safeDivide(int quotient, int divisor) {
|
||||
if (divisor == 0) {
|
||||
return 0;
|
||||
} else {
|
||||
return quotient / divisor;
|
||||
}
|
||||
}
|
||||
|
||||
public static double roundTo(double value, int to) {
|
||||
double toMult = Math.pow(10, to);
|
||||
return (double) Math.round(value * toMult) / toMult;
|
||||
}
|
||||
|
||||
public static double nanosToMillis(long nanos) {
|
||||
return nanos / 1000000.0;
|
||||
}
|
||||
|
||||
public static long millisToNanos(long millis) {
|
||||
return millis * 1000000;
|
||||
}
|
||||
|
||||
public static long microsToNanos(long micros) {
|
||||
return micros * 1000;
|
||||
}
|
||||
|
||||
public static double map(
|
||||
double value, double in_min, double in_max, double out_min, double out_max) {
|
||||
return (value - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
public static int map(int value, int inMin, int inMax, int outMin, int outMax) {
|
||||
return (int) Math.floor(map((double) value, inMin, inMax, outMin, outMax) + 0.5);
|
||||
}
|
||||
}
|
||||
@@ -1,48 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.numbers;
|
||||
|
||||
import org.opencv.core.Point;
|
||||
|
||||
public class DoubleCouple extends NumberCouple<Double> {
|
||||
|
||||
public DoubleCouple() {
|
||||
super(0.0, 0.0);
|
||||
}
|
||||
|
||||
public DoubleCouple(Number first, Number second) {
|
||||
super(first.doubleValue(), second.doubleValue());
|
||||
}
|
||||
|
||||
public DoubleCouple(Double first, Double second) {
|
||||
super(first, second);
|
||||
}
|
||||
|
||||
public DoubleCouple(Point point) {
|
||||
super(point.x, point.y);
|
||||
}
|
||||
|
||||
public Point toPoint() {
|
||||
return new Point(first, second);
|
||||
}
|
||||
|
||||
public void fromPoint(Point point) {
|
||||
first = point.x;
|
||||
second = point.y;
|
||||
}
|
||||
}
|
||||
@@ -1,29 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.numbers;
|
||||
|
||||
public class IntegerCouple extends NumberCouple<Integer> {
|
||||
|
||||
public IntegerCouple() {
|
||||
super(0, 0);
|
||||
}
|
||||
|
||||
public IntegerCouple(Integer first, Integer second) {
|
||||
super(first, second);
|
||||
}
|
||||
}
|
||||
@@ -1,75 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.numbers;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonIgnore;
|
||||
|
||||
public abstract class NumberCouple<T extends Number> {
|
||||
|
||||
protected T first;
|
||||
protected T second;
|
||||
|
||||
public NumberCouple(T first, T second) {
|
||||
this.first = first;
|
||||
this.second = second;
|
||||
}
|
||||
|
||||
public void setFirst(T first) {
|
||||
this.first = first;
|
||||
}
|
||||
|
||||
public T getFirst() {
|
||||
return first;
|
||||
}
|
||||
|
||||
public void setSecond(T second) {
|
||||
this.second = second;
|
||||
}
|
||||
|
||||
public T getSecond() {
|
||||
return second;
|
||||
}
|
||||
|
||||
public void set(T first, T second) {
|
||||
this.first = first;
|
||||
this.second = second;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object obj) {
|
||||
if (!(obj instanceof NumberCouple)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
var couple = (NumberCouple) obj;
|
||||
if (!couple.first.equals(first)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!couple.second.equals(second)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public boolean isEmpty() {
|
||||
return first.intValue() == 0 && second.intValue() == 0;
|
||||
}
|
||||
}
|
||||
@@ -1,115 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.util.numbers;
|
||||
|
||||
import java.math.BigDecimal;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Comparator;
|
||||
import java.util.List;
|
||||
import java.util.StringJoiner;
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
public class NumberListUtils {
|
||||
|
||||
/**
|
||||
* @param collection an ArrayList of Comparable objects
|
||||
* @return the median of collection
|
||||
*/
|
||||
public static <T extends Number> double median(List<T> collection, Comparator<T> comp) {
|
||||
double result;
|
||||
int n = collection.size() / 2;
|
||||
|
||||
if (collection.size() % 2 == 0) // even number of items; find the middle two and average them
|
||||
result =
|
||||
(nthSmallest(collection, n - 1, comp).doubleValue()
|
||||
+ nthSmallest(collection, n, comp).doubleValue())
|
||||
/ 2.0;
|
||||
else // odd number of items; return the one in the middle
|
||||
result = nthSmallest(collection, n, comp).doubleValue();
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
public static <T extends Number> String toString(List<T> collection) {
|
||||
return toString(collection, "");
|
||||
}
|
||||
|
||||
public static <T extends Number> String toString(List<T> collection, String suffix) {
|
||||
StringJoiner joiner = new StringJoiner(", ");
|
||||
for (T x : collection) {
|
||||
String s = x.doubleValue() + suffix;
|
||||
joiner.add(s);
|
||||
}
|
||||
return joiner.toString();
|
||||
}
|
||||
|
||||
/**
|
||||
* @param collection an ArrayList of Numbers
|
||||
* @return the mean of collection
|
||||
*/
|
||||
public static double mean(final List<? extends Number> collection) {
|
||||
BigDecimal sum = BigDecimal.ZERO;
|
||||
for (final Number number : collection) {
|
||||
sum = sum.add(BigDecimal.valueOf(number.doubleValue()));
|
||||
}
|
||||
return (sum.doubleValue() / collection.size());
|
||||
}
|
||||
|
||||
/**
|
||||
* @param collection a collection of Comparable objects
|
||||
* @param n the position of the desired object, using the ordering defined on the collection
|
||||
* elements
|
||||
* @return the nth smallest object
|
||||
*/
|
||||
public static <T> T nthSmallest(List<T> collection, int n, Comparator<T> comp) {
|
||||
T result, pivot;
|
||||
ArrayList<T> underPivot = new ArrayList<>(),
|
||||
overPivot = new ArrayList<>(),
|
||||
equalPivot = new ArrayList<>();
|
||||
|
||||
// choosing a pivot is a whole topic in itself.
|
||||
// this implementation uses the simple strategy of grabbing something from the middle of the
|
||||
// ArrayList.
|
||||
|
||||
pivot = collection.get(n / 2);
|
||||
|
||||
// split collection into 3 lists based on comparison with the pivot
|
||||
|
||||
for (T obj : collection) {
|
||||
int order = comp.compare(obj, pivot);
|
||||
|
||||
if (order < 0) // obj < pivot
|
||||
underPivot.add(obj);
|
||||
else if (order > 0) // obj > pivot
|
||||
overPivot.add(obj);
|
||||
else // obj = pivot
|
||||
equalPivot.add(obj);
|
||||
} // for each obj in collection
|
||||
|
||||
// recurse on the appropriate collection
|
||||
|
||||
if (n < underPivot.size()) result = nthSmallest(underPivot, n, comp);
|
||||
else if (n < underPivot.size() + equalPivot.size()) // equal to pivot; just return it
|
||||
result = pivot;
|
||||
else // everything in underPivot and equalPivot is too small. Adjust n accordingly in the
|
||||
// recursion.
|
||||
result = nthSmallest(overPivot, n - underPivot.size() - equalPivot.size(), comp);
|
||||
|
||||
return result;
|
||||
}
|
||||
}
|
||||
@@ -1,141 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.raspi;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import java.io.InputStream;
|
||||
import java.net.URL;
|
||||
import java.nio.file.Files;
|
||||
import java.nio.file.Path;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class PicamJNI {
|
||||
|
||||
private static boolean libraryLoaded = false;
|
||||
private static Logger logger = new Logger(PicamJNI.class, LogGroup.Camera);
|
||||
|
||||
public enum SensorModel {
|
||||
Disconnected,
|
||||
OV5647, // Picam v1
|
||||
IMX219, // Picam v2
|
||||
IMX477, // Picam HQ
|
||||
Unknown;
|
||||
|
||||
public String getFriendlyName() {
|
||||
switch (this) {
|
||||
case Disconnected:
|
||||
return "Disconnected Camera";
|
||||
case OV5647:
|
||||
return "Camera Module v1";
|
||||
case IMX219:
|
||||
return "Camera Module v2";
|
||||
case IMX477:
|
||||
return "HQ Camera";
|
||||
case Unknown:
|
||||
default:
|
||||
return "Unknown Camera";
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static synchronized void forceLoad() throws IOException {
|
||||
if (libraryLoaded || !Platform.isRaspberryPi()) return;
|
||||
|
||||
try {
|
||||
File libDirectory = Path.of("lib/").toFile();
|
||||
if (!libDirectory.exists()) {
|
||||
Files.createDirectory(libDirectory.toPath()).toFile();
|
||||
}
|
||||
|
||||
// We always extract the shared object (we could hash each so, but that's a lot of work)
|
||||
URL resourceURL = PicamJNI.class.getResource("/nativelibraries/libpicam.so");
|
||||
File libFile = Path.of("lib/libpicam.so").toFile();
|
||||
try (InputStream in = resourceURL.openStream()) {
|
||||
if (libFile.exists()) Files.delete(libFile.toPath());
|
||||
Files.copy(in, libFile.toPath());
|
||||
} catch (Exception e) {
|
||||
logger.error("Could not extract the native library!");
|
||||
}
|
||||
System.load(libFile.getAbsolutePath());
|
||||
|
||||
libraryLoaded = true;
|
||||
logger.info("Successfully loaded libpicam shared object");
|
||||
} catch (UnsatisfiedLinkError e) {
|
||||
logger.error("Couldn't load libpicam shared object");
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
|
||||
public static boolean isSupported() {
|
||||
return libraryLoaded && getSensorModel() != SensorModel.Disconnected;
|
||||
}
|
||||
|
||||
public static SensorModel getSensorModel() {
|
||||
switch (getSensorModelRaw().toLowerCase()) {
|
||||
case "":
|
||||
return SensorModel.Disconnected;
|
||||
case "ov5647":
|
||||
return SensorModel.OV5647;
|
||||
case "imx219":
|
||||
return SensorModel.IMX219;
|
||||
case "imx477":
|
||||
return SensorModel.IMX477;
|
||||
default:
|
||||
return SensorModel.Unknown;
|
||||
}
|
||||
}
|
||||
|
||||
private static native String getSensorModelRaw();
|
||||
|
||||
// Everything here is static because multiple picams are unsupported at the hardware level
|
||||
|
||||
/**
|
||||
* Called once for each video mode change. Starts a native thread running MMAL that stays alive
|
||||
* until destroyCamera is called.
|
||||
*
|
||||
* @return true on error.
|
||||
*/
|
||||
public static native boolean createCamera(int width, int height, int fps);
|
||||
|
||||
/**
|
||||
* Destroys MMAL and EGL contexts. Called once for each video mode change *before* createCamera.
|
||||
*
|
||||
* @return true on error.
|
||||
*/
|
||||
public static native boolean destroyCamera();
|
||||
|
||||
public static native void setThresholds(
|
||||
double hL, double sL, double vL, double hU, double sU, double vU);
|
||||
|
||||
public static native boolean setExposure(int exposure);
|
||||
|
||||
public static native boolean setBrightness(int brightness);
|
||||
|
||||
public static native boolean setGain(int gain);
|
||||
|
||||
public static native boolean setRotation(int rotation);
|
||||
|
||||
public static native void setShouldCopyColor(boolean shouldCopyColor);
|
||||
|
||||
public static native long getFrameLatency();
|
||||
|
||||
public static native long grabFrame(boolean shouldReturnColor);
|
||||
}
|
||||
@@ -1,83 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.calibration;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonCreator;
|
||||
import com.fasterxml.jackson.annotation.JsonIgnore;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.MatOfDouble;
|
||||
import org.opencv.core.Size;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
|
||||
public class CameraCalibrationCoefficients implements Releasable {
|
||||
@JsonProperty("resolution")
|
||||
public final Size resolution;
|
||||
|
||||
@JsonProperty("cameraIntrinsics")
|
||||
public final JsonMat cameraIntrinsics;
|
||||
|
||||
@JsonProperty("cameraExtrinsics")
|
||||
public final JsonMat cameraExtrinsics;
|
||||
|
||||
@JsonProperty("perViewErrors")
|
||||
public final double[] perViewErrors;
|
||||
|
||||
@JsonProperty("standardDeviation")
|
||||
public final double standardDeviation;
|
||||
|
||||
@JsonCreator
|
||||
public CameraCalibrationCoefficients(
|
||||
@JsonProperty("resolution") Size resolution,
|
||||
@JsonProperty("cameraIntrinsics") JsonMat cameraIntrinsics,
|
||||
@JsonProperty("cameraExtrinsics") JsonMat cameraExtrinsics,
|
||||
@JsonProperty("perViewErrors") double[] perViewErrors,
|
||||
@JsonProperty("standardDeviation") double standardDeviation) {
|
||||
this.resolution = resolution;
|
||||
this.cameraIntrinsics = cameraIntrinsics;
|
||||
this.cameraExtrinsics = cameraExtrinsics;
|
||||
this.perViewErrors = perViewErrors;
|
||||
this.standardDeviation = standardDeviation;
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public Mat getCameraIntrinsicsMat() {
|
||||
return cameraIntrinsics.getAsMat();
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public MatOfDouble getCameraExtrinsicsMat() {
|
||||
return cameraExtrinsics.getAsMatOfDouble();
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public double[] getPerViewErrors() {
|
||||
return perViewErrors;
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public double getStandardDeviation() {
|
||||
return standardDeviation;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
cameraIntrinsics.release();
|
||||
cameraExtrinsics.release();
|
||||
}
|
||||
}
|
||||
@@ -1,109 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.calibration;
|
||||
|
||||
import com.fasterxml.jackson.annotation.JsonIgnore;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import java.util.Arrays;
|
||||
import org.opencv.core.CvType;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.MatOfDouble;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
|
||||
public class JsonMat implements Releasable {
|
||||
public final int rows;
|
||||
public final int cols;
|
||||
public final int type;
|
||||
public final double[] data;
|
||||
|
||||
@JsonIgnore private Mat wrappedMat;
|
||||
private MatOfDouble wrappedMatOfDouble;
|
||||
|
||||
public JsonMat(int rows, int cols, double[] data) {
|
||||
this(rows, cols, CvType.CV_64FC1, data);
|
||||
}
|
||||
|
||||
public JsonMat(
|
||||
@JsonProperty("rows") int rows,
|
||||
@JsonProperty("cols") int cols,
|
||||
@JsonProperty("type") int type,
|
||||
@JsonProperty("data") double[] data) {
|
||||
this.rows = rows;
|
||||
this.cols = cols;
|
||||
this.type = type;
|
||||
this.data = data;
|
||||
}
|
||||
|
||||
private static boolean isCameraMatrixMat(Mat mat) {
|
||||
return mat.type() == CvType.CV_64FC1 && mat.cols() == 3 && mat.rows() == 3;
|
||||
}
|
||||
|
||||
private static boolean isDistortionCoeffsMat(Mat mat) {
|
||||
return mat.type() == CvType.CV_64FC1 && mat.cols() == 5 && mat.rows() == 1;
|
||||
}
|
||||
|
||||
private static boolean isCalibrationMat(Mat mat) {
|
||||
return isDistortionCoeffsMat(mat) || isCameraMatrixMat(mat);
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public static double[] getDataFromMat(Mat mat) {
|
||||
if (!isCalibrationMat(mat)) return null;
|
||||
|
||||
double[] data = new double[(int) (mat.total() * mat.elemSize())];
|
||||
mat.get(0, 0, data);
|
||||
|
||||
int dataLen = -1;
|
||||
|
||||
if (isCameraMatrixMat(mat)) dataLen = 9;
|
||||
if (isDistortionCoeffsMat(mat)) dataLen = 5;
|
||||
|
||||
// truncate Mat data to correct number data points.
|
||||
return Arrays.copyOfRange(data, 0, dataLen);
|
||||
}
|
||||
|
||||
public static JsonMat fromMat(Mat mat) {
|
||||
if (!isCalibrationMat(mat)) return null;
|
||||
return new JsonMat(mat.rows(), mat.cols(), getDataFromMat(mat));
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public Mat getAsMat() {
|
||||
if (this.type != CvType.CV_64FC1) return null;
|
||||
|
||||
if (wrappedMat == null) {
|
||||
this.wrappedMat = new Mat(this.rows, this.cols, this.type);
|
||||
this.wrappedMat.put(0, 0, this.data);
|
||||
}
|
||||
return this.wrappedMat;
|
||||
}
|
||||
|
||||
@JsonIgnore
|
||||
public MatOfDouble getAsMatOfDouble() {
|
||||
if (this.wrappedMatOfDouble == null) {
|
||||
this.wrappedMatOfDouble = new MatOfDouble();
|
||||
getAsMat().convertTo(wrappedMatOfDouble, CvType.CV_64F);
|
||||
}
|
||||
return this.wrappedMatOfDouble;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
getAsMat().release();
|
||||
}
|
||||
}
|
||||
@@ -1,27 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.camera;
|
||||
|
||||
public enum CameraQuirk {
|
||||
/** Camera settable for controllable image gain */
|
||||
Gain,
|
||||
/** For the Raspberry Pi Camera */
|
||||
PiCam,
|
||||
/** Cap at 100FPS for high-bandwidth cameras */
|
||||
FPSCap100
|
||||
}
|
||||
@@ -1,24 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.camera;
|
||||
|
||||
public enum CameraType {
|
||||
UsbCamera,
|
||||
HttpCamera,
|
||||
ZeroCopyPicam
|
||||
}
|
||||
@@ -1,115 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.camera;
|
||||
|
||||
import edu.wpi.cscore.VideoMode;
|
||||
import edu.wpi.cscore.VideoMode.PixelFormat;
|
||||
import java.nio.file.Path;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
import org.photonvision.vision.frame.FrameStaticProperties;
|
||||
import org.photonvision.vision.frame.provider.FileFrameProvider;
|
||||
import org.photonvision.vision.processes.VisionSource;
|
||||
import org.photonvision.vision.processes.VisionSourceSettables;
|
||||
|
||||
public class FileVisionSource implements VisionSource {
|
||||
|
||||
private final CameraConfiguration cameraConfiguration;
|
||||
private final FileFrameProvider frameProvider;
|
||||
private final FileSourceSettables settables;
|
||||
|
||||
public FileVisionSource(CameraConfiguration cameraConfiguration) {
|
||||
this.cameraConfiguration = cameraConfiguration;
|
||||
frameProvider =
|
||||
new FileFrameProvider(
|
||||
Path.of(cameraConfiguration.path),
|
||||
cameraConfiguration.FOV,
|
||||
FileFrameProvider.MAX_FPS,
|
||||
cameraConfiguration.camPitch,
|
||||
cameraConfiguration.calibrations.get(0));
|
||||
settables =
|
||||
new FileSourceSettables(cameraConfiguration, frameProvider.get().frameStaticProperties);
|
||||
}
|
||||
|
||||
public FileVisionSource(String name, String imagePath, double fov) {
|
||||
cameraConfiguration = new CameraConfiguration(name, imagePath);
|
||||
frameProvider = new FileFrameProvider(imagePath, fov);
|
||||
settables =
|
||||
new FileSourceSettables(cameraConfiguration, frameProvider.get().frameStaticProperties);
|
||||
}
|
||||
|
||||
@Override
|
||||
public FrameProvider getFrameProvider() {
|
||||
return frameProvider;
|
||||
}
|
||||
|
||||
@Override
|
||||
public VisionSourceSettables getSettables() {
|
||||
return settables;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isVendorCamera() {
|
||||
return false;
|
||||
}
|
||||
|
||||
private static class FileSourceSettables extends VisionSourceSettables {
|
||||
|
||||
private final VideoMode videoMode;
|
||||
|
||||
private final HashMap<Integer, VideoMode> videoModes = new HashMap<>();
|
||||
|
||||
FileSourceSettables(
|
||||
CameraConfiguration cameraConfiguration, FrameStaticProperties frameStaticProperties) {
|
||||
super(cameraConfiguration);
|
||||
this.frameStaticProperties = frameStaticProperties;
|
||||
videoMode =
|
||||
new VideoMode(
|
||||
PixelFormat.kMJPEG,
|
||||
frameStaticProperties.imageWidth,
|
||||
frameStaticProperties.imageHeight,
|
||||
30);
|
||||
videoModes.put(0, videoMode);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setExposure(double exposure) {}
|
||||
|
||||
@Override
|
||||
public void setBrightness(int brightness) {}
|
||||
|
||||
@Override
|
||||
public void setGain(int gain) {}
|
||||
|
||||
@Override
|
||||
public VideoMode getCurrentVideoMode() {
|
||||
return videoMode;
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void setVideoModeInternal(VideoMode videoMode) {
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
@Override
|
||||
public HashMap<Integer, VideoMode> getAllVideoModes() {
|
||||
return videoModes;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,117 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.camera;
|
||||
|
||||
import java.util.HashMap;
|
||||
import java.util.List;
|
||||
import java.util.Objects;
|
||||
|
||||
public class QuirkyCamera {
|
||||
|
||||
private static final List<QuirkyCamera> quirkyCameras =
|
||||
List.of(
|
||||
new QuirkyCamera(0x2000, 0x1415, CameraQuirk.Gain, CameraQuirk.FPSCap100), // PS3Eye
|
||||
new QuirkyCamera(-1, -1, "mmal service 16.1", CameraQuirk.PiCam) // PiCam (via V4L2)
|
||||
);
|
||||
|
||||
public static final QuirkyCamera DefaultCamera = new QuirkyCamera(0, 0, "");
|
||||
public static final QuirkyCamera ZeroCopyPiCamera =
|
||||
new QuirkyCamera(
|
||||
-1,
|
||||
-1,
|
||||
"mmal service 16.1",
|
||||
CameraQuirk.PiCam,
|
||||
CameraQuirk.Gain); // PiCam (special zerocopy version)
|
||||
|
||||
public final String baseName;
|
||||
public final int usbVid;
|
||||
public final int usbPid;
|
||||
public final HashMap<CameraQuirk, Boolean> quirks;
|
||||
|
||||
/**
|
||||
* Creates a QuirkyCamera that matches by USB VID/PID
|
||||
*
|
||||
* @param usbVid USB VID of camera
|
||||
* @param usbPid USB PID of camera
|
||||
* @param quirks Camera quirks
|
||||
*/
|
||||
private QuirkyCamera(int usbVid, int usbPid, CameraQuirk... quirks) {
|
||||
this(usbVid, usbPid, "", quirks);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a QuirkyCamera that matches by USB VID/PID and name
|
||||
*
|
||||
* @param usbVid USB VID of camera
|
||||
* @param usbPid USB PID of camera
|
||||
* @param baseName CSCore name of camera
|
||||
* @param quirks Camera quirks
|
||||
*/
|
||||
private QuirkyCamera(int usbVid, int usbPid, String baseName, CameraQuirk... quirks) {
|
||||
this.usbVid = usbVid;
|
||||
this.usbPid = usbPid;
|
||||
this.baseName = baseName;
|
||||
|
||||
this.quirks = new HashMap<>();
|
||||
for (var q : quirks) {
|
||||
this.quirks.put(q, true);
|
||||
}
|
||||
for (var q : CameraQuirk.values()) {
|
||||
this.quirks.putIfAbsent(q, false);
|
||||
}
|
||||
}
|
||||
|
||||
public boolean hasQuirk(CameraQuirk quirk) {
|
||||
return quirks.get(quirk);
|
||||
}
|
||||
|
||||
public static QuirkyCamera getQuirkyCamera(int usbVid, int usbPid) {
|
||||
return getQuirkyCamera(usbVid, usbPid, "");
|
||||
}
|
||||
|
||||
public static QuirkyCamera getQuirkyCamera(int usbVid, int usbPid, String baseName) {
|
||||
for (var qc : quirkyCameras) {
|
||||
boolean hasBaseName = !qc.baseName.equals("");
|
||||
boolean matchesBaseName = qc.baseName.equals(baseName) || !hasBaseName;
|
||||
if (qc.usbVid == usbVid && qc.usbPid == usbPid && matchesBaseName) {
|
||||
return qc;
|
||||
}
|
||||
}
|
||||
return new QuirkyCamera(usbVid, usbPid, baseName);
|
||||
}
|
||||
|
||||
public boolean hasQuirks() {
|
||||
return quirks.containsValue(true);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
if (this == o) return true;
|
||||
if (o == null || getClass() != o.getClass()) return false;
|
||||
QuirkyCamera that = (QuirkyCamera) o;
|
||||
return usbVid == that.usbVid
|
||||
&& usbPid == that.usbPid
|
||||
&& Objects.equals(baseName, that.baseName)
|
||||
&& Objects.equals(quirks, that.quirks);
|
||||
}
|
||||
|
||||
@Override
|
||||
public int hashCode() {
|
||||
return Objects.hash(usbVid, usbPid, baseName, quirks);
|
||||
}
|
||||
}
|
||||
@@ -1,286 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.camera;
|
||||
|
||||
import edu.wpi.cscore.CvSink;
|
||||
import edu.wpi.cscore.UsbCamera;
|
||||
import edu.wpi.cscore.VideoException;
|
||||
import edu.wpi.cscore.VideoMode;
|
||||
import edu.wpi.first.cameraserver.CameraServer;
|
||||
import java.util.*;
|
||||
import java.util.stream.Collectors;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
import org.photonvision.vision.frame.provider.USBFrameProvider;
|
||||
import org.photonvision.vision.processes.VisionSource;
|
||||
import org.photonvision.vision.processes.VisionSourceSettables;
|
||||
|
||||
public class USBCameraSource implements VisionSource {
|
||||
private final Logger logger;
|
||||
private final UsbCamera camera;
|
||||
private final USBCameraSettables usbCameraSettables;
|
||||
private final USBFrameProvider usbFrameProvider;
|
||||
public final CameraConfiguration configuration;
|
||||
private final CvSink cvSink;
|
||||
|
||||
public final QuirkyCamera cameraQuirks;
|
||||
|
||||
public USBCameraSource(CameraConfiguration config) {
|
||||
logger = new Logger(USBCameraSource.class, config.nickname, LogGroup.Camera);
|
||||
configuration = config;
|
||||
camera = new UsbCamera(config.nickname, config.path);
|
||||
cvSink = CameraServer.getInstance().getVideo(this.camera);
|
||||
|
||||
cameraQuirks =
|
||||
QuirkyCamera.getQuirkyCamera(
|
||||
camera.getInfo().productId, camera.getInfo().vendorId, config.baseName);
|
||||
|
||||
if (cameraQuirks.hasQuirks()) {
|
||||
logger.info("Quirky camera detected: " + cameraQuirks.baseName);
|
||||
}
|
||||
|
||||
usbCameraSettables = new USBCameraSettables(config);
|
||||
usbFrameProvider = new USBFrameProvider(cvSink, usbCameraSettables);
|
||||
|
||||
if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) {
|
||||
// Pick a bunch of reasonable setting defaults for vision processing.
|
||||
camera.getProperty("exposure_dynamic_framerate").set(0);
|
||||
camera.getProperty("auto_exposure_bias").set(0);
|
||||
camera.getProperty("image_stabilization").set(0);
|
||||
camera.getProperty("iso_sensitivity").set(0);
|
||||
camera.getProperty("iso_sensitivity_auto").set(0);
|
||||
camera.getProperty("exposure_metering_mode").set(0);
|
||||
camera.getProperty("scene_mode").set(0);
|
||||
camera.getProperty("power_line_frequency").set(2);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public FrameProvider getFrameProvider() {
|
||||
return usbFrameProvider;
|
||||
}
|
||||
|
||||
@Override
|
||||
public VisionSourceSettables getSettables() {
|
||||
return this.usbCameraSettables;
|
||||
}
|
||||
|
||||
public class USBCameraSettables extends VisionSourceSettables {
|
||||
protected USBCameraSettables(CameraConfiguration configuration) {
|
||||
super(configuration);
|
||||
getAllVideoModes();
|
||||
setVideoMode(videoModes.get(0));
|
||||
calculateFrameStaticProps();
|
||||
}
|
||||
|
||||
private int timeToPiCamV2RawExposure(double time_us) {
|
||||
int retVal =
|
||||
(int) Math.round(time_us / 100.0); // PiCamV2 needs exposure time in units of 100us/bit
|
||||
return Math.min(Math.max(retVal, 1), 10000); // Cap to allowable range for parameter
|
||||
}
|
||||
|
||||
private double pctToExposureTimeUs(double pct_in) {
|
||||
// Mirror the photonvision raspicam driver's algorithm for picking an exposure time
|
||||
// from a 0-100% input
|
||||
final double PADDING_LOW_US = 100;
|
||||
final double PADDING_HIGH_US = 200;
|
||||
return PADDING_LOW_US
|
||||
+ (pct_in / 100.0) * ((1e6 / (double) camera.getVideoMode().fps) - PADDING_HIGH_US);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setExposure(double exposure) {
|
||||
try {
|
||||
int scaledExposure = 1;
|
||||
if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) {
|
||||
camera.getProperty("white_balance_auto_preset").set(2); // Auto white-balance off
|
||||
camera.getProperty("auto_exposure").set(1); // auto exposure off
|
||||
|
||||
scaledExposure =
|
||||
(int) Math.round(timeToPiCamV2RawExposure(pctToExposureTimeUs(exposure)));
|
||||
logger.debug("Setting camera raw exposure to " + Integer.toString(scaledExposure));
|
||||
camera.getProperty("raw_exposure_time_absolute").set(scaledExposure);
|
||||
camera.getProperty("raw_exposure_time_absolute").set(scaledExposure);
|
||||
|
||||
} else {
|
||||
scaledExposure = (int) Math.round(exposure);
|
||||
logger.debug("Setting camera exposure to " + Integer.toString(scaledExposure));
|
||||
camera.setExposureManual(scaledExposure);
|
||||
camera.setExposureManual(scaledExposure);
|
||||
}
|
||||
} catch (VideoException e) {
|
||||
logger.error("Failed to set camera exposure!", e);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setBrightness(int brightness) {
|
||||
try {
|
||||
camera.setBrightness(brightness);
|
||||
camera.setBrightness(brightness);
|
||||
} catch (VideoException e) {
|
||||
logger.error("Failed to set camera brightness!", e);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setGain(int gain) {
|
||||
try {
|
||||
if (cameraQuirks.hasQuirk(CameraQuirk.Gain)) {
|
||||
camera.getProperty("gain_automatic").set(0);
|
||||
camera.getProperty("gain").set(gain);
|
||||
}
|
||||
} catch (VideoException e) {
|
||||
logger.error("Failed to set camera gain!", e);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public VideoMode getCurrentVideoMode() {
|
||||
return camera.isConnected() ? camera.getVideoMode() : null;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setVideoModeInternal(VideoMode videoMode) {
|
||||
try {
|
||||
if (videoMode == null) {
|
||||
logger.error("Got a null video mode! Doing nothing...");
|
||||
return;
|
||||
}
|
||||
camera.setVideoMode(videoMode);
|
||||
} catch (Exception e) {
|
||||
logger.error("Failed to set video mode!", e);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public HashMap<Integer, VideoMode> getAllVideoModes() {
|
||||
if (videoModes == null) {
|
||||
videoModes = new HashMap<>();
|
||||
List<VideoMode> videoModesList = new ArrayList<>();
|
||||
try {
|
||||
var modes = camera.enumerateVideoModes();
|
||||
for (int i = 0; i < modes.length; i++) {
|
||||
var videoMode = modes[i];
|
||||
|
||||
// Filter grey modes
|
||||
if (videoMode.pixelFormat == VideoMode.PixelFormat.kGray
|
||||
|| videoMode.pixelFormat == VideoMode.PixelFormat.kUnknown) {
|
||||
continue;
|
||||
}
|
||||
|
||||
// On picam, filter non-bgr modes for performance
|
||||
if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) {
|
||||
if (videoMode.pixelFormat != VideoMode.PixelFormat.kBGR) {
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
if (cameraQuirks.hasQuirk(CameraQuirk.FPSCap100)) {
|
||||
if (videoMode.fps > 100) {
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
videoModesList.add(videoMode);
|
||||
|
||||
// We look for modes with the same height/width/pixelformat as this mode
|
||||
// and remove all the ones that are slower. This is sorted low to high.
|
||||
// So we remove the last element (the fastest FPS) from the duplicate list,
|
||||
// and remove all remaining elements from the final list
|
||||
var duplicateModes =
|
||||
videoModesList.stream()
|
||||
.filter(
|
||||
it ->
|
||||
it.height == videoMode.height
|
||||
&& it.width == videoMode.width
|
||||
&& it.pixelFormat == videoMode.pixelFormat)
|
||||
.sorted(Comparator.comparingDouble(it -> it.fps))
|
||||
.collect(Collectors.toList());
|
||||
duplicateModes.remove(duplicateModes.size() - 1);
|
||||
videoModesList.removeAll(duplicateModes);
|
||||
}
|
||||
} catch (Exception e) {
|
||||
logger.error("Exception while enumerating video modes!", e);
|
||||
videoModesList = List.of();
|
||||
}
|
||||
|
||||
// Sort by resolution
|
||||
var sortedList =
|
||||
videoModesList.stream()
|
||||
.sorted(((a, b) -> (b.width + b.height) - (a.width + a.height)))
|
||||
.collect(Collectors.toList());
|
||||
Collections.reverse(sortedList);
|
||||
|
||||
// On vendor cameras, respect blacklisted indices
|
||||
var indexBlacklist =
|
||||
ConfigManager.getInstance().getConfig().getHardwareConfig().blacklistedResIndices;
|
||||
for (int badIdx : indexBlacklist) {
|
||||
sortedList.remove(badIdx);
|
||||
}
|
||||
|
||||
// Filter bogus modes on picam
|
||||
if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) {
|
||||
sortedList.removeIf(
|
||||
it ->
|
||||
(it.width == 1296
|
||||
&& it.height == 730
|
||||
&& it.pixelFormat == VideoMode.PixelFormat.kBGR)
|
||||
|| (it.width == 1296
|
||||
&& it.height == 972
|
||||
&& it.pixelFormat == VideoMode.PixelFormat.kBGR)
|
||||
|| (it.width == 2592
|
||||
&& it.height == 1944
|
||||
&& it.pixelFormat == VideoMode.PixelFormat.kBGR)
|
||||
|| (it.width == 160
|
||||
&& it.height == 120
|
||||
&& it.pixelFormat == VideoMode.PixelFormat.kBGR));
|
||||
}
|
||||
|
||||
for (VideoMode videoMode : sortedList) {
|
||||
videoModes.put(sortedList.indexOf(videoMode), videoMode);
|
||||
}
|
||||
}
|
||||
return videoModes;
|
||||
}
|
||||
}
|
||||
|
||||
// TODO improve robustness of this detection
|
||||
@Override
|
||||
public boolean isVendorCamera() {
|
||||
return ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV()
|
||||
&& cameraQuirks.hasQuirk(CameraQuirk.PiCam);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
if (this == o) return true;
|
||||
if (o == null || getClass() != o.getClass()) return false;
|
||||
USBCameraSource that = (USBCameraSource) o;
|
||||
return cameraQuirks.equals(that.cameraQuirks);
|
||||
}
|
||||
|
||||
@Override
|
||||
public int hashCode() {
|
||||
return Objects.hash(
|
||||
camera, usbCameraSettables, usbFrameProvider, configuration, cvSink, cameraQuirks);
|
||||
}
|
||||
}
|
||||
@@ -1,183 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.camera;
|
||||
|
||||
import edu.wpi.cscore.VideoMode;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.raspi.PicamJNI;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
import org.photonvision.vision.frame.provider.AcceleratedPicamFrameProvider;
|
||||
import org.photonvision.vision.processes.VisionSource;
|
||||
import org.photonvision.vision.processes.VisionSourceSettables;
|
||||
|
||||
public class ZeroCopyPicamSource implements VisionSource {
|
||||
private static final Logger logger = new Logger(ZeroCopyPicamSource.class, LogGroup.Camera);
|
||||
|
||||
private final VisionSourceSettables settables;
|
||||
private final AcceleratedPicamFrameProvider frameProvider;
|
||||
|
||||
public ZeroCopyPicamSource(CameraConfiguration configuration) {
|
||||
if (configuration.cameraType != CameraType.ZeroCopyPicam) {
|
||||
throw new IllegalArgumentException(
|
||||
"GPUAcceleratedPicamSource only accepts CameraConfigurations with type Picam");
|
||||
}
|
||||
|
||||
settables = new PicamSettables(configuration);
|
||||
frameProvider = new AcceleratedPicamFrameProvider(settables);
|
||||
}
|
||||
|
||||
@Override
|
||||
public FrameProvider getFrameProvider() {
|
||||
return frameProvider;
|
||||
}
|
||||
|
||||
@Override
|
||||
public VisionSourceSettables getSettables() {
|
||||
return settables;
|
||||
}
|
||||
|
||||
/**
|
||||
* On the OV5649 the actual FPS we want to request from the GPU can be higher than the FPS that we
|
||||
* can do after processing. On the IMX219 these FPSes match pretty closely, except for the
|
||||
* 1280x720 mode. We use this to present a rated FPS to the user that's lower than the actual FPS
|
||||
* we request from the GPU. This is important for setting user expectations, and is also used by
|
||||
* the frontend to detect and explain FPS drops.
|
||||
*/
|
||||
private static class FPSRatedVideoMode extends VideoMode {
|
||||
public final int fpsActual;
|
||||
public final double fovMultiplier;
|
||||
|
||||
public FPSRatedVideoMode(
|
||||
PixelFormat pixelFormat,
|
||||
int width,
|
||||
int height,
|
||||
int ratedFPS,
|
||||
int actualFPS,
|
||||
double fovMultiplier) {
|
||||
super(pixelFormat, width, height, ratedFPS);
|
||||
|
||||
this.fpsActual = actualFPS;
|
||||
this.fovMultiplier = fovMultiplier;
|
||||
}
|
||||
}
|
||||
|
||||
public static class PicamSettables extends VisionSourceSettables {
|
||||
|
||||
private FPSRatedVideoMode currentVideoMode;
|
||||
private double lastExposure;
|
||||
private int lastBrightness;
|
||||
private int lastGain;
|
||||
|
||||
public PicamSettables(CameraConfiguration configuration) {
|
||||
super(configuration);
|
||||
|
||||
videoModes = new HashMap<>();
|
||||
PicamJNI.SensorModel sensorModel = PicamJNI.getSensorModel();
|
||||
|
||||
if (sensorModel == PicamJNI.SensorModel.IMX219) {
|
||||
// Settings for the IMX219 sensor, which is used on the Pi Camera Module v2
|
||||
videoModes.put(
|
||||
0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 120, 120, .39));
|
||||
videoModes.put(
|
||||
1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39));
|
||||
// TODO: fix 1280x720 in the native code and re-add it
|
||||
videoModes.put(
|
||||
3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, .53));
|
||||
} else {
|
||||
if (sensorModel == PicamJNI.SensorModel.IMX477) {
|
||||
logger.warn(
|
||||
"It appears you are using a Pi HQ Camera. This camera is not officially supported. You will have to set your camera FOV differently based on resolution.");
|
||||
} else if (sensorModel == PicamJNI.SensorModel.Unknown) {
|
||||
logger.warn(
|
||||
"You have an unknown sensor connected to your Pi over CSI! This is likely a bug. If it is not, then you will have to set your camera FOV differently based on resolution.");
|
||||
}
|
||||
|
||||
// Settings for the OV5647 sensor, which is used by the Pi Camera Module v1
|
||||
videoModes.put(
|
||||
0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 90, 90, 1));
|
||||
videoModes.put(
|
||||
1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 85, 90, 1));
|
||||
videoModes.put(
|
||||
2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 960, 720, 45, 60, 1));
|
||||
videoModes.put(
|
||||
3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 720, 30, 45, 0.92));
|
||||
videoModes.put(
|
||||
4, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, 0.72));
|
||||
}
|
||||
|
||||
currentVideoMode = (FPSRatedVideoMode) videoModes.get(0);
|
||||
}
|
||||
|
||||
@Override
|
||||
public double getFOV() {
|
||||
return getCurrentVideoMode().fovMultiplier * getConfiguration().FOV;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setExposure(double exposure) {
|
||||
lastExposure = exposure;
|
||||
PicamJNI.setExposure((int) Math.round(exposure));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setBrightness(int brightness) {
|
||||
lastBrightness = brightness;
|
||||
PicamJNI.setBrightness(brightness);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setGain(int gain) {
|
||||
lastGain = gain;
|
||||
PicamJNI.setGain(gain);
|
||||
}
|
||||
|
||||
@Override
|
||||
public FPSRatedVideoMode getCurrentVideoMode() {
|
||||
return currentVideoMode;
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void setVideoModeInternal(VideoMode videoMode) {
|
||||
var mode = (FPSRatedVideoMode) videoMode;
|
||||
PicamJNI.destroyCamera();
|
||||
PicamJNI.createCamera(mode.width, mode.height, mode.fpsActual);
|
||||
|
||||
// We don't store last settings on the native side, and when you change video mode these get
|
||||
// reset on MMAL's end
|
||||
setExposure(lastExposure);
|
||||
setBrightness(lastBrightness);
|
||||
setGain(lastGain);
|
||||
|
||||
currentVideoMode = mode;
|
||||
}
|
||||
|
||||
@Override
|
||||
public HashMap<Integer, VideoMode> getAllVideoModes() {
|
||||
return videoModes;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isVendorCamera() {
|
||||
return ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV();
|
||||
}
|
||||
}
|
||||
@@ -1,60 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
|
||||
public class Frame implements Releasable {
|
||||
public final long timestampNanos;
|
||||
public final CVMat image;
|
||||
public final FrameStaticProperties frameStaticProperties;
|
||||
|
||||
public Frame(CVMat image, long timestampNanos, FrameStaticProperties frameStaticProperties) {
|
||||
this.image = image;
|
||||
this.timestampNanos = timestampNanos;
|
||||
this.frameStaticProperties = frameStaticProperties;
|
||||
}
|
||||
|
||||
public Frame(CVMat image, FrameStaticProperties frameStaticProperties) {
|
||||
this(image, System.nanoTime(), frameStaticProperties);
|
||||
}
|
||||
|
||||
public Frame() {
|
||||
timestampNanos = 0;
|
||||
image = new CVMat();
|
||||
frameStaticProperties = new FrameStaticProperties(0, 0, 0, new Rotation2d(), null);
|
||||
}
|
||||
|
||||
public void copyTo(Frame destFrame) {
|
||||
image.getMat().copyTo(destFrame.image.getMat());
|
||||
}
|
||||
|
||||
public static Frame copyFromAndRelease(Frame frame) {
|
||||
var mat = new CVMat();
|
||||
frame.image.copyTo(mat);
|
||||
frame.release();
|
||||
return new Frame(mat, frame.timestampNanos, frame.frameStaticProperties);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
image.release();
|
||||
}
|
||||
}
|
||||
@@ -1,22 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame;
|
||||
|
||||
import java.util.function.Consumer;
|
||||
|
||||
public interface FrameConsumer extends Consumer<Frame> {}
|
||||
@@ -1,31 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame;
|
||||
|
||||
public enum FrameDivisor {
|
||||
NONE(1),
|
||||
HALF(2),
|
||||
QUARTER(4),
|
||||
SIXTH(6);
|
||||
|
||||
public final Integer value;
|
||||
|
||||
FrameDivisor(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
@@ -1,24 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame;
|
||||
|
||||
import java.util.function.Supplier;
|
||||
|
||||
public interface FrameProvider extends Supplier<Frame> {
|
||||
String getName();
|
||||
}
|
||||
@@ -1,102 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame;
|
||||
|
||||
import edu.wpi.cscore.VideoMode;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import org.apache.commons.math3.fraction.Fraction;
|
||||
import org.apache.commons.math3.util.FastMath;
|
||||
import org.opencv.core.Point;
|
||||
import org.photonvision.common.util.numbers.DoubleCouple;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
|
||||
/** Represents the properties of a frame. */
|
||||
public class FrameStaticProperties {
|
||||
public final int imageWidth;
|
||||
public final int imageHeight;
|
||||
public final double fov;
|
||||
public final double imageArea;
|
||||
public final double centerX;
|
||||
public final double centerY;
|
||||
public final Point centerPoint;
|
||||
public final double horizontalFocalLength;
|
||||
public final double verticalFocalLength;
|
||||
public final Rotation2d cameraPitch;
|
||||
public CameraCalibrationCoefficients cameraCalibration;
|
||||
|
||||
/**
|
||||
* Instantiates a new Frame static properties.
|
||||
*
|
||||
* @param mode The Video Mode of the camera.
|
||||
* @param fov The fov of the image.
|
||||
*/
|
||||
public FrameStaticProperties(
|
||||
VideoMode mode, double fov, Rotation2d cameraPitch, CameraCalibrationCoefficients cal) {
|
||||
this(mode != null ? mode.width : 1, mode != null ? mode.height : 1, fov, cameraPitch, cal);
|
||||
}
|
||||
|
||||
/**
|
||||
* Instantiates a new Frame static properties.
|
||||
*
|
||||
* @param imageWidth The width of the image.
|
||||
* @param imageHeight The width of the image.
|
||||
* @param fov The fov of the image.
|
||||
*/
|
||||
public FrameStaticProperties(
|
||||
int imageWidth,
|
||||
int imageHeight,
|
||||
double fov,
|
||||
Rotation2d cameraPitch,
|
||||
CameraCalibrationCoefficients cal) {
|
||||
this.imageWidth = imageWidth;
|
||||
this.imageHeight = imageHeight;
|
||||
this.fov = fov;
|
||||
this.cameraPitch = cameraPitch;
|
||||
this.cameraCalibration = cal;
|
||||
|
||||
imageArea = this.imageWidth * this.imageHeight;
|
||||
|
||||
centerX = ((double) this.imageWidth / 2) - 0.5;
|
||||
centerY = ((double) this.imageHeight / 2) - 0.5;
|
||||
centerPoint = new Point(centerX, centerY);
|
||||
|
||||
// pinhole model calculations
|
||||
DoubleCouple horizVertViews =
|
||||
calculateHorizontalVerticalFoV(this.fov, this.imageWidth, this.imageHeight);
|
||||
|
||||
horizontalFocalLength = this.imageWidth / (2 * FastMath.tan(horizVertViews.getFirst() / 2));
|
||||
verticalFocalLength = this.imageHeight / (2 * FastMath.tan(horizVertViews.getSecond() / 2));
|
||||
}
|
||||
|
||||
public static DoubleCouple calculateHorizontalVerticalFoV(
|
||||
double diagonalFoV, int imageWidth, int imageHeight) {
|
||||
double diagonalView = FastMath.toRadians(diagonalFoV);
|
||||
Fraction aspectFraction = new Fraction(imageWidth, imageHeight);
|
||||
|
||||
int horizontalRatio = aspectFraction.getNumerator();
|
||||
int verticalRatio = aspectFraction.getDenominator();
|
||||
|
||||
double diagonalAspect = FastMath.hypot(horizontalRatio, verticalRatio);
|
||||
double horizontalView =
|
||||
FastMath.atan(FastMath.tan(diagonalView / 2) * (horizontalRatio / diagonalAspect)) * 2;
|
||||
double verticalView =
|
||||
FastMath.atan(FastMath.tan(diagonalView / 2) * (verticalRatio / diagonalAspect)) * 2;
|
||||
|
||||
return new DoubleCouple(horizontalView, verticalView);
|
||||
}
|
||||
}
|
||||
@@ -1,28 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame.consumer;
|
||||
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
import org.photonvision.vision.frame.FrameConsumer;
|
||||
|
||||
public class DummyFrameConsumer implements FrameConsumer {
|
||||
@Override
|
||||
public void accept(Frame frame) {
|
||||
frame.release(); // lol ez
|
||||
}
|
||||
}
|
||||
@@ -1,122 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame.consumer;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import java.io.File;
|
||||
import java.text.DateFormat;
|
||||
import java.text.SimpleDateFormat;
|
||||
import java.util.Date;
|
||||
import java.util.concurrent.locks.ReentrantLock;
|
||||
import java.util.function.Consumer;
|
||||
import org.opencv.imgcodecs.Imgcodecs;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.TimedTaskManager;
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
|
||||
public class FileSaveFrameConsumer implements Consumer<Frame> {
|
||||
|
||||
// Formatters to generate unique, timestamped file names
|
||||
private static String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString();
|
||||
private static String FILE_EXTENSION = ".jpg";
|
||||
DateFormat df = new SimpleDateFormat("yyyy-MM-dd");
|
||||
DateFormat tf = new SimpleDateFormat("hhmmssSS");
|
||||
private final String NT_SUFFIX = "SaveImgCmd";
|
||||
private final String ntEntryName;
|
||||
private NetworkTable subTable;
|
||||
private final NetworkTable rootTable;
|
||||
private final Logger logger;
|
||||
private boolean prevCommand = false;
|
||||
private String camNickname;
|
||||
private String fnamePrefix;
|
||||
private final long CMD_RESET_TIME_MS = 500;
|
||||
private final NetworkTableEntry entry;
|
||||
// Helps prevent race conditions between user set & auto-reset logic
|
||||
private ReentrantLock lock;
|
||||
|
||||
public FileSaveFrameConsumer(String camNickname, String streamPrefix) {
|
||||
this.lock = new ReentrantLock();
|
||||
this.fnamePrefix = camNickname + "_" + streamPrefix;
|
||||
this.ntEntryName = streamPrefix + NT_SUFFIX;
|
||||
this.rootTable = NetworkTablesManager.getInstance().kRootTable;
|
||||
updateCameraNickname(camNickname);
|
||||
entry = subTable.getEntry(ntEntryName);
|
||||
entry.forceSetBoolean(false);
|
||||
this.logger = new Logger(FileSaveFrameConsumer.class, this.camNickname, LogGroup.General);
|
||||
}
|
||||
|
||||
public void accept(Frame frame) {
|
||||
if (frame != null && !frame.image.getMat().empty()) {
|
||||
|
||||
if (lock.tryLock()) {
|
||||
boolean curCommand = entry.getBoolean(false);
|
||||
if (curCommand && !prevCommand) {
|
||||
Date now = new Date();
|
||||
String savefile =
|
||||
FILE_PATH
|
||||
+ File.separator
|
||||
+ fnamePrefix
|
||||
+ "_"
|
||||
+ df.format(now)
|
||||
+ "T"
|
||||
+ tf.format(now)
|
||||
+ FILE_EXTENSION;
|
||||
|
||||
Imgcodecs.imwrite(savefile, frame.image.getMat());
|
||||
|
||||
// Help the user a bit - set the NT entry back to false after 500ms
|
||||
TimedTaskManager.getInstance().addOneShotTask(this::resetCommand, CMD_RESET_TIME_MS);
|
||||
|
||||
logger.info("Saved new image at " + savefile);
|
||||
} else if (!curCommand) {
|
||||
// If the entry is currently false, set it again. This will make sure it shows up on the
|
||||
// dashboard.
|
||||
entry.forceSetBoolean(false);
|
||||
}
|
||||
|
||||
prevCommand = curCommand;
|
||||
lock.unlock();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void resetCommand() {
|
||||
lock.lock();
|
||||
this.subTable.getEntry(ntEntryName).setBoolean(false);
|
||||
lock.unlock();
|
||||
}
|
||||
|
||||
private void removeEntries() {
|
||||
if (this.subTable != null) {
|
||||
if (this.subTable.containsKey(ntEntryName)) {
|
||||
this.subTable.delete(ntEntryName);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public void updateCameraNickname(String newCameraNickname) {
|
||||
removeEntries();
|
||||
this.camNickname = newCameraNickname;
|
||||
this.subTable = rootTable.getSubTable(this.camNickname);
|
||||
resetCommand();
|
||||
}
|
||||
}
|
||||
@@ -1,161 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame.consumer;
|
||||
|
||||
import edu.wpi.cscore.CameraServerJNI;
|
||||
import edu.wpi.cscore.CvSource;
|
||||
import edu.wpi.cscore.MjpegServer;
|
||||
import edu.wpi.cscore.VideoEvent;
|
||||
import edu.wpi.cscore.VideoListener;
|
||||
import edu.wpi.cscore.VideoMode;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import java.util.ArrayList;
|
||||
import org.opencv.core.Size;
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
import org.photonvision.vision.frame.FrameDivisor;
|
||||
|
||||
public class MJPGFrameConsumer {
|
||||
|
||||
private CvSource cvSource;
|
||||
private MjpegServer mjpegServer;
|
||||
|
||||
@SuppressWarnings("FieldCanBeLocal")
|
||||
private VideoListener listener;
|
||||
|
||||
private final NetworkTable table;
|
||||
|
||||
public MJPGFrameConsumer(String sourceName, int width, int height, int port) {
|
||||
this.cvSource = new CvSource(sourceName, VideoMode.PixelFormat.kMJPEG, width, height, 30);
|
||||
this.table =
|
||||
NetworkTableInstance.getDefault().getTable("/CameraPublisher").getSubTable(sourceName);
|
||||
|
||||
this.mjpegServer = new MjpegServer("serve_" + cvSource.getName(), port);
|
||||
mjpegServer.setSource(cvSource);
|
||||
|
||||
listener =
|
||||
new VideoListener(
|
||||
event -> {
|
||||
if (event.kind == VideoEvent.Kind.kNetworkInterfacesChanged) {
|
||||
table.getEntry("source").setString("cv:");
|
||||
table.getEntry("streams");
|
||||
table.getEntry("connected").setBoolean(true);
|
||||
table.getEntry("mode").setString(videoModeToString(cvSource.getVideoMode()));
|
||||
table.getEntry("modes").setStringArray(getSourceModeValues(cvSource.getHandle()));
|
||||
updateStreamValues();
|
||||
}
|
||||
},
|
||||
0x4fff,
|
||||
true);
|
||||
}
|
||||
|
||||
private synchronized void updateStreamValues() {
|
||||
// Get port
|
||||
int port = mjpegServer.getPort();
|
||||
|
||||
// Generate values
|
||||
var addresses = CameraServerJNI.getNetworkInterfaces();
|
||||
ArrayList<String> values = new ArrayList<>(addresses.length + 1);
|
||||
String listenAddress = CameraServerJNI.getMjpegServerListenAddress(mjpegServer.getHandle());
|
||||
if (!listenAddress.isEmpty()) {
|
||||
// If a listen address is specified, only use that
|
||||
values.add(makeStreamValue(listenAddress, port));
|
||||
} else {
|
||||
// Otherwise generate for hostname and all interface addresses
|
||||
values.add(makeStreamValue(CameraServerJNI.getHostname() + ".local", port));
|
||||
for (String addr : addresses) {
|
||||
if ("127.0.0.1".equals(addr)) {
|
||||
continue; // ignore localhost
|
||||
}
|
||||
values.add(makeStreamValue(addr, port));
|
||||
}
|
||||
}
|
||||
|
||||
String[] streamAddresses = values.toArray(new String[0]);
|
||||
table.getEntry("streams").setStringArray(streamAddresses);
|
||||
}
|
||||
|
||||
public MJPGFrameConsumer(String name, int port) {
|
||||
this(name, 320, 240, port);
|
||||
}
|
||||
|
||||
public void accept(Frame frame) {
|
||||
if (frame != null && !frame.image.getMat().empty()) {
|
||||
cvSource.putFrame(frame.image.getMat());
|
||||
}
|
||||
}
|
||||
|
||||
private Size getScaledSize(Size orig, FrameDivisor divisor) {
|
||||
return new Size(orig.width / divisor.value, orig.height / divisor.value);
|
||||
}
|
||||
|
||||
public int getCurrentStreamPort() {
|
||||
return mjpegServer.getPort();
|
||||
}
|
||||
|
||||
private static String makeStreamValue(String address, int port) {
|
||||
return "mjpg:http://" + address + ":" + port + "/?action=stream";
|
||||
}
|
||||
|
||||
private static String[] getSourceModeValues(int sourceHandle) {
|
||||
VideoMode[] modes = CameraServerJNI.enumerateSourceVideoModes(sourceHandle);
|
||||
String[] modeStrings = new String[modes.length];
|
||||
for (int i = 0; i < modes.length; i++) {
|
||||
modeStrings[i] = videoModeToString(modes[i]);
|
||||
}
|
||||
return modeStrings;
|
||||
}
|
||||
|
||||
private static String videoModeToString(VideoMode mode) {
|
||||
return mode.width
|
||||
+ "x"
|
||||
+ mode.height
|
||||
+ " "
|
||||
+ pixelFormatToString(mode.pixelFormat)
|
||||
+ " "
|
||||
+ mode.fps
|
||||
+ " fps";
|
||||
}
|
||||
|
||||
private static String pixelFormatToString(VideoMode.PixelFormat pixelFormat) {
|
||||
switch (pixelFormat) {
|
||||
case kMJPEG:
|
||||
return "MJPEG";
|
||||
case kYUYV:
|
||||
return "YUYV";
|
||||
case kRGB565:
|
||||
return "RGB565";
|
||||
case kBGR:
|
||||
return "BGR";
|
||||
case kGray:
|
||||
return "Gray";
|
||||
default:
|
||||
return "Unknown";
|
||||
}
|
||||
}
|
||||
|
||||
public void close() {
|
||||
table.getEntry("connected").setBoolean(false);
|
||||
mjpegServer.close();
|
||||
cvSource.close();
|
||||
listener.close();
|
||||
mjpegServer = null;
|
||||
cvSource = null;
|
||||
listener = null;
|
||||
}
|
||||
}
|
||||
@@ -1,52 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame.provider;
|
||||
|
||||
import org.opencv.core.Mat;
|
||||
import org.photonvision.raspi.PicamJNI;
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.processes.VisionSourceSettables;
|
||||
|
||||
public class AcceleratedPicamFrameProvider implements FrameProvider {
|
||||
|
||||
private final VisionSourceSettables settables;
|
||||
|
||||
private CVMat mat;
|
||||
|
||||
public AcceleratedPicamFrameProvider(VisionSourceSettables visionSettables) {
|
||||
this.settables = visionSettables;
|
||||
|
||||
var vidMode = settables.getCurrentVideoMode();
|
||||
PicamJNI.createCamera(vidMode.width, vidMode.height, vidMode.fps);
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getName() {
|
||||
return "AcceleratedPicamFrameProvider";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Frame get() {
|
||||
long matHandle = PicamJNI.grabFrame(false);
|
||||
mat = new CVMat(new Mat(matHandle));
|
||||
return new Frame(
|
||||
mat, System.nanoTime() - PicamJNI.getFrameLatency(), settables.getFrameStaticProperties());
|
||||
}
|
||||
}
|
||||
@@ -1,128 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame.provider;
|
||||
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import java.nio.file.Files;
|
||||
import java.nio.file.Path;
|
||||
import java.nio.file.Paths;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.imgcodecs.Imgcodecs;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
import org.photonvision.vision.frame.FrameStaticProperties;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
|
||||
/**
|
||||
* A {@link FrameProvider} that will read and provide an image from a {@link java.nio.file.Path
|
||||
* path}.
|
||||
*/
|
||||
public class FileFrameProvider implements FrameProvider {
|
||||
public static final int MAX_FPS = 120;
|
||||
private static int count = 0;
|
||||
|
||||
private final int thisIndex = count++;
|
||||
private final Path path;
|
||||
private final int millisDelay;
|
||||
private final Frame originalFrame;
|
||||
|
||||
private final FrameStaticProperties properties;
|
||||
|
||||
private long lastGetMillis = System.currentTimeMillis();
|
||||
|
||||
/**
|
||||
* Instantiates a new FileFrameProvider.
|
||||
*
|
||||
* @param path The path of the image to read from.
|
||||
* @param fov The fov of the image.
|
||||
* @param maxFPS The max framerate to provide the image at.
|
||||
*/
|
||||
public FileFrameProvider(Path path, double fov, int maxFPS) {
|
||||
this(path, fov, maxFPS, null, null);
|
||||
}
|
||||
|
||||
public FileFrameProvider(
|
||||
Path path, double fov, Rotation2d pitch, CameraCalibrationCoefficients calibration) {
|
||||
this(path, fov, MAX_FPS, pitch, calibration);
|
||||
}
|
||||
|
||||
public FileFrameProvider(
|
||||
Path path,
|
||||
double fov,
|
||||
int maxFPS,
|
||||
Rotation2d pitch,
|
||||
CameraCalibrationCoefficients calibration) {
|
||||
if (!Files.exists(path))
|
||||
throw new RuntimeException("Invalid path for image: " + path.toAbsolutePath().toString());
|
||||
this.path = path;
|
||||
this.millisDelay = 1000 / maxFPS;
|
||||
|
||||
Mat rawImage = Imgcodecs.imread(path.toString());
|
||||
if (rawImage.cols() > 0 && rawImage.rows() > 0) {
|
||||
properties =
|
||||
new FrameStaticProperties(rawImage.width(), rawImage.height(), fov, pitch, calibration);
|
||||
originalFrame = new Frame(new CVMat(rawImage), properties);
|
||||
} else {
|
||||
throw new RuntimeException("Image loading failed!");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Instantiates a new File frame provider.
|
||||
*
|
||||
* @param pathAsString The path of the image to read from as a string.
|
||||
* @param fov The fov of the image.
|
||||
*/
|
||||
public FileFrameProvider(String pathAsString, double fov) {
|
||||
this(Paths.get(pathAsString), fov, MAX_FPS);
|
||||
}
|
||||
|
||||
/**
|
||||
* Instantiates a new File frame provider.
|
||||
*
|
||||
* @param path The path of the image to read from.
|
||||
* @param fov The fov of the image.
|
||||
*/
|
||||
public FileFrameProvider(Path path, double fov) {
|
||||
this(path, fov, MAX_FPS);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Frame get() {
|
||||
Frame outputFrame = new Frame(new CVMat(), properties);
|
||||
originalFrame.copyTo(outputFrame);
|
||||
|
||||
// block to keep FPS at a defined rate
|
||||
if (System.currentTimeMillis() - lastGetMillis < millisDelay) {
|
||||
try {
|
||||
Thread.sleep(millisDelay);
|
||||
} catch (InterruptedException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
|
||||
lastGetMillis = System.currentTimeMillis();
|
||||
return outputFrame;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getName() {
|
||||
return "FileFrameProvider" + thisIndex + " - " + path.getFileName();
|
||||
}
|
||||
}
|
||||
@@ -1,36 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame.provider;
|
||||
|
||||
import org.apache.commons.lang3.NotImplementedException;
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
|
||||
public class NetworkFrameProvider implements FrameProvider {
|
||||
private int count = 0;
|
||||
|
||||
@Override
|
||||
public Frame get() {
|
||||
throw new NotImplementedException("");
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getName() {
|
||||
return "NetworkFrameProvider" + count++;
|
||||
}
|
||||
}
|
||||
@@ -1,59 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.frame.provider;
|
||||
|
||||
import edu.wpi.cscore.CvSink;
|
||||
import org.photonvision.common.util.math.MathUtils;
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.processes.VisionSourceSettables;
|
||||
|
||||
public class USBFrameProvider implements FrameProvider {
|
||||
private static final long unixEpochToNanoEpoch =
|
||||
System.nanoTime()
|
||||
- MathUtils.millisToNanos(System.currentTimeMillis()); // Units are nanoseconds
|
||||
private final CvSink cvSink;
|
||||
|
||||
@SuppressWarnings("SpellCheckingInspection")
|
||||
private final VisionSourceSettables settables;
|
||||
|
||||
@SuppressWarnings("SpellCheckingInspection")
|
||||
public USBFrameProvider(CvSink sink, VisionSourceSettables visionSettables) {
|
||||
cvSink = sink;
|
||||
cvSink.setEnabled(true);
|
||||
this.settables = visionSettables;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Frame get() {
|
||||
var mat = new CVMat(); // We do this so that we don't fill a Mat in use by another thread
|
||||
long time =
|
||||
cvSink.grabFrame(
|
||||
mat.getMat()); // Units are microseconds, epoch is the same as the Unix epoch
|
||||
return new Frame(
|
||||
mat,
|
||||
MathUtils.microsToNanos(time) + unixEpochToNanoEpoch,
|
||||
settables.getFrameStaticProperties());
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getName() {
|
||||
return "USBFrameProvider - " + cvSink.getName();
|
||||
}
|
||||
}
|
||||
@@ -1,102 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
import java.util.HashMap;
|
||||
import org.opencv.core.Mat;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class CVMat implements Releasable {
|
||||
private static final Logger logger = new Logger(CVMat.class, LogGroup.General);
|
||||
|
||||
private static int allMatCounter = 0;
|
||||
private static final HashMap<Mat, Integer> allMats = new HashMap<>();
|
||||
|
||||
private static boolean shouldPrint;
|
||||
|
||||
private final Mat mat;
|
||||
|
||||
public CVMat() {
|
||||
this(new Mat());
|
||||
}
|
||||
|
||||
public void copyTo(CVMat srcMat) {
|
||||
copyTo(srcMat.getMat());
|
||||
}
|
||||
|
||||
public void copyTo(Mat srcMat) {
|
||||
srcMat.copyTo(mat);
|
||||
}
|
||||
|
||||
private StringBuilder getStackTraceBuilder() {
|
||||
var trace = Thread.currentThread().getStackTrace();
|
||||
|
||||
final int STACK_FRAMES_TO_SKIP = 4;
|
||||
final var traceStr = new StringBuilder();
|
||||
for (int idx = STACK_FRAMES_TO_SKIP; idx < trace.length; idx++) {
|
||||
traceStr.append("\t\n").append(trace[idx]);
|
||||
}
|
||||
traceStr.append("\n");
|
||||
return traceStr;
|
||||
}
|
||||
|
||||
public CVMat(Mat mat) {
|
||||
this.mat = mat;
|
||||
allMatCounter++;
|
||||
allMats.put(mat, allMatCounter);
|
||||
|
||||
if (shouldPrint) {
|
||||
logger.trace(() -> "CVMat" + allMatCounter + " alloc - new count: " + allMats.size());
|
||||
logger.trace(getStackTraceBuilder()::toString);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
// If this mat is empty, all we can do is return
|
||||
if (mat.empty()) return;
|
||||
|
||||
// If the mat isn't in the hashmap, we can't remove it
|
||||
Integer matNo = allMats.get(mat);
|
||||
if (matNo != null) allMats.remove(mat);
|
||||
mat.release();
|
||||
|
||||
if (shouldPrint) {
|
||||
logger.trace(() -> "CVMat" + matNo + " de-alloc - new count: " + allMats.size());
|
||||
logger.trace(getStackTraceBuilder()::toString);
|
||||
}
|
||||
}
|
||||
|
||||
public Mat getMat() {
|
||||
return mat;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "CVMat{" + mat.toString() + '}';
|
||||
}
|
||||
|
||||
public static int getMatCount() {
|
||||
return allMats.size();
|
||||
}
|
||||
|
||||
public static void enablePrint(boolean enabled) {
|
||||
shouldPrint = enabled;
|
||||
}
|
||||
}
|
||||
@@ -1,79 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
import org.opencv.core.MatOfPoint2f;
|
||||
import org.opencv.core.MatOfPoint3f;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
|
||||
public class CVShape {
|
||||
public final Contour contour;
|
||||
public final ContourShape shape;
|
||||
|
||||
private MatOfPoint3f customTarget = null;
|
||||
|
||||
private MatOfPoint2f approxCurve = new MatOfPoint2f();
|
||||
|
||||
public CVShape(Contour contour, ContourShape shape) {
|
||||
this.contour = contour;
|
||||
this.shape = shape;
|
||||
}
|
||||
|
||||
public CVShape(Contour contour, MatOfPoint3f targetPoints) {
|
||||
this.contour = contour;
|
||||
this.shape = ContourShape.Custom;
|
||||
customTarget = targetPoints;
|
||||
}
|
||||
|
||||
public Contour getContour() {
|
||||
return contour;
|
||||
}
|
||||
|
||||
public MatOfPoint2f getApproxPolyDp(double epsilon, boolean closed) {
|
||||
approxCurve.release();
|
||||
approxCurve = new MatOfPoint2f();
|
||||
|
||||
Imgproc.approxPolyDP(contour.getMat2f(), approxCurve, epsilon, closed);
|
||||
return approxCurve;
|
||||
}
|
||||
|
||||
public MatOfPoint2f getApproxPolyDpConvex(double epsilon, boolean closed) {
|
||||
approxCurve.release();
|
||||
approxCurve = new MatOfPoint2f();
|
||||
|
||||
Imgproc.approxPolyDP(contour.getConvexHull(), approxCurve, epsilon, closed);
|
||||
return approxCurve;
|
||||
}
|
||||
|
||||
boolean approxPolyMatchesShape() {
|
||||
var pointList = approxCurve.toList();
|
||||
|
||||
// TODO: @Matt
|
||||
switch (shape) {
|
||||
case Custom:
|
||||
break;
|
||||
case Circle:
|
||||
break;
|
||||
case Triangle:
|
||||
break;
|
||||
case Quadrilateral:
|
||||
break;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
@@ -1,215 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
import java.util.Comparator;
|
||||
import org.opencv.core.CvType;
|
||||
import org.opencv.core.MatOfInt;
|
||||
import org.opencv.core.MatOfPoint;
|
||||
import org.opencv.core.MatOfPoint2f;
|
||||
import org.opencv.core.Point;
|
||||
import org.opencv.core.Rect;
|
||||
import org.opencv.core.RotatedRect;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
import org.opencv.imgproc.Moments;
|
||||
import org.photonvision.common.util.math.MathUtils;
|
||||
|
||||
public class Contour implements Releasable {
|
||||
|
||||
public static final Comparator<Contour> SortByMomentsX =
|
||||
Comparator.comparingDouble(
|
||||
(contour) -> contour.getMoments().get_m10() / contour.getMoments().get_m00());
|
||||
|
||||
public final MatOfPoint mat;
|
||||
|
||||
private Double area = Double.NaN;
|
||||
private Double perimeter = Double.NaN;
|
||||
private MatOfPoint2f mat2f = null;
|
||||
private RotatedRect minAreaRect = null;
|
||||
private Rect boundingRect = null;
|
||||
private Moments moments = null;
|
||||
|
||||
private MatOfPoint2f convexHull = null;
|
||||
|
||||
public Contour(MatOfPoint mat) {
|
||||
this.mat = mat;
|
||||
}
|
||||
|
||||
public MatOfPoint2f getMat2f() {
|
||||
if (mat2f == null) {
|
||||
mat2f = new MatOfPoint2f(mat.toArray());
|
||||
mat.convertTo(mat2f, CvType.CV_32F);
|
||||
}
|
||||
return mat2f;
|
||||
}
|
||||
|
||||
public MatOfPoint2f getConvexHull() {
|
||||
if (this.convexHull == null) {
|
||||
var ints = new MatOfInt();
|
||||
Imgproc.convexHull(mat, ints);
|
||||
this.convexHull = Contour.convertIndexesToPoints(mat, ints);
|
||||
ints.release();
|
||||
}
|
||||
return convexHull;
|
||||
}
|
||||
|
||||
public double getArea() {
|
||||
if (Double.isNaN(area)) {
|
||||
area = Imgproc.contourArea(mat);
|
||||
}
|
||||
return area;
|
||||
}
|
||||
|
||||
public double getPerimeter() {
|
||||
if (Double.isNaN(perimeter)) {
|
||||
perimeter = Imgproc.arcLength(getMat2f(), true);
|
||||
}
|
||||
return perimeter;
|
||||
}
|
||||
|
||||
public RotatedRect getMinAreaRect() {
|
||||
if (minAreaRect == null) {
|
||||
minAreaRect = Imgproc.minAreaRect(getMat2f());
|
||||
}
|
||||
return minAreaRect;
|
||||
}
|
||||
|
||||
public Rect getBoundingRect() {
|
||||
if (boundingRect == null) {
|
||||
boundingRect = Imgproc.boundingRect(mat);
|
||||
}
|
||||
return boundingRect;
|
||||
}
|
||||
|
||||
public Moments getMoments() {
|
||||
if (moments == null) {
|
||||
moments = Imgproc.moments(mat);
|
||||
}
|
||||
return moments;
|
||||
}
|
||||
|
||||
public Point getCenterPoint() {
|
||||
return getMinAreaRect().center;
|
||||
}
|
||||
|
||||
public boolean isEmpty() {
|
||||
return mat.empty();
|
||||
}
|
||||
|
||||
public boolean isIntersecting(
|
||||
Contour secondContour, ContourIntersectionDirection intersectionDirection) {
|
||||
boolean isIntersecting = false;
|
||||
|
||||
if (intersectionDirection == ContourIntersectionDirection.None) {
|
||||
isIntersecting = true;
|
||||
} else {
|
||||
try {
|
||||
MatOfPoint2f intersectMatA = new MatOfPoint2f();
|
||||
MatOfPoint2f intersectMatB = new MatOfPoint2f();
|
||||
|
||||
mat.convertTo(intersectMatA, CvType.CV_32F);
|
||||
secondContour.mat.convertTo(intersectMatB, CvType.CV_32F);
|
||||
|
||||
RotatedRect a = Imgproc.fitEllipse(intersectMatA);
|
||||
RotatedRect b = Imgproc.fitEllipse(intersectMatB);
|
||||
double mA = MathUtils.toSlope(a.angle);
|
||||
double mB = MathUtils.toSlope(b.angle);
|
||||
double x0A = a.center.x;
|
||||
double y0A = a.center.y;
|
||||
double x0B = b.center.x;
|
||||
double y0B = b.center.y;
|
||||
double intersectionX = ((mA * x0A) - y0A - (mB * x0B) + y0B) / (mA - mB);
|
||||
double intersectionY = (mA * (intersectionX - x0A)) + y0A;
|
||||
double massX = (x0A + x0B) / 2;
|
||||
double massY = (y0A + y0B) / 2;
|
||||
switch (intersectionDirection) {
|
||||
case Up:
|
||||
if (intersectionY < massY) isIntersecting = true;
|
||||
break;
|
||||
case Down:
|
||||
if (intersectionY > massY) isIntersecting = true;
|
||||
break;
|
||||
case Left:
|
||||
if (intersectionX < massX) isIntersecting = true;
|
||||
break;
|
||||
case Right:
|
||||
if (intersectionX > massX) isIntersecting = true;
|
||||
break;
|
||||
}
|
||||
intersectMatA.release();
|
||||
intersectMatB.release();
|
||||
} catch (Exception e) {
|
||||
// defaults to false
|
||||
}
|
||||
}
|
||||
|
||||
return isIntersecting;
|
||||
}
|
||||
|
||||
// TODO: refactor to do "infinite" contours ???????
|
||||
public static Contour groupContoursByIntersection(
|
||||
Contour firstContour, Contour secondContour, ContourIntersectionDirection intersection) {
|
||||
if (areIntersecting(firstContour, secondContour, intersection)) {
|
||||
return combineContours(firstContour, secondContour);
|
||||
} else {
|
||||
return null;
|
||||
}
|
||||
}
|
||||
|
||||
public static boolean areIntersecting(
|
||||
Contour firstContour,
|
||||
Contour secondContour,
|
||||
ContourIntersectionDirection intersectionDirection) {
|
||||
return firstContour.isIntersecting(secondContour, intersectionDirection)
|
||||
|| secondContour.isIntersecting(firstContour, intersectionDirection);
|
||||
}
|
||||
|
||||
private static Contour combineContours(Contour... contours) {
|
||||
var points = new MatOfPoint();
|
||||
|
||||
for (var contour : contours) {
|
||||
points.push_back(contour.mat);
|
||||
}
|
||||
|
||||
var finalContour = new Contour(points);
|
||||
|
||||
boolean contourEmpty = finalContour.isEmpty();
|
||||
return contourEmpty ? null : finalContour;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
if (mat != null) mat.release();
|
||||
if (mat2f != null) mat2f.release();
|
||||
if (convexHull != null) convexHull.release();
|
||||
}
|
||||
|
||||
public static MatOfPoint2f convertIndexesToPoints(MatOfPoint contour, MatOfInt indexes) {
|
||||
int[] arrIndex = indexes.toArray();
|
||||
Point[] arrContour = contour.toArray();
|
||||
Point[] arrPoints = new Point[arrIndex.length];
|
||||
|
||||
for (int i = 0; i < arrIndex.length; i++) {
|
||||
arrPoints[i] = arrContour[arrIndex[i]];
|
||||
}
|
||||
|
||||
var hull = new MatOfPoint2f();
|
||||
hull.fromArray(arrPoints);
|
||||
return hull;
|
||||
}
|
||||
}
|
||||
@@ -1,29 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
public enum ContourGroupingMode {
|
||||
Single(1),
|
||||
Dual(2);
|
||||
|
||||
public final int count;
|
||||
|
||||
ContourGroupingMode(int count) {
|
||||
this.count = count;
|
||||
}
|
||||
}
|
||||
@@ -1,26 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
public enum ContourIntersectionDirection {
|
||||
None,
|
||||
Up,
|
||||
Down,
|
||||
Left,
|
||||
Right
|
||||
}
|
||||
@@ -1,46 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
import java.util.EnumSet;
|
||||
import java.util.HashMap;
|
||||
|
||||
public enum ContourShape {
|
||||
Custom(-1),
|
||||
Circle(0),
|
||||
Triangle(3),
|
||||
Quadrilateral(4);
|
||||
|
||||
public final int sides;
|
||||
|
||||
ContourShape(int sides) {
|
||||
this.sides = sides;
|
||||
}
|
||||
|
||||
private static final HashMap<Integer, ContourShape> sidesToValueMap = new HashMap<>();
|
||||
|
||||
static {
|
||||
for (var value : EnumSet.allOf(ContourShape.class)) {
|
||||
sidesToValueMap.put(value.sides, value);
|
||||
}
|
||||
}
|
||||
|
||||
public static ContourShape fromSides(int sides) {
|
||||
return sidesToValueMap.get(sides);
|
||||
}
|
||||
}
|
||||
@@ -1,48 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
import java.util.Comparator;
|
||||
import org.apache.commons.math3.util.FastMath;
|
||||
import org.photonvision.vision.target.PotentialTarget;
|
||||
|
||||
public enum ContourSortMode {
|
||||
Largest(
|
||||
Comparator.comparingDouble(PotentialTarget::getArea)
|
||||
.reversed()), // reversed so that zero index has the largest size
|
||||
Smallest(Largest.getComparator().reversed()),
|
||||
Highest(Comparator.comparingDouble(rect -> rect.getMinAreaRect().center.y)),
|
||||
Lowest(Highest.getComparator().reversed()),
|
||||
Leftmost(Comparator.comparingDouble(target -> target.getMinAreaRect().center.x * -1)),
|
||||
Rightmost(Leftmost.getComparator().reversed()),
|
||||
Centermost(
|
||||
Comparator.comparingDouble(
|
||||
rect ->
|
||||
(FastMath.pow(rect.getMinAreaRect().center.y, 2)
|
||||
+ FastMath.pow(rect.getMinAreaRect().center.x, 2))));
|
||||
|
||||
private Comparator<PotentialTarget> m_comparator;
|
||||
|
||||
ContourSortMode(Comparator<PotentialTarget> comparator) {
|
||||
m_comparator = comparator;
|
||||
}
|
||||
|
||||
public Comparator<PotentialTarget> getComparator() {
|
||||
return m_comparator;
|
||||
}
|
||||
}
|
||||
@@ -1,25 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
import org.opencv.core.Mat;
|
||||
|
||||
public class DualMat {
|
||||
public Mat first;
|
||||
public Mat second;
|
||||
}
|
||||
@@ -1,48 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
import org.opencv.core.Point;
|
||||
import org.photonvision.common.util.numbers.DoubleCouple;
|
||||
import org.photonvision.vision.target.TargetCalculations;
|
||||
|
||||
public class DualOffsetValues {
|
||||
public final Point firstPoint;
|
||||
public final double firstPointArea;
|
||||
public final Point secondPoint;
|
||||
public final double secondPointArea;
|
||||
|
||||
public DualOffsetValues() {
|
||||
firstPoint = new Point();
|
||||
firstPointArea = 0;
|
||||
secondPoint = new Point();
|
||||
secondPointArea = 0;
|
||||
}
|
||||
|
||||
public DualOffsetValues(
|
||||
Point firstPoint, double firstPointArea, Point secondPoint, double secondPointArea) {
|
||||
this.firstPoint = firstPoint;
|
||||
this.firstPointArea = firstPointArea;
|
||||
this.secondPoint = secondPoint;
|
||||
this.secondPointArea = secondPointArea;
|
||||
}
|
||||
|
||||
public DoubleCouple getLineValues() {
|
||||
return TargetCalculations.getLineFromPoints(firstPoint, secondPoint);
|
||||
}
|
||||
}
|
||||
@@ -1,31 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
public enum ImageFlipMode {
|
||||
NONE(Integer.MIN_VALUE),
|
||||
VERTICAL(1),
|
||||
HORIZONTAL(0),
|
||||
BOTH(-1);
|
||||
|
||||
public final int value;
|
||||
|
||||
ImageFlipMode(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
@@ -1,35 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
public enum ImageRotationMode {
|
||||
DEG_0(-1),
|
||||
DEG_90(0),
|
||||
DEG_180(1),
|
||||
DEG_270(2);
|
||||
|
||||
public final int value;
|
||||
|
||||
ImageRotationMode(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
|
||||
public boolean isRotated() {
|
||||
return this.value == DEG_90.value || this.value == DEG_270.value;
|
||||
}
|
||||
}
|
||||
@@ -1,22 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.opencv;
|
||||
|
||||
public interface Releasable {
|
||||
void release();
|
||||
}
|
||||
@@ -1,60 +0,0 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.pipe;
|
||||
|
||||
/**
|
||||
* Defines a pipe. A pipe is a single step in a pipeline. This class is to be extended, never used
|
||||
* on its own.
|
||||
*
|
||||
* @param <I> Input type for the pipe
|
||||
* @param <O> Output type for the pipe
|
||||
* @param <P> Parameters type for the pipe
|
||||
*/
|
||||
public abstract class CVPipe<I, O, P> {
|
||||
|
||||
protected CVPipeResult<O> result = new CVPipeResult<>();
|
||||
protected P params;
|
||||
|
||||
public void setParams(P params) {
|
||||
this.params = params;
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs the process for the pipe.
|
||||
*
|
||||
* @param in Input for pipe processing.
|
||||
* @return Result of processing.
|
||||
*/
|
||||
protected abstract O process(I in);
|
||||
|
||||
/**
|
||||
* @param in Input for pipe processing.
|
||||
* @return Result of processing.
|
||||
*/
|
||||
public CVPipeResult<O> run(I in) {
|
||||
long pipeStartNanos = System.nanoTime();
|
||||
result.output = process(in);
|
||||
result.nanosElapsed = System.nanoTime() - pipeStartNanos;
|
||||
return result;
|
||||
}
|
||||
|
||||
public static class CVPipeResult<O> {
|
||||
public O output;
|
||||
public long nanosElapsed;
|
||||
}
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user