34#include <frc/Errors.h>
35#include <frc/MathUtil.h>
36#include <frc/geometry/Rotation2d.h>
37#include <frc/geometry/Translation3d.h>
39#include <units/frequency.h>
40#include <units/time.h>
77 const Eigen::Matrix<double, 3, 3>& newCamIntrinsics,
78 const Eigen::Matrix<double, 8, 1>& newDistCoeffs);
81 avgErrorPx = newAvgErrorPx;
82 errorStdDevPx = newErrorStdDevPx;
92 frameSpeed = units::math::max(1 / fps, exposureTime);
102 this->exposureTime = exposureTime;
103 frameSpeed = units::math::max(frameSpeed, this->exposureTime);
113 this->avgLatency = avgLatency;
122 this->latencyStdDev = latencyStdDev;
147 return static_cast<double>(resWidth) /
static_cast<double>(resHeight);
165 units::hertz_t
GetFPS()
const {
return 1 / frameSpeed; }
210 double fx = camIntrinsics(0, 0);
211 double cx = camIntrinsics(0, 2);
212 double xOffset = cx - pixelX;
213 return frc::Rotation2d{fx, xOffset};
224 double fy = camIntrinsics(1, 1);
225 double cy = camIntrinsics(1, 2);
226 double yOffset = cy - pixelY;
227 return frc::Rotation2d{fy, -yOffset};
237 return frc::Rotation3d{0_rad,
GetPixelPitch(point.y).Radians(),
267 double fx = camIntrinsics(0, 0);
268 double cx = camIntrinsics(0, 2);
269 double xOffset = cx - point.x;
271 double fy = camIntrinsics(1, 1);
272 double cy = camIntrinsics(1, 2);
273 double yOffset = cy - point.y;
275 frc::Rotation2d yaw{fx, xOffset};
276 frc::Rotation2d pitch{fy / std::cos(std::atan(xOffset / fx)), -yOffset};
277 return frc::Rotation3d{0_rad, pitch.Radians(), yaw.Radians()};
289 return below - above;
293 return frc::Rotation2d{
323 const frc::Translation3d& b)
const;
332 const std::vector<cv::Point2f>& points) {
333 if (avgErrorPx == 0 && errorStdDevPx == 0) {
337 std::vector<cv::Point2f> noisyPts;
338 noisyPts.reserve(points.size());
339 for (
size_t i = 0; i < points.size(); i++) {
340 cv::Point2f p = points[i];
341 float error = avgErrorPx + gaussian(generator) * errorStdDevPx;
343 uniform(generator) * 2 * std::numbers::pi - std::numbers::pi;
344 noisyPts.emplace_back(cv::Point2f{p.x + error * std::cos(errorAngle),
345 p.y + error * std::sin(errorAngle)});
356 return units::math::max(avgLatency + gaussian(generator) * latencyStdDev,
366 return frameSpeed + units::math::max(0_s,
EstLatency() - frameSpeed);
394 (Eigen::MatrixXd(3, 3) << 328.2733242048587, 0.0, 164.8190261141906,
395 0.0, 318.0609794305216, 123.8633838438093, 0.0, 0.0, 1.0)
397 Eigen::Matrix<double, 8, 1>{
398 0.09957946553445934, -0.9166265114485799, 0.0019519890627236526,
399 -0.0036071725380870333, 1.5627234622420942, 0, 0, 0});
400 prop.SetCalibError(0.21, 0.0124);
402 prop.SetAvgLatency(30_ms);
403 prop.SetLatencyStdDev(10_ms);
424 (Eigen::MatrixXd(3, 3) << 669.1428078983059, 0.0, 322.53377249329213,
425 0.0, 646.9843137061716, 241.26567383784163, 0.0, 0.0, 1.0)
427 Eigen::Matrix<double, 8, 1>{
428 0.12788470750464645, -1.2350335805796528, 0.0024990767286192732,
429 -0.0026958287600230705, 2.2951386729115537, 0, 0, 0});
430 prop.SetCalibError(0.26, 0.046);
432 prop.SetAvgLatency(65_ms);
433 prop.SetLatencyStdDev(15_ms);
454 (Eigen::MatrixXd(3, 3) << 511.22843367007755, 0.0, 323.62049380211096,
455 0.0, 514.5452336723849, 261.8827920543568, 0.0, 0.0, 1.0)
457 Eigen::Matrix<double, 8, 1>{0.1917469998873756, -0.5142936883324216,
458 0.012461562046896614, 0.0014084973492408186,
459 0.35160648971214437, 0, 0, 0});
460 prop.SetCalibError(0.25, 0.05);
462 prop.SetAvgLatency(35_ms);
463 prop.SetLatencyStdDev(8_ms);
484 (Eigen::MatrixXd(3, 3) << 769.6873145148892, 0.0, 486.1096609458122,
485 0.0, 773.8164483705323, 384.66071662358354, 0.0, 0.0, 1.0)
487 Eigen::Matrix<double, 8, 1>{0.189462064814501, -0.49903003669627627,
488 0.007468423590519429, 0.002496885298683693,
489 0.3443122090208624, 0, 0, 0});
490 prop.SetCalibError(0.35, 0.10);
492 prop.SetAvgLatency(50_ms);
493 prop.SetLatencyStdDev(15_ms);
514 (Eigen::MatrixXd(3, 3) << 1011.3749416937393, 0.0, 645.4955139388737,
515 0.0, 1008.5391755084075, 508.32877656020196, 0.0, 0.0, 1.0)
517 Eigen::Matrix<double, 8, 1>{0.13730101577061535, -0.2904345656989261,
518 8.32475714507539E-4, -3.694397782014239E-4,
519 0.09487962227027584, 0, 0, 0});
520 prop.SetCalibError(0.37, 0.06);
522 prop.SetAvgLatency(60_ms);
523 prop.SetLatencyStdDev(20_ms);
528 std::mt19937 generator{std::random_device{}()};
529 std::normal_distribution<float> gaussian{0.0, 1.0};
530 std::uniform_real_distribution<float> uniform{0.0, 1.0};
534 Eigen::Matrix<double, 3, 3> camIntrinsics;
535 Eigen::Matrix<double, 8, 1> distCoeffs;
536 double avgErrorPx{0};
537 double errorStdDevPx{0};
538 units::second_t frameSpeed{0};
539 units::second_t exposureTime{0};
540 units::second_t avgLatency{0};
541 units::second_t latencyStdDev{0};
542 std::vector<Eigen::Matrix<double, 3, 1>> viewplanes{};
Calibration and performance values for this camera.
Definition SimCameraProperties.h:59
frc::Rotation3d GetPixelRot(const cv::Point2d &point) const
Finds the yaw and pitch to the given image point.
Definition SimCameraProperties.h:236
static SimCameraProperties LL2_960_720()
Creates a set of camera properties matching those of a Limelight 2 running at 960x720 resolution.
Definition SimCameraProperties.h:480
Eigen::Matrix< double, 8, 1 > GetDistCoeffs() const
Returns the camera calibration's distortion coefficients, in OPENCV8 form.
Definition SimCameraProperties.h:158
std::vector< cv::Point2f > EstPixelNoise(const std::vector< cv::Point2f > &points)
Returns these points after applying this camera's estimated noise.
Definition SimCameraProperties.h:331
SimCameraProperties(std::string path, int width, int height)
Reads camera properties from a PhotonVision config.json file.
Definition SimCameraProperties.h:73
void SetFPS(units::hertz_t fps)
Sets the simulated FPS for this camera.
Definition SimCameraProperties.h:91
void SetCalibError(double newAvgErrorPx, double newErrorStdDevPx)
Definition SimCameraProperties.h:80
int GetResHeight() const
Gets the height of the simulated camera image.
Definition SimCameraProperties.h:137
int GetResWidth() const
Gets the width of the simulated camera image.
Definition SimCameraProperties.h:130
void SetLatencyStdDev(units::second_t latencyStdDev)
Sets the simulated latency variation for this camera.
Definition SimCameraProperties.h:121
static SimCameraProperties PERFECT_90DEG()
Creates a set of camera properties where the camera has a 960x720 resolution, 90 degree FOV,...
Definition SimCameraProperties.h:375
void SetExposureTime(units::second_t exposureTime)
Sets the simulated exposure time for this camera.
Definition SimCameraProperties.h:101
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 frust...
int GetResArea() const
Gets the area of the simulated camera image.
Definition SimCameraProperties.h:144
units::second_t GetExposureTime() const
Gets the exposure time of the simulated camera.
Definition SimCameraProperties.h:179
frc::Rotation2d GetPixelYaw(double pixelX) const
The yaw from the principal point of this camera to the pixel x value.
Definition SimCameraProperties.h:209
void SetAvgLatency(units::second_t avgLatency)
Sets the simulated latency for this camera.
Definition SimCameraProperties.h:112
SimCameraProperties()
Default constructor which is the same as PERFECT_90DEG.
Definition SimCameraProperties.h:62
static SimCameraProperties LL2_1280_720()
Creates a set of camera properties matching those of a Limelight 2 running at 1280x720 resolution.
Definition SimCameraProperties.h:510
double GetAspectRatio() const
Definition SimCameraProperties.h:146
units::second_t EstLatency()
Returns an estimation of a frame's processing latency with noise added.
Definition SimCameraProperties.h:355
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 t...
Definition SimCameraProperties.h:266
units::second_t GetFrameSpeed() const
Gets the time per frame of the simulated camera.
Definition SimCameraProperties.h:172
frc::Rotation2d GetDiagFOV() const
Definition SimCameraProperties.h:292
units::second_t GetAverageLatency() const
Gets the average latency of the simulated camera.
Definition SimCameraProperties.h:186
frc::Rotation2d GetHorizFOV() const
Definition SimCameraProperties.h:280
static SimCameraProperties PI4_LIFECAM_320_240()
Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at...
Definition SimCameraProperties.h:390
units::second_t GetLatencyStdDev() const
Gets the time per frame of the simulated camera.
Definition SimCameraProperties.h:193
void SetCalibration(int width, int height, frc::Rotation2d fovDiag)
frc::Rotation2d GetPixelPitch(double pixelY) const
The pitch from the principal point of this camera to the pixel y value.
Definition SimCameraProperties.h:223
static SimCameraProperties LL2_640_480()
Creates a set of camera properties matching those of a Limelight 2 running at 640x480 resolution.
Definition SimCameraProperties.h:450
units::second_t EstSecUntilNextFrame()
Estimates how long until the next frame should be processed.
Definition SimCameraProperties.h:365
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.
Definition SimCameraProperties.h:202
frc::Rotation2d GetVertFOV() const
Definition SimCameraProperties.h:286
static SimCameraProperties PI4_LIFECAM_640_480()
Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry Pi 4 at...
Definition SimCameraProperties.h:420
Eigen::Matrix< double, 3, 3 > GetIntrinsics() const
Definition SimCameraProperties.h:150
void SetCalibration(int width, int height, const Eigen::Matrix< double, 3, 3 > &newCamIntrinsics, const Eigen::Matrix< double, 8, 1 > &newDistCoeffs)
units::hertz_t GetFPS() const
Gets the FPS of the simulated camera.
Definition SimCameraProperties.h:165
static std::vector< cv::Point2f > GetConvexHull(const std::vector< cv::Point2f > &points)
Definition OpenCVHelp.h:45
Definition TargetModel.h:27