Skip to content
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

SVO logging #598

Merged
merged 8 commits into from
Feb 10, 2025
Merged
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@ public class ZEDImageSensor extends ImageSensor
ZEDJavaAPINativeLibrary.load();
}

private static int nextStreamingPort = 30000;

public static final int LEFT_COLOR_IMAGE_KEY = 0;
public static final int RIGHT_COLOR_IMAGE_KEY = 1;
public static final int DEPTH_IMAGE_KEY = 2;
Expand All @@ -45,6 +47,7 @@ public class ZEDImageSensor extends ImageSensor
private final int cameraID;
private final ZEDModelData zedModel;
private final int slInputType;
private final int streamingPort = nextStreamingPort++;

private final RawImage[] grabbedImages = new RawImage[OUTPUT_IMAGE_COUNT];
private final Pointer[] slMatPointers = new Pointer[OUTPUT_IMAGE_COUNT];
Expand Down Expand Up @@ -109,6 +112,8 @@ 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);
Copy link
Member

@calvertdw calvertdw Jan 14, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this mean it's always streaming, even when doing local tests & development?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Streaming is always enabled, not necessarily streaming to anything

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You could use StreamingTools.getOpenPort() here. Though it's kinda nice knowing that ZED uses port 30000 and up. Up to you to decide which method you prefer.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I want to keep it like this, since ZED SDK typically always uses port 30000 or around there


// Get camera intrinsics
SL_CalibrationParameters sensorIntrinsics = sl_get_calibration_parameters(cameraID, false);
imageWidth = sl_get_width(cameraID);
Expand Down Expand Up @@ -180,7 +185,8 @@ protected int openCamera()
@Override
public boolean isSensorRunning()
{
return sl_is_opened(cameraID) && !lastGrabFailed;
boolean recentlyGrabbed = lastGrabTime != null && lastGrabTime.isAfter(Instant.now().minusSeconds(1));
return sl_is_opened(cameraID) && !lastGrabFailed && recentlyGrabbed;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

👍

}

@Override
Expand Down Expand Up @@ -304,6 +310,11 @@ public int getCameraID()
return cameraID;
}

public int getStreamingPort()
{
return streamingPort;
}

public void enablePositionalTracking(boolean enable)
{
positionalTrackingEnabled = enable;
Expand Down
Loading