Skip to content

Commit

Permalink
Update LibcameraGpuSettables.java
Browse files Browse the repository at this point in the history
  • Loading branch information
BytingBulldogs3539 committed Dec 24, 2023
1 parent bfc16d0 commit f07bb5f
Showing 1 changed file with 12 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -149,15 +149,15 @@ public void setExposure(double exposure) {
}

lastManualExposure = exposure;
var success = LibCameraJNI.setExposure(r_ptr,(int) Math.round(exposure) * 800);
var success = LibCameraJNI.setExposure(r_ptr, (int) Math.round(exposure) * 800);
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera exposure");
}

@Override
public void setBrightness(int brightness) {
lastBrightness = brightness;
double realBrightness = MathUtils.map(brightness, 0.0, 100.0, -1.0, 1.0);
var success = LibCameraJNI.setBrightness(r_ptr,realBrightness);
var success = LibCameraJNI.setBrightness(r_ptr, realBrightness);
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera brightness");
}

Expand Down Expand Up @@ -204,7 +204,7 @@ protected void setVideoModeInternal(VideoMode videoMode) {
// We need to make sure that other threads don't try to do anything funny while we're recreating
// the camera
synchronized (CAMERA_LOCK) {
if (r_ptr!=0) {
if (r_ptr != 0) {
logger.debug("Stopping libcamera");
if (!LibCameraJNI.stopCamera(r_ptr)) {
logger.error("Couldn't stop a zero copy Pi Camera while switching video modes");
Expand All @@ -216,9 +216,13 @@ protected void setVideoModeInternal(VideoMode videoMode) {
}

logger.debug("Creating libcamera");
r_ptr = LibCameraJNI.createCamera(
getConfiguration().path, mode.width, mode.height, (m_rotationMode == ImageRotationMode.DEG_180 ? 180 : 0));
if (r_ptr==0) {
r_ptr =
LibCameraJNI.createCamera(
getConfiguration().path,
mode.width,
mode.height,
(m_rotationMode == ImageRotationMode.DEG_180 ? 180 : 0));
if (r_ptr == 0) {
logger.error("Couldn't create a zero copy Pi Camera while switching video modes");
if (!LibCameraJNI.destroyCamera(r_ptr)) {
logger.error("Couldn't destroy a zero copy Pi Camera while switching video modes");
Expand All @@ -238,7 +242,7 @@ protected void setVideoModeInternal(VideoMode videoMode) {
setGain(lastGain);
setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond());

LibCameraJNI.setFramesToCopy(r_ptr,true, true);
LibCameraJNI.setFramesToCopy(r_ptr, true, true);

currentVideoMode = mode;
}
Expand All @@ -248,8 +252,7 @@ public HashMap<Integer, VideoMode> getAllVideoModes() {
return videoModes;
}

public LibCameraJNI.SensorModel getModel()
{
public LibCameraJNI.SensorModel getModel() {
return sensorModel;
}
}

0 comments on commit f07bb5f

Please sign in to comment.