001/* 002 * Copyright (C) Photon Vision. 003 * 004 * This program is free software: you can redistribute it and/or modify 005 * it under the terms of the GNU General Public License as published by 006 * the Free Software Foundation, either version 3 of the License, or 007 * (at your option) any later version. 008 * 009 * This program is distributed in the hope that it will be useful, 010 * but WITHOUT ANY WARRANTY; without even the implied warranty of 011 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 012 * GNU General Public License for more details. 013 * 014 * You should have received a copy of the GNU General Public License 015 * along with this program. If not, see <https://www.gnu.org/licenses/>. 016 */ 017 018package org.photonvision.vision.pipeline; 019 020import com.fasterxml.jackson.annotation.JsonSubTypes; 021import com.fasterxml.jackson.annotation.JsonTypeInfo; 022import java.util.Objects; 023import org.photonvision.vision.frame.FrameDivisor; 024import org.photonvision.vision.opencv.ImageRotationMode; 025 026@JsonTypeInfo( 027 use = JsonTypeInfo.Id.NAME, 028 include = JsonTypeInfo.As.WRAPPER_ARRAY, 029 property = "type") 030@JsonSubTypes({ 031 @JsonSubTypes.Type(value = ColoredShapePipelineSettings.class), 032 @JsonSubTypes.Type(value = ReflectivePipelineSettings.class), 033 @JsonSubTypes.Type(value = DriverModePipelineSettings.class), 034 @JsonSubTypes.Type(value = AprilTagPipelineSettings.class), 035 @JsonSubTypes.Type(value = ArucoPipelineSettings.class), 036 @JsonSubTypes.Type(value = ObjectDetectionPipelineSettings.class) 037}) 038public class CVPipelineSettings implements Cloneable { 039 public int pipelineIndex = 0; 040 @SuppressSettingCopy public PipelineType pipelineType = PipelineType.DriverMode; 041 public ImageRotationMode inputImageRotationMode = ImageRotationMode.DEG_0; 042 public String pipelineNickname = "New Pipeline"; 043 public boolean cameraAutoExposure = false; 044 // manual exposure only used if cameraAutoExposure is false 045 public double cameraExposureRaw = 20; 046 public double cameraMinExposureRaw = 1; 047 public double cameraMaxExposureRaw = 100; 048 public int cameraBrightness = 50; 049 // Currently only used by a few cameras (notably the zero-copy Pi Camera driver) with the Gain 050 // quirk 051 public int cameraGain = 75; 052 // Currently only used by the zero-copy Pi Camera driver 053 public int cameraRedGain = 11; 054 public int cameraBlueGain = 20; 055 public int cameraVideoModeIndex = 0; 056 public FrameDivisor streamingFrameDivisor = FrameDivisor.NONE; 057 public boolean ledMode = false; 058 public boolean inputShouldShow = false; 059 public boolean outputShouldShow = true; 060 061 public boolean cameraAutoWhiteBalance = false; 062 public double cameraWhiteBalanceTemp = 4000; 063 064 @Override 065 public boolean equals(Object o) { 066 if (this == o) return true; 067 if (o == null || getClass() != o.getClass()) return false; 068 CVPipelineSettings that = (CVPipelineSettings) o; 069 return pipelineIndex == that.pipelineIndex 070 && Double.compare(that.cameraExposureRaw, cameraExposureRaw) == 0 071 && Double.compare(that.cameraMinExposureRaw, cameraMinExposureRaw) == 0 072 && Double.compare(that.cameraMaxExposureRaw, cameraMaxExposureRaw) == 0 073 && Double.compare(that.cameraBrightness, cameraBrightness) == 0 074 && Double.compare(that.cameraGain, cameraGain) == 0 075 && Double.compare(that.cameraRedGain, cameraRedGain) == 0 076 && Double.compare(that.cameraBlueGain, cameraBlueGain) == 0 077 && Double.compare(that.cameraWhiteBalanceTemp, cameraWhiteBalanceTemp) == 0 078 && cameraVideoModeIndex == that.cameraVideoModeIndex 079 && ledMode == that.ledMode 080 && pipelineType == that.pipelineType 081 && inputImageRotationMode == that.inputImageRotationMode 082 && pipelineNickname.equals(that.pipelineNickname) 083 && streamingFrameDivisor == that.streamingFrameDivisor 084 && inputShouldShow == that.inputShouldShow 085 && outputShouldShow == that.outputShouldShow; 086 } 087 088 @Override 089 public int hashCode() { 090 return Objects.hash( 091 pipelineIndex, 092 pipelineType, 093 inputImageRotationMode, 094 pipelineNickname, 095 cameraExposureRaw, 096 cameraMinExposureRaw, 097 cameraMaxExposureRaw, 098 cameraBrightness, 099 cameraGain, 100 cameraRedGain, 101 cameraBlueGain, 102 cameraWhiteBalanceTemp, 103 cameraVideoModeIndex, 104 streamingFrameDivisor, 105 ledMode, 106 inputShouldShow, 107 outputShouldShow); 108 } 109 110 @Override 111 public CVPipelineSettings clone() { 112 try { 113 return (CVPipelineSettings) super.clone(); 114 } catch (CloneNotSupportedException e) { 115 e.printStackTrace(); 116 return null; 117 } 118 } 119 120 @Override 121 public String toString() { 122 return "CVPipelineSettings{" 123 + "pipelineIndex=" 124 + pipelineIndex 125 + ", pipelineType=" 126 + pipelineType 127 + ", inputImageRotationMode=" 128 + inputImageRotationMode 129 + ", pipelineNickname='" 130 + pipelineNickname 131 + '\'' 132 + ", cameraExposureRaw=" 133 + cameraExposureRaw 134 + ", cameraBrightness=" 135 + cameraBrightness 136 + ", cameraGain=" 137 + cameraGain 138 + ", cameraRedGain=" 139 + cameraRedGain 140 + ", cameraBlueGain=" 141 + cameraBlueGain 142 + ", cameraVideoModeIndex=" 143 + cameraVideoModeIndex 144 + ", streamingFrameDivisor=" 145 + streamingFrameDivisor 146 + ", ledMode=" 147 + ledMode 148 + ", inputShouldShow=" 149 + inputShouldShow 150 + ", outputShouldShow=" 151 + outputShouldShow 152 + '}'; 153 } 154}