Skip to content

Commit 0b98f02

Browse files
Enable multi-CSI-camera with libcamera (#1068)
We should continue being paranoid about multi-cam with all these changes --------- Co-authored-by: Matt <[email protected]>
1 parent 5be9b8b commit 0b98f02

File tree

10 files changed

+513
-353
lines changed

10 files changed

+513
-353
lines changed

photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ public Map<String, Object> toHashMap() {
137137
generalSubmap.put(
138138
"gpuAcceleration",
139139
LibCameraJNI.isSupported()
140-
? "Zerocopy Libcamera on " + LibCameraJNI.getSensorModel().getFriendlyName()
140+
? "Zerocopy Libcamera Working"
141141
: ""); // TODO add support for other types of GPU accel
142142
generalSubmap.put("hardwareModel", hardwareConfig.deviceName);
143143
generalSubmap.put("hardwarePlatform", Platform.getPlatformName());

photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/LinuxCmds.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
public class LinuxCmds extends CmdBase {
2323
public void initCmds(HardwareConfig config) {
2424
// CPU
25-
cpuMemoryCommand = "awk '/MemTotal:/ {print int($2 / 1000);}' /proc/meminfo";
25+
cpuMemoryCommand = "free -m | awk 'FNR == 2 {print $3}'";
2626

2727
// TODO: boards have lots of thermal devices. Hard to pick the CPU
2828

@@ -32,7 +32,7 @@ public void initCmds(HardwareConfig config) {
3232
cpuUptimeCommand = "uptime -p | cut -c 4-";
3333

3434
// RAM
35-
ramUsageCommand = "awk '/MemAvailable:/ {print int($2 / 1000);}' /proc/meminfo";
35+
ramUsageCommand = "free -m | awk 'FNR == 2 {print $3}'";
3636

3737
// Disk
3838
diskUsageCommand = "df ./ --output=pcent | tail -n +2";

photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/PiCmds.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ public void initCmds(HardwareConfig config) {
2525
super.initCmds(config);
2626

2727
// CPU
28-
cpuMemoryCommand = "vcgencmd get_mem arm | grep -Eo '[0-9]+'";
28+
cpuMemoryCommand = "free -m | awk 'FNR == 2 {print $2}'";
2929
cpuTemperatureCommand = "sed 's/.\\{3\\}$/.&/' /sys/class/thermal/thermal_zone0/temp";
3030
cpuThrottleReasonCmd =
3131
"if (( $(( $(vcgencmd get_throttled | grep -Eo 0x[0-9a-fA-F]*) & 0x01 )) != 0x00 )); then echo \"LOW VOLTAGE\"; "

photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java

Lines changed: 41 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,6 @@ public class LibCameraJNI {
3030
private static boolean libraryLoaded = false;
3131
private static final Logger logger = new Logger(LibCameraJNI.class, LogGroup.Camera);
3232

33-
public static final Object CAMERA_LOCK = new Object();
34-
3533
public static synchronized void forceLoad() throws IOException {
3634
if (libraryLoaded) return;
3735

@@ -93,8 +91,13 @@ public String getFriendlyName() {
9391
}
9492
}
9593

96-
public static SensorModel getSensorModel() {
97-
int model = getSensorModelRaw();
94+
public static SensorModel getSensorModel(long r_ptr) {
95+
int model = getSensorModelRaw(r_ptr);
96+
return SensorModel.values()[model];
97+
}
98+
99+
public static SensorModel getSensorModel(String name) {
100+
int model = getSensorModelRaw(name);
98101
return SensorModel.values()[model];
99102
}
100103

@@ -107,88 +110,101 @@ public static boolean isSupported() {
107110

108111
private static native boolean isLibraryWorking();
109112

110-
public static native int getSensorModelRaw();
113+
public static native int getSensorModelRaw(long r_ptr);
114+
115+
public static native int getSensorModelRaw(String name);
111116

112117
// ======================================================== //
113118

114119
/**
115120
* Creates a new runner with a given width/height/fps
116121
*
122+
* @param the path / name of the camera as given from libcamera.
117123
* @param width Camera video mode width in pixels
118124
* @param height Camera video mode height in pixels
119125
* @param fps Camera video mode FPS
120-
* @return success of creating a camera object
126+
* @return the runner pointer for the camera.
121127
*/
122-
public static native boolean createCamera(int width, int height, int rotation);
128+
public static native long createCamera(String name, int width, int height, int rotation);
123129

124130
/**
125131
* Starts the camera thresholder and display threads running. Make sure that this function is
126132
* called synchronously with stopCamera and returnFrame!
127133
*/
128-
public static native boolean startCamera();
134+
public static native boolean startCamera(long r_ptr);
129135

130136
/** Stops the camera runner. Make sure to call prior to destroying the camera! */
131-
public static native boolean stopCamera();
137+
public static native boolean stopCamera(long r_ptr);
132138

133139
// Destroy all native resources associated with a camera. Ensure stop is called prior!
134-
public static native boolean destroyCamera();
140+
public static native boolean destroyCamera(long r_ptr);
135141

136142
// ======================================================== //
137143

138144
// Set thresholds on [0..1]
139145
public static native boolean setThresholds(
140-
double hl, double sl, double vl, double hu, double su, double vu, boolean hueInverted);
146+
long r_ptr,
147+
double hl,
148+
double sl,
149+
double vl,
150+
double hu,
151+
double su,
152+
double vu,
153+
boolean hueInverted);
141154

142-
public static native boolean setAutoExposure(boolean doAutoExposure);
155+
public static native boolean setAutoExposure(long r_ptr, boolean doAutoExposure);
143156

144157
// Exposure time, in microseconds
145-
public static native boolean setExposure(int exposureUs);
158+
public static native boolean setExposure(long r_ptr, int exposureUs);
146159

147160
// Set brightness on [-1, 1]
148-
public static native boolean setBrightness(double brightness);
161+
public static native boolean setBrightness(long r_ptr, double brightness);
149162

150163
// Unknown ranges for red and blue AWB gain
151-
public static native boolean setAwbGain(double red, double blue);
164+
public static native boolean setAwbGain(long r_ptr, double red, double blue);
152165

153166
/**
154167
* Get the time when the first pixel exposure was started, in the same timebase as libcamera gives
155168
* the frame capture time. Units are nanoseconds.
156169
*/
157-
public static native long getFrameCaptureTime();
170+
public static native long getFrameCaptureTime(long p_ptr);
158171

159172
/**
160173
* Get the current time, in the same timebase as libcamera gives the frame capture time. Units are
161174
* nanoseconds.
162175
*/
163176
public static native long getLibcameraTimestamp();
164177

165-
public static native long setFramesToCopy(boolean copyIn, boolean copyOut);
178+
public static native long setFramesToCopy(long r_ptr, boolean copyIn, boolean copyOut);
166179

167180
// Analog gain multiplier to apply to all color channels, on [1, Big Number]
168-
public static native boolean setAnalogGain(double analog);
181+
public static native boolean setAnalogGain(long r_ptr, double analog);
169182

170183
/** Block until a new frame is available from native code. */
171-
public static native boolean awaitNewFrame();
184+
public static native long awaitNewFrame(long r_ptr);
172185

173186
/**
174187
* Get a pointer to the most recent color mat generated. Call this immediately after
175188
* awaitNewFrame, and call only once per new frame!
176189
*/
177-
public static native long takeColorFrame();
190+
public static native long takeColorFrame(long pair_ptr);
178191

179192
/**
180193
* Get a pointer to the most recent processed mat generated. Call this immediately after
181194
* awaitNewFrame, and call only once per new frame!
182195
*/
183-
public static native long takeProcessedFrame();
196+
public static native long takeProcessedFrame(long pair_ptr);
184197

185198
/**
186199
* Set the GPU processing type we should do. Enum of [none, HSV, greyscale, adaptive threshold].
187200
*/
188-
public static native boolean setGpuProcessType(int type);
201+
public static native boolean setGpuProcessType(long r_ptr, int type);
202+
203+
public static native int getGpuProcessType(long p_ptr);
189204

190-
public static native int getGpuProcessType();
205+
/** Release a pair pointer back to the libcamera driver code to be filled again */
206+
public static native boolean releasePair(long p_ptr);
191207

192-
// Release a frame pointer back to the libcamera driver code to be filled again */
193-
// public static native long returnFrame(long frame);
208+
/** Get an array containing the names/ids/paths of all connected CSI cameras from libcamera. */
209+
public static native String[] getCameraNames();
194210
}
Lines changed: 83 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,83 @@
1+
/*
2+
* Copyright (C) Photon Vision.
3+
*
4+
* This program is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* This program is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with this program. If not, see <https://www.gnu.org/licenses/>.
16+
*/
17+
18+
package org.photonvision.vision.camera;
19+
20+
import edu.wpi.first.cscore.UsbCameraInfo;
21+
import java.util.Arrays;
22+
23+
public class CameraInfo extends UsbCameraInfo {
24+
public final CameraType cameraType;
25+
26+
public CameraInfo(
27+
int dev, String path, String name, String[] otherPaths, int vendorId, int productId) {
28+
super(dev, path, name, otherPaths, vendorId, productId);
29+
cameraType = CameraType.UsbCamera;
30+
}
31+
32+
public CameraInfo(
33+
int dev,
34+
String path,
35+
String name,
36+
String[] otherPaths,
37+
int vendorId,
38+
int productId,
39+
CameraType cameraType) {
40+
super(dev, path, name, otherPaths, vendorId, productId);
41+
this.cameraType = cameraType;
42+
}
43+
44+
public CameraInfo(UsbCameraInfo info) {
45+
super(info.dev, info.path, info.name, info.otherPaths, info.vendorId, info.productId);
46+
cameraType = CameraType.UsbCamera;
47+
}
48+
49+
/**
50+
* @return True, if this camera is reported from V4L and is a CSI camera.
51+
*/
52+
public boolean getIsV4lCsiCamera() {
53+
return (Arrays.stream(otherPaths).anyMatch(it -> it.contains("csi-video"))
54+
|| getBaseName().equals("unicam"));
55+
}
56+
57+
/**
58+
* @return The base name of the camera aka the name as just ascii.
59+
*/
60+
public String getBaseName() {
61+
return name.replaceAll("[^\\x00-\\x7F]", "");
62+
}
63+
64+
/**
65+
* @param baseName
66+
* @return Returns a human readable name
67+
*/
68+
public String getHumanReadableName() {
69+
return getBaseName().replaceAll(" ", "_");
70+
}
71+
72+
@Override
73+
public boolean equals(Object o) {
74+
if (o == this) return true;
75+
if (!(o instanceof UsbCameraInfo || o instanceof CameraInfo)) return false;
76+
UsbCameraInfo other = (UsbCameraInfo) o;
77+
return path.equals(other.path)
78+
// && a.dev == b.dev (dev is not constant in Windows)
79+
&& name.equals(other.name)
80+
&& productId == other.productId
81+
&& vendorId == other.vendorId;
82+
}
83+
}

0 commit comments

Comments
 (0)