PhotonVision C++ v2026.2.2
Loading...
Searching...
No Matches
photon::SimCameraProperties Class Reference

Calibration and performance values for this camera. More...

#include <photon/simulation/SimCameraProperties.h>

Public Member Functions

 SimCameraProperties ()
 Default constructor which is the same as PERFECT_90DEG.
 
 SimCameraProperties (std::string path, int width, int height)
 Reads camera properties from a PhotonVision config.json file.
 
void SetCalibration (int width, int height, frc::Rotation2d fovDiag)
 
void SetCalibration (int width, int height, const Eigen::Matrix< double, 3, 3 > &newCamIntrinsics, const Eigen::Matrix< double, 8, 1 > &newDistCoeffs)
 
void SetCalibError (double newAvgErrorPx, double newErrorStdDevPx)
 
void SetFPS (units::hertz_t fps)
 Sets the simulated FPS for this camera.
 
void SetExposureTime (units::second_t exposureTime)
 Sets the simulated exposure time for this camera.
 
void SetAvgLatency (units::second_t avgLatency)
 Sets the simulated latency for this camera.
 
void SetLatencyStdDev (units::second_t latencyStdDev)
 Sets the simulated latency variation for this camera.
 
int GetResWidth () const
 Gets the width of the simulated camera image.
 
int GetResHeight () const
 Gets the height of the simulated camera image.
 
int GetResArea () const
 Gets the area of the simulated camera image.
 
double GetAspectRatio () const
 
Eigen::Matrix< double, 3, 3 > GetIntrinsics () const
 
Eigen::Matrix< double, 8, 1 > GetDistCoeffs () const
 Returns the camera calibration's distortion coefficients, in OPENCV8 form.
 
units::hertz_t GetFPS () const
 Gets the FPS of the simulated camera.
 
units::second_t GetFrameSpeed () const
 Gets the time per frame of the simulated camera.
 
units::second_t GetExposureTime () const
 Gets the exposure time of the simulated camera.
 
units::second_t GetAverageLatency () const
 Gets the average latency of the simulated camera.
 
units::second_t GetLatencyStdDev () const
 Gets the time per frame of the simulated camera.
 
double GetContourAreaPercent (const std::vector< cv::Point2f > &points)
 The percentage (0 - 100) of this camera's resolution the contour takes up in pixels of the image.
 
frc::Rotation2d GetPixelYaw (double pixelX) const
 The yaw from the principal point of this camera to the pixel x value.
 
frc::Rotation2d GetPixelPitch (double pixelY) const
 The pitch from the principal point of this camera to the pixel y value.
 
frc::Rotation3d GetPixelRot (const cv::Point2d &point) const
 Finds the yaw and pitch to the given image point.
 
frc::Rotation3d GetCorrectedPixelRot (const cv::Point2d &point) const
 Gives the yaw and pitch of the line intersecting the camera lens and the given pixel coordinates on the sensor.
 
frc::Rotation2d GetHorizFOV () const
 
frc::Rotation2d GetVertFOV () const
 
frc::Rotation2d GetDiagFOV () const
 
std::pair< std::optional< double >, std::optional< double > > GetVisibleLine (const RotTrlTransform3d &camRt, const frc::Translation3d &a, const frc::Translation3d &b) const
 Determines where the line segment defined by the two given translations intersects the camera's frustum/field-of-vision, if at all.
 
std::vector< cv::Point2f > EstPixelNoise (const std::vector< cv::Point2f > &points)
 Returns these points after applying this camera's estimated noise.
 
units::second_t EstLatency ()
 Returns an estimation of a frame's processing latency with noise added.
 
units::second_t EstSecUntilNextFrame ()
 Estimates how long until the next frame should be processed.
 

Static Public Member Functions

static SimCameraProperties PERFECT_90DEG ()
 Creates a set of camera properties where the camera has a 960x720 resolution, 90 degree FOV, and is a "perfect" lagless camera.
 
static SimCameraProperties PI4_LIFECAM_320_240 ()
 Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at 320x240 resolution.
 
static SimCameraProperties PI4_LIFECAM_640_480 ()
 Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at 640x480 resolution.
 
