|
| | 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.
|
| |
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.
| 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).
| 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
-
| camRt | The change in basis from world coordinates to camera coordinates. See RotTrlTransform3d#makeRelativeTo(frc::Pose3d). |
| a | The initial translation of the line |
| b | The 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.