36#include <frc/Errors.h>
37#include <frc/MathUtil.h>
38#include <frc/geometry/Rotation2d.h>
39#include <frc/geometry/Translation3d.h>
40#include <units/frequency.h>
41#include <units/time.h>
51 const Eigen::Matrix<double, 3, 3>& newCamIntrinsics,
52 const Eigen::Matrix<double, 8, 1>& newDistCoeffs);
55 avgErrorPx = newAvgErrorPx;
56 errorStdDevPx = newErrorStdDevPx;
60 frameSpeed = units::math::max(1 / fps, exposureTime);
64 exposureTime = newExposureTime;
65 frameSpeed = units::math::max(frameSpeed, exposureTime);
69 avgLatency = newAvgLatency;
73 latencyStdDev = newLatencyStdDev;
83 return static_cast<double>(resWidth) /
static_cast<double>(resHeight);
86 Eigen::Matrix<double, 3, 3>
GetIntrinsics()
const {
return camIntrinsics; }
88 Eigen::Matrix<double, 8, 1>
GetDistCoeffs()
const {
return distCoeffs; }
90 units::hertz_t
GetFPS()
const {
return 1 / frameSpeed; }
106 double fx = camIntrinsics(0, 0);
107 double cx = camIntrinsics(0, 2);
108 double xOffset = cx - pixelX;
109 return frc::Rotation2d{fx, xOffset};
113 double fy = camIntrinsics(1, 1);
114 double cy = camIntrinsics(1, 2);
115 double yOffset = cy - pixelY;
116 return frc::Rotation2d{fy, -yOffset};
120 return frc::Rotation3d{0_rad,
GetPixelPitch(point.y).Radians(),
125 double fx = camIntrinsics(0, 0);
126 double cx = camIntrinsics(0, 2);
127 double xOffset = cx - point.x;
129 double fy = camIntrinsics(1, 1);
130 double cy = camIntrinsics(1, 2);
131 double yOffset = cy - point.y;
133 frc::Rotation2d yaw{fx, xOffset};
134 frc::Rotation2d pitch{fy / std::cos(std::atan(xOffset / fx)), -yOffset};
135 return frc::Rotation3d{0_rad, pitch.Radians(), yaw.Radians()};
147 return below - above;
151 return frc::Rotation2d{
157 const frc::Translation3d& b)
const;
160 const std::vector<cv::Point2f>& points) {
161 if (avgErrorPx == 0 && errorStdDevPx == 0) {
165 std::vector<cv::Point2f> noisyPts;
166 noisyPts.reserve(points.size());
167 for (
size_t i = 0; i < points.size(); i++) {
168 cv::Point2f p = points[i];
169 float error = avgErrorPx + gaussian(generator) * errorStdDevPx;
171 uniform(generator) * 2 * std::numbers::pi - std::numbers::pi;
172 noisyPts.emplace_back(cv::Point2f{p.x + error * std::cos(errorAngle),
173 p.y + error * std::sin(errorAngle)});
179 return units::math::max(avgLatency + gaussian(generator) * latencyStdDev,
184 return frameSpeed + units::math::max(0_s,
EstLatency() - frameSpeed);
193 (Eigen::MatrixXd(3, 3) << 328.2733242048587, 0.0, 164.8190261141906,
194 0.0, 318.0609794305216, 123.8633838438093, 0.0, 0.0, 1.0)
196 Eigen::Matrix<double, 8, 1>{
197 0.09957946553445934, -0.9166265114485799, 0.0019519890627236526,
198 -0.0036071725380870333, 1.5627234622420942, 0, 0, 0});
199 prop.SetCalibError(0.21, 0.0124);
201 prop.SetAvgLatency(30_ms);
202 prop.SetLatencyStdDev(10_ms);
210 (Eigen::MatrixXd(3, 3) << 669.1428078983059, 0.0, 322.53377249329213,
211 0.0, 646.9843137061716, 241.26567383784163, 0.0, 0.0, 1.0)
213 Eigen::Matrix<double, 8, 1>{
214 0.12788470750464645, -1.2350335805796528, 0.0024990767286192732,
215 -0.0026958287600230705, 2.2951386729115537, 0, 0, 0});
216 prop.SetCalibError(0.26, 0.046);
218 prop.SetAvgLatency(65_ms);
219 prop.SetLatencyStdDev(15_ms);
227 (Eigen::MatrixXd(3, 3) << 511.22843367007755, 0.0, 323.62049380211096,
228 0.0, 514.5452336723849, 261.8827920543568, 0.0, 0.0, 1.0)
230 Eigen::Matrix<double, 8, 1>{0.1917469998873756, -0.5142936883324216,
231 0.012461562046896614, 0.0014084973492408186,
232 0.35160648971214437, 0, 0, 0});
233 prop.SetCalibError(0.25, 0.05);
235 prop.SetAvgLatency(35_ms);
236 prop.SetLatencyStdDev(8_ms);
244 (Eigen::MatrixXd(3, 3) << 769.6873145148892, 0.0, 486.1096609458122,
245 0.0, 773.8164483705323, 384.66071662358354, 0.0, 0.0, 1.0)
247 Eigen::Matrix<double, 8, 1>{0.189462064814501, -0.49903003669627627,
248 0.007468423590519429, 0.002496885298683693,
249 0.3443122090208624, 0, 0, 0});
250 prop.SetCalibError(0.35, 0.10);
252 prop.SetAvgLatency(50_ms);
253 prop.SetLatencyStdDev(15_ms);
261 (Eigen::MatrixXd(3, 3) << 1011.3749416937393, 0.0, 645.4955139388737,
262 0.0, 1008.5391755084075, 508.32877656020196, 0.0, 0.0, 1.0)
264 Eigen::Matrix<double, 8, 1>{0.13730101577061535, -0.2904345656989261,
265 8.32475714507539E-4, -3.694397782014239E-4,
266 0.09487962227027584, 0, 0, 0});
267 prop.SetCalibError(0.37, 0.06);
269 prop.SetAvgLatency(60_ms);
270 prop.SetLatencyStdDev(20_ms);
275 std::mt19937 generator{std::random_device{}()};
276 std::normal_distribution<float> gaussian{0.0, 1.0};
277 std::uniform_real_distribution<float> uniform{0.0, 1.0};
281 Eigen::Matrix<double, 3, 3> camIntrinsics;
282 Eigen::Matrix<double, 8, 1> distCoeffs;
284 double errorStdDevPx;
285 units::second_t frameSpeed{0};
286 units::second_t exposureTime{0};
287 units::second_t avgLatency{0};
288 units::second_t latencyStdDev{0};
289 std::vector<Eigen::Matrix<double, 3, 1>> viewplanes{};
Definition SimCameraProperties.h:44
frc::Rotation3d GetPixelRot(const cv::Point2d &point) const
Definition SimCameraProperties.h:119
static SimCameraProperties LL2_960_720()
Definition SimCameraProperties.h:240
Eigen::Matrix< double, 8, 1 > GetDistCoeffs() const
Definition SimCameraProperties.h:88
std::vector< cv::Point2f > EstPixelNoise(const std::vector< cv::Point2f > &points)
Definition SimCameraProperties.h:159
SimCameraProperties(std::string path, int width, int height)
Definition SimCameraProperties.h:47
void SetExposureTime(units::second_t newExposureTime)
Definition SimCameraProperties.h:63
void SetFPS(units::hertz_t fps)
Definition SimCameraProperties.h:59
void SetCalibError(double newAvgErrorPx, double newErrorStdDevPx)
Definition SimCameraProperties.h:54
int GetResHeight() const
Definition SimCameraProperties.h:78
int GetResWidth() const
Definition SimCameraProperties.h:76
static SimCameraProperties PERFECT_90DEG()
Definition SimCameraProperties.h:187
std::pair< std::optional< double >, std::optional< double > > GetVisibleLine(const RotTrlTransform3d &camRt, const frc::Translation3d &a, const frc::Translation3d &b) const
int GetResArea() const
Definition SimCameraProperties.h:80
units::second_t GetExposureTime() const
Definition SimCameraProperties.h:94
frc::Rotation2d GetPixelYaw(double pixelX) const
Definition SimCameraProperties.h:105
void SetAvgLatency(units::second_t newAvgLatency)
Definition SimCameraProperties.h:68
void SetLatencyStdDev(units::second_t newLatencyStdDev)
Definition SimCameraProperties.h:72
SimCameraProperties()
Definition SimCameraProperties.h:46
static SimCameraProperties LL2_1280_720()
Definition SimCameraProperties.h:257
double GetAspectRatio() const
Definition SimCameraProperties.h:82
units::second_t EstLatency()
Definition SimCameraProperties.h:178
frc::Rotation3d GetCorrectedPixelRot(const cv::Point2d &point) const
Definition SimCameraProperties.h:124
units::second_t GetFrameSpeed() const
Definition SimCameraProperties.h:92
frc::Rotation2d GetDiagFOV() const
Definition SimCameraProperties.h:150
units::second_t GetAverageLatency() const
Definition SimCameraProperties.h:96
frc::Rotation2d GetHorizFOV() const
Definition SimCameraProperties.h:138
static SimCameraProperties PI4_LIFECAM_320_240()
Definition SimCameraProperties.h:189
units::second_t GetLatencyStdDev() const
Definition SimCameraProperties.h:98
void SetCalibration(int width, int height, frc::Rotation2d fovDiag)
frc::Rotation2d GetPixelPitch(double pixelY) const
Definition SimCameraProperties.h:112
static SimCameraProperties LL2_640_480()
Definition SimCameraProperties.h:223
units::second_t EstSecUntilNextFrame()
Definition SimCameraProperties.h:183
double GetContourAreaPercent(const std::vector< cv::Point2f > &points)
Definition SimCameraProperties.h:100
frc::Rotation2d GetVertFOV() const
Definition SimCameraProperties.h:144
static SimCameraProperties PI4_LIFECAM_640_480()
Definition SimCameraProperties.h:206
Eigen::Matrix< double, 3, 3 > GetIntrinsics() const
Definition SimCameraProperties.h:86
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
Definition SimCameraProperties.h:90
static std::vector< cv::Point2f > GetConvexHull(const std::vector< cv::Point2f > &points)
Definition OpenCVHelp.h:45
Definition VisionEstimation.h:32