Class SimCameraProperties
The resolution will affect the accuracy of projected(3d to 2d) target corners and similarly the severity of image noise on estimation(2d to 3d).
The camera intrinsics and distortion coefficients describe the results of calibration, and how to map between 3d field points and 2d image points.
The performance values (framerate/exposure time, latency) determine how often results should be updated and with how much latency in simulation. High exposure time causes motion blur which can inhibit target detection while moving. Note that latency estimation does not account for network latency and the latency reported will always be perfect.
-
Constructor Summary
ConstructorsConstructorDescriptionDefault constructor which is the same asPERFECT_90DEG()SimCameraProperties(String path, int width, int height) Reads camera properties from a PhotonVisionconfig.jsonfile.SimCameraProperties(Path path, int width, int height) Reads camera properties from a PhotonVisionconfig.jsonfile. -
Method Summary
Modifier and TypeMethodDescriptioncopy()Returns a copy of the camera properties.doubleReturns an estimation of a frame's processing latency with noise added.doubleEstimates how long until the next frame should be processed.org.opencv.core.Point[]estPixelNoise(org.opencv.core.Point[] points) Returns these points after applying this camera's estimated noise.doubleWidth:heightdoubleGets the average latency of the simulated camera.doublegetContourAreaPercent(org.opencv.core.Point[] points) The percentage (0 - 100) of this camera's resolution the contour takes up in pixels of the image.getCorrectedPixelRot(org.opencv.core.Point point) Gives the yaw and pitch of the line intersecting the camera lens and the given pixel coordinates on the sensor.Returns the camera calibration's distortion coefficients, in OPENCV8 form.doubleGets the exposure time of the simulated camera.doublegetFPS()Gets the FPS of the simulated camera.doubleGets the time per frame of the simulated camera.doubleGets the time per frame of the simulated camera.getPixelPitch(double pixelY) The pitch from the principal point of this camera to the pixel y value.getPixelRot(org.opencv.core.Point point) Finds the yaw and pitch to the given image point.getPixelYaw(double pixelX) The yaw from the principal point of this camera to the pixel x value.intGets the area of the simulated camera image.intGets the height of the simulated camera image.intGets the width of the simulated camera image.getVisibleLine(RotTrlTransform3d camRt, Translation3d a, Translation3d b) Determines where the line segment defined by the two given translations intersects the camera's frustum/field-of-vision, if at all.static SimCameraPropertiesCreates a set of camera properties matching those of a Limelight 2 running at 1280x720 resolution.static SimCameraPropertiesCreates a set of camera properties matching those of a Limelight 2 running at 640x480 resolution.static SimCameraPropertiesCreates a set of camera properties matching those of a Limelight 2 running at 960x720 resolution.static SimCameraPropertiesCreates a set of camera properties where the camera has a 960x720 resolution, 90 degree FOV, and is a "perfect" lagless camera.static SimCameraPropertiesCreates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at 320x240 resolution.static SimCameraPropertiesCreates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at 640x480 resolution.setAvgLatencyMs(double avgLatencyMs) Sets the simulated latency for this camera.setCalibError(double avgErrorPx, double errorStdDevPx) setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) setExposureTimeMs(double exposureTimeMs) Sets the simulated exposure time for this camera.setFPS(double fps) Sets the simulated FPS for this camera.setLatencyStdDevMs(double latencyStdDevMs) Sets the simulated latency variation for this camera.setRandomSeed(long seed)
-
Constructor Details
-
SimCameraProperties
public SimCameraProperties()Default constructor which is the same asPERFECT_90DEG() -
SimCameraProperties
Reads camera properties from a PhotonVisionconfig.jsonfile. This is only the resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error. Other camera properties must be set.- Parameters:
path- Path to theconfig.jsonfilewidth- The width of the desired resolution in the JSONheight- The height of the desired resolution in the JSON- Throws:
IOException- If reading the JSON fails, either from an invalid path or a missing/invalid calibrated resolution.
-
SimCameraProperties
Reads camera properties from a PhotonVisionconfig.jsonfile. This is only the resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error. Other camera properties must be set.- Parameters:
path- Path to theconfig.jsonfilewidth- The width of the desired resolution in the JSONheight- The height of the desired resolution in the JSON- Throws:
IOException- If reading the JSON fails, either from an invalid path or a missing/invalid calibrated resolution.
-
-
Method Details
-
setRandomSeed
-
setCalibration
-
setCalibration
public SimCameraProperties setCalibration(int resWidth, int resHeight, Matrix<N3, N3> camIntrinsics, Matrix<N8, N1> distCoeffs) -
setCalibError
-
setFPS
Sets the simulated FPS for this camera.- Parameters:
fps- The average frames per second the camera should process at. Exposure time limits FPS if set!- Returns:
- This camera properties object for use in chaining
-
setExposureTimeMs
Sets the simulated exposure time for this camera.- Parameters:
exposureTimeMs- The amount of time the "shutter" is open for one frame. Affects motion blur. Frame speed(from FPS) is limited to this!- Returns:
- This camera properties object for use in chaining
-
setAvgLatencyMs
Sets the simulated latency for this camera.- Parameters:
avgLatencyMs- The average latency (from image capture to data published) in milliseconds a frame should have- Returns:
- This camera properties object for use in chaining
-
setLatencyStdDevMs
Sets the simulated latency variation for this camera.- Parameters:
latencyStdDevMs- The standard deviation in milliseconds of the latency- Returns:
- This camera properties object for use in chaining
-
getResWidth
Gets the width of the simulated camera image.- Returns:
- The width in pixels
-
getResHeight
Gets the height of the simulated camera image.- Returns:
- The height in pixels
-
getResArea
Gets the area of the simulated camera image.- Returns:
- The area in pixels
-
getAspectRatio
Width:height -
getIntrinsics
-
getDistCoeffs
Returns the camera calibration's distortion coefficients, in OPENCV8 form. Higher-order terms are set to 0- Returns:
- The distortion coefficients in an 8d vector
-
getFPS
Gets the FPS of the simulated camera.- Returns:
- The FPS
-
getFrameSpeedMs
Gets the time per frame of the simulated camera.- Returns:
- The time per frame in milliseconds
-
getExposureTimeMs
Gets the exposure time of the simulated camera.- Returns:
- The exposure time in milliseconds
-
getAvgLatencyMs
Gets the average latency of the simulated camera.- Returns:
- The average latency in milliseconds
-
getLatencyStdDevMs
Gets the time per frame of the simulated camera.- Returns:
- The time per frame in milliseconds
-
copy
Returns a copy of the camera properties.- Returns:
- The copied camera properties
-
getContourAreaPercent
The percentage (0 - 100) of this camera's resolution the contour takes up in pixels of the image.- Parameters:
points- Points of the contour- Returns:
- The percentage
-
getPixelYaw
The yaw from the principal point of this camera to the pixel x value. Positive values left. -
getPixelPitch
The pitch from the principal point of this camera to the pixel y value. Pitch is positive down.Note that this angle is naively computed and may be incorrect. See
getCorrectedPixelRot(Point). -
getPixelRot
Finds the yaw and pitch to the given image point. Yaw is positive left, and pitch is positive down.Note that pitch is naively computed and may be incorrect. See
getCorrectedPixelRot(Point). -
getCorrectedPixelRot
Gives the yaw and pitch of the line intersecting the camera lens and the given pixel coordinates on the sensor. Yaw is positive left, and pitch positive down.The pitch traditionally calculated from pixel offsets do not correctly account for non-zero values of yaw because of perspective distortion (not to be confused with lens distortion)-- for example, the pitch angle is naively calculated as:
pitch = arctan(pixel y offset / focal length y)
However, using focal length as a side of the associated right triangle is not correct when the pixel x value is not 0, because the distance from this pixel (projected on the x-axis) to the camera lens increases. Projecting a line back out of the camera with these naive angles will not intersect the 3d point that was originally projected into this 2d pixel. Instead, this length should be:focal length y ⟶ (focal length y / cos(arctan(pixel x offset / focal length x)))
- Returns:
- Rotation3d with yaw and pitch of the line projected out of the camera from the given pixel (roll is zero).
-
getHorizFOV
-
getVertFOV
-
getDiagFOV
-
getVisibleLine
public Pair<Double,Double> getVisibleLine(RotTrlTransform3d camRt, Translation3d a, Translation3d b) Determines where the line segment defined by the two given translations intersects the camera's frustum/field-of-vision, if at all.The line is parametrized so any of its points
p = t * (b - a) + a. This method returns these values of t, minimum first, defining the region of the line segment which is visible in the frustum. If both ends of the line segment are visible, this simply returns {0, 1}. If, for example, point b is visible while a is not, and half of the line segment is inside the camera frustum, {0.5, 1} would be returned.- Parameters:
camRt- The change in basis from world coordinates to camera coordinates. SeeRotTrlTransform3d.makeRelativeTo(Pose3d).a- The initial translation of the lineb- The final translation of the line- Returns:
- A Pair of Doubles. The values may be null:
- {Double, Double} : Two parametrized values(t), minimum first, representing which segment of the line is visible in the camera frustum.
- {Double, null} : One value(t) representing a single intersection point. For example, the line only intersects the intersection of two adjacent viewplanes.
- {null, null} : No values. The line segment is not visible in the camera frustum.
-
estPixelNoise
Returns these points after applying this camera's estimated noise.- Parameters:
points- The points to add noise to- Returns:
- The points with noise
-
estLatencyMs
Returns an estimation of a frame's processing latency with noise added.- Returns:
- The latency estimate in milliseconds
-
estMsUntilNextFrame
Estimates how long until the next frame should be processed.- Returns:
- The estimated time until the next frame in milliseconds
-
PERFECT_90DEG
Creates a set of camera properties where the camera has a 960x720 resolution, 90 degree FOV, and is a "perfect" lagless camera.- Returns:
- The properties for this theoretical camera
-
PI4_LIFECAM_320_240
Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at 320x240 resolution.Note that this set of properties represents a camera setup, not your camera setup. Do not use these camera properties for any non-sim vision calculations, especially the calibration data. Always use your camera's calibration data to do vision calculations in non-sim environments. These properties exist as a sample that may be used to get representative data in sim.
- Returns:
- The properties for this camera setup
-
PI4_LIFECAM_640_480
Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at 640x480 resolution.Note that this set of properties represents a camera setup, not your camera setup. Do not use these camera properties for any non-sim vision calculations, especially the calibration data. Always use your camera's calibration data to do vision calculations in non-sim environments. These properties exist as a sample that may be used to get representative data in sim.
- Returns:
- The properties for this camera setup
-
LL2_640_480
Creates a set of camera properties matching those of a Limelight 2 running at 640x480 resolution.Note that this set of properties represents a camera setup, not your camera setup. Do not use these camera properties for any non-sim vision calculations, especially the calibration data. Always use your camera's calibration data to do vision calculations in non-sim environments. These properties exist as a sample that may be used to get representative data in sim.
- Returns:
- The properties for this camera setup
-
LL2_960_720
Creates a set of camera properties matching those of a Limelight 2 running at 960x720 resolution.Note that this set of properties represents a camera setup, not your camera setup. Do not use these camera properties for any non-sim vision calculations, especially the calibration data. Always use your camera's calibration data to do vision calculations in non-sim environments. These properties exist as a sample that may be used to get representative data in sim.
- Returns:
- The properties for this camera setup
-
LL2_1280_720
Creates a set of camera properties matching those of a Limelight 2 running at 1280x720 resolution.Note that this set of properties represents a camera setup, not your camera setup. Do not use these camera properties for any non-sim vision calculations, especially the calibration data. Always use your camera's calibration data to do vision calculations in non-sim environments. These properties exist as a sample that may be used to get representative data in sim.
- Returns:
- The properties for this camera setup
-