-
Notifications
You must be signed in to change notification settings - Fork 98
Add remote connectivity constructor to ZEDImageSensor #791
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Merged
Merged
Changes from 1 commit
Commits
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -50,7 +50,9 @@ public class ZEDImageSensor extends ImageSensor | |
private final ZEDModelData zedModel; | ||
private final int slInputType; | ||
private final int slDepthMode; | ||
private final int streamingPort = nextStreamingPort++; | ||
private String remoteStreamingAddress; | ||
private int remoteStreamingPort; | ||
private final int localStreamingPort = nextStreamingPort++; | ||
|
||
private final RawImage[] grabbedImages = new RawImage[OUTPUT_IMAGE_COUNT]; | ||
private final Pointer[] slMatPointers = new Pointer[OUTPUT_IMAGE_COUNT]; | ||
|
@@ -98,6 +100,20 @@ public ZEDImageSensor(int cameraID, ZEDModelData zedModel, int slInputType, int | |
zedRuntimeParameters.enable_fill_mode(false); | ||
} | ||
|
||
/** | ||
* Constructor to connect to a remote ZED SDK instance | ||
*/ | ||
public ZEDImageSensor(int cameraID, ZEDModelData zedModel, int slInputType, int slDepthMode, String remoteStreamingAddress, int remoteStreamingPort) | ||
{ | ||
this(cameraID, zedModel, slInputType, slDepthMode); | ||
|
||
if (slInputType != SL_INPUT_TYPE_STREAM) | ||
throw new RuntimeException("Invalid SL_INPUT_TYPE for called constructor (must be SL_INPUT_TYPE_STREAM)"); | ||
|
||
this.remoteStreamingAddress = remoteStreamingAddress; | ||
this.remoteStreamingPort = remoteStreamingPort; | ||
} | ||
|
||
private void updateReferenceFrames() | ||
{ | ||
if (leftSensorFrame != null) | ||
|
@@ -140,13 +156,21 @@ protected boolean startSensor() | |
sl_enable_positional_tracking(cameraID, positionalTrackingParameters, ""); | ||
} | ||
|
||
sl_enable_streaming(cameraID, SL_STREAMING_CODEC_H264, 8000, (short) streamingPort, -1, 0, 16084, CAMERA_FPS); | ||
|
||
// Get camera intrinsics | ||
SL_CalibrationParameters sensorIntrinsics = sl_get_calibration_parameters(cameraID, false); | ||
imageWidth = sl_get_width(cameraID); | ||
imageHeight = sl_get_height(cameraID); | ||
|
||
if (slInputType != SL_INPUT_TYPE_STREAM) | ||
sl_enable_streaming(cameraID, | ||
SL_STREAMING_CODEC_H264, | ||
calculateBitrate(imageWidth, imageHeight, CAMERA_FPS), | ||
(short) localStreamingPort, | ||
-1, | ||
0, | ||
16084, | ||
CAMERA_FPS); | ||
|
||
leftSensorIntrinsics.setWidth(imageWidth); | ||
leftSensorIntrinsics.setHeight(imageHeight); | ||
leftSensorIntrinsics.setFx(sensorIntrinsics.left_cam().fx()); | ||
|
@@ -208,7 +232,10 @@ protected void setInitParameters(SL_InitParameters parametersToSet) | |
|
||
protected int openCamera() | ||
{ | ||
return sl_open_camera(cameraID, zedInitParameters, 0, "", "", 0, "", "", ""); | ||
if (slInputType == SL_INPUT_TYPE_STREAM) | ||
return sl_open_camera(cameraID, zedInitParameters, 0, "", remoteStreamingAddress, remoteStreamingPort, "", "", ""); | ||
else | ||
return sl_open_camera(cameraID, zedInitParameters, 0, "", "", 0, "", "", ""); | ||
} | ||
|
||
@Override | ||
|
@@ -372,7 +399,7 @@ public int getCameraID() | |
|
||
public int getStreamingPort() | ||
{ | ||
return streamingPort; | ||
return localStreamingPort; | ||
} | ||
|
||
public void enablePositionalTracking(boolean enable) | ||
|
@@ -470,4 +497,10 @@ private String getZEDErrorName(int errorCode) | |
default -> "UNKNOWN"; | ||
}; | ||
} | ||
|
||
private static int calculateBitrate(int width, int height, int fps) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. returns ~8000 for 1920x1080@30 |
||
{ | ||
double bpp = 0.128; // Derived from 8000 kbps for 1080p30 | ||
return (int) ((width * height * fps * bpp) / 1000); | ||
} | ||
} |
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Why not just remove the parameter from the constructor?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Yes, good idea. Ive done that