static SimCameraProperties LL2_640_480 ()
 Creates a set of camera properties matching those of a Limelight 2 running at 640x480 resolution.
 
static SimCameraProperties LL2_960_720 ()
 Creates a set of camera properties matching those of a Limelight 2 running at 960x720 resolution.
 
static SimCameraProperties LL2_1280_720 ()
 Creates a set of camera properties matching those of a Limelight 2 running at 1280x720 resolution.
 

Detailed Description

Calibration and performance values for this camera.

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 & Destructor Documentation

◆ SimCameraProperties() [1/2]

photon::SimCameraProperties::SimCameraProperties ( )
inline

Default constructor which is the same as PERFECT_90DEG.

◆ SimCameraProperties() [2/2]

photon::SimCameraProperties::SimCameraProperties ( std::string path,
int width,
int height )
inline

Reads camera properties from a PhotonVision config.json file.

This is only the resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error. Other camera properties must be set.

Parameters
pathPath to the config.json file
widthThe width of the desired resolution in the JSON
heightThe height of the desired resolution in the JSON

Member Function Documentation

◆ EstLatency()

units::second_t photon::SimCameraProperties::EstLatency ( )
inline

Returns an estimation of a frame's processing latency with noise added.

Returns
The latency estimate

◆ EstPixelNoise()

std::vector< cv::Point2f > photon::SimCameraProperties::EstPixelNoise ( const std::vector< cv::Point2f > & points)
inline

Returns these points after applying this camera's estimated noise.

Parameters
pointsThe points to add noise to
Returns
The points with noise

◆ EstSecUntilNextFrame()

units::second_t photon::SimCameraProperties::EstSecUntilNextFrame ( )
inline

Estimates how long until the next frame should be processed.

Returns
The estimated time until the next frame

◆ GetAspectRatio()

double photon::SimCameraProperties::GetAspectRatio ( ) const
inline

◆ GetAverageLatency()

units::second_t photon::SimCameraProperties::GetAverageLatency ( ) const
inline

Gets the average latency of the simulated camera.

Returns
The average latency

◆ GetContourAreaPercent()

double photon::SimCameraProperties::GetContourAreaPercent ( const std::vector< cv::Point2f > & points)
inline

The percentage (0 - 100) of this camera's resolution the contour takes up in pixels of the image.

Parameters
pointsPoints of the contour
Returns
The percentage

◆ GetCorrectedPixelRot()

frc::Rotation3d photon::SimCameraProperties::GetCorrectedPixelRot ( const cv::Point2d & point) const
inline

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).

◆ GetDiagFOV()

frc::Rotation2d photon::SimCameraProperties::GetDiagFOV ( ) const
inline

◆ GetDistCoeffs()

Eigen::Matrix< double, 8, 1 > photon::SimCameraProperties::GetDistCoeffs ( ) const
inline

Returns the camera calibration's distortion coefficients, in OPENCV8 form.

Higher-order terms are set to 0

Returns
The distortion coefficients in an 8x1 matrix

◆ GetExposureTime()

units::second_t photon::SimCameraProperties::GetExposureTime ( ) const
inline

Gets the exposure time of the simulated camera.

Returns
The exposure time

◆ GetFPS()

units::hertz_t photon::SimCameraProperties::GetFPS ( ) const
inline

Gets the FPS of the simulated camera.

Returns
The FPS

◆ GetFrameSpeed()

units::second_t photon::SimCameraProperties::GetFrameSpeed ( ) const
inline

Gets the time per frame of the simulated camera.

Returns
The time per frame

◆ GetHorizFOV()

frc::Rotation2d photon::SimCameraProperties::GetHorizFOV ( ) const
inline

◆ GetIntrinsics()

Eigen::Matrix< double, 3, 3 > photon::SimCameraProperties::GetIntrinsics ( ) const
inline

◆ GetLatencyStdDev()

units::second_t photon::SimCameraProperties::GetLatencyStdDev ( ) const
inline

Gets the time per frame of the simulated camera.

Returns
The time per frame

◆ GetPixelPitch()

frc::Rotation2d photon::SimCameraProperties::GetPixelPitch ( double pixelY) const
inline

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(const cv::Point2d).

◆ GetPixelRot()

frc::Rotation3d photon::SimCameraProperties::GetPixelRot ( const cv::Point2d & point) const
inline

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(const cv::Point2d).

◆ GetPixelYaw()

frc::Rotation2d photon::SimCameraProperties::GetPixelYaw ( double pixelX) const
inline

The yaw from the principal point of this camera to the pixel x value.

Positive values left.

◆ GetResArea()

int photon::SimCameraProperties::GetResArea ( ) const
inline

Gets the area of the simulated camera image.

Returns
The area in pixels

◆ GetResHeight()

int photon::SimCameraProperties::GetResHeight ( ) const
inline

Gets the height of the simulated camera image.

Returns
The height in pixels

◆ GetResWidth()

int photon::SimCameraProperties::GetResWidth ( ) const
inline

Gets the width of the simulated camera image.

Returns
The width in pixels

◆ GetVertFOV()

frc::Rotation2d photon::SimCameraProperties::GetVertFOV ( ) const
inline

◆ GetVisibleLine()

std::pair< std::optional< double >, std::optional< double > > photon::SimCameraProperties::GetVisibleLine ( const RotTrlTransform3d & camRt,
const frc::Translation3d & a,
const frc::Translation3d & b ) const

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
camRtThe change in basis from world coordinates to camera coordinates. See RotTrlTransform3d#makeRelativeTo(frc::Pose3d).
aThe initial translation of the line
bThe final translation of the line
Returns
A Pair of Doubles. The values may be empty:
  • {double, double} : Two parametrized values(t), minimum first, representing which segment of the line is visible in the camera frustum.
  • {double, std::nullopt} : One value(t) representing a single intersection point. For example, the line only intersects the intersection of two adjacent viewplanes.
  • {std::nullopt, std::nullopt} : No values. The line segment is not visible in the camera frustum.

◆ LL2_1280_720()

static SimCameraProperties photon::SimCameraProperties::LL2_1280_720 ( )
inlinestatic

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

◆ LL2_640_480()

static SimCameraProperties photon::SimCameraProperties::LL2_640_480 ( )
inlinestatic

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()

static SimCameraProperties photon::SimCameraProperties::LL2_960_720 ( )
inlinestatic

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

◆ PERFECT_90DEG()

static SimCameraProperties photon::SimCameraProperties::PERFECT_90DEG ( )
inlinestatic

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()

static SimCameraProperties photon::SimCameraProperties::PI4_LIFECAM_320_240 ( )
inlinestatic

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()

static SimCameraProperties photon::SimCameraProperties::PI4_LIFECAM_640_480 ( )
inlinestatic

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

◆ SetAvgLatency()

void photon::SimCameraProperties::SetAvgLatency ( units::second_t avgLatency)
inline

Sets the simulated latency for this camera.

Parameters
avgLatencyThe average latency (from image capture to data published) a frame should have

◆ SetCalibError()

void photon::SimCameraProperties::SetCalibError ( double newAvgErrorPx,
double newErrorStdDevPx )
inline

◆ SetCalibration() [1/2]

void photon::SimCameraProperties::SetCalibration ( int width,
int height,
const Eigen::Matrix< double, 3, 3 > & newCamIntrinsics,
const Eigen::Matrix< double, 8, 1 > & newDistCoeffs )

◆ SetCalibration() [2/2]

void photon::SimCameraProperties::SetCalibration ( int width,
int height,
frc::Rotation2d fovDiag )

◆ SetExposureTime()

void photon::SimCameraProperties::SetExposureTime ( units::second_t exposureTime)
inline

Sets the simulated exposure time for this camera.

Parameters
exposureTimeThe amount of time the "shutter" is open for one frame. Affects motion blur. Frame speed(from FPS) is limited to this!

◆ SetFPS()

void photon::SimCameraProperties::SetFPS ( units::hertz_t fps)
inline

Sets the simulated FPS for this camera.

Parameters
fpsThe average frames per second the camera should process at. Exposure time limits FPS if set!

◆ SetLatencyStdDev()

void photon::SimCameraProperties::SetLatencyStdDev ( units::second_t latencyStdDev)
inline

Sets the simulated latency variation for this camera.

Parameters
latencyStdDevThe standard deviation of the latency

The documentation for this class was generated from the following file: