PhotonVision C++ v2026.2.2
Loading...
Searching...
No Matches
SimCameraProperties.h
Go to the documentation of this file.
1/*
2 * MIT License
3 *
4 * Copyright (c) PhotonVision
5 *
6 * Permission is hereby granted, free of charge, to any person obtaining a copy
7 * of this software and associated documentation files (the "Software"), to deal
8 * in the Software without restriction, including without limitation the rights
9 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10 * copies of the Software, and to permit persons to whom the Software is
11 * furnished to do so, subject to the following conditions:
12 *
13 * The above copyright notice and this permission notice shall be included in
14 * all copies or substantial portions of the Software.
15 *
16 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22 * SOFTWARE.
23 */
24
25#pragma once
26
27#include <algorithm>
28#include <random>
29#include <string>
30#include <utility>
31#include <vector>
32
33#include <Eigen/Core>
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>
41
42namespace photon {
43
44/**
45 * Calibration and performance values for this camera.
46 *
47 * The resolution will affect the accuracy of projected(3d to 2d) target
48 * corners and similarly the severity of image noise on estimation(2d to 3d).
49 *
50 * The camera intrinsics and distortion coefficients describe the results of
51 * calibration, and how to map between 3d field points and 2d image points.
52 *
53 * The performance values (framerate/exposure time, latency) determine how
54 * often results should be updated and with how much latency in simulation. High
55 * exposure time causes motion blur which can inhibit target detection while
56 * moving. Note that latency estimation does not account for network latency and
57 * the latency reported will always be perfect.
58 */
60 public:
61 /** Default constructor which is the same as PERFECT_90DEG */
62 SimCameraProperties() { SetCalibration(960, 720, frc::Rotation2d{90_deg}); }
63
64 /**
65 * Reads camera properties from a PhotonVision config.json file.
66 * This is only the resolution, camera intrinsics, distortion coefficients,
67 * and average/std. dev. pixel error. Other camera properties must be set.
68 *
69 * @param path Path to the config.json file
70 * @param width The width of the desired resolution in the JSON
71 * @param height The height of the desired resolution in the JSON
72 */
73 SimCameraProperties(std::string path, int width, int height) {}
74
75 void SetCalibration(int width, int height, frc::Rotation2d fovDiag);
76 void SetCalibration(int width, int height,
77 const Eigen::Matrix<double, 3, 3>& newCamIntrinsics,
78 const Eigen::Matrix<double, 8, 1>& newDistCoeffs);
79
80 void SetCalibError(double newAvgErrorPx, double newErrorStdDevPx) {
81 avgErrorPx = newAvgErrorPx;
82 errorStdDevPx = newErrorStdDevPx;
83 }
84
85 /**
86 * Sets the simulated FPS for this camera.
87 *
88 * @param fps The average frames per second the camera should process at.
89 * **Exposure time limits FPS if set!**
90 */
91 void SetFPS(units::hertz_t fps) {
92 frameSpeed = units::math::max(1 / fps, exposureTime);
93 }
94
95 /**
96 * Sets the simulated exposure time for this camera.
97 *
98 * @param exposureTime The amount of time the "shutter" is open for one frame.
99 * Affects motion blur. **Frame speed(from FPS) is limited to this!**
100 */
101 void SetExposureTime(units::second_t exposureTime) {
102 this->exposureTime = exposureTime;
103 frameSpeed = units::math::max(frameSpeed, this->exposureTime);
104 }
105
106 /**
107 * Sets the simulated latency for this camera.
108 *
109 * @param avgLatency The average latency (from image capture to data
110 * published) a frame should have
111 */
112 void SetAvgLatency(units::second_t avgLatency) {
113 this->avgLatency = avgLatency;
114 }
115
116 /**
117 * Sets the simulated latency variation for this camera.
118 *
119 * @param latencyStdDev The standard deviation of the latency
120 */
121 void SetLatencyStdDev(units::second_t latencyStdDev) {
122 this->latencyStdDev = latencyStdDev;
123 }
124
125 /**
126 * Gets the width of the simulated camera image.
127 *
128 * @return The width in pixels
129 */
130 int GetResWidth() const { return resWidth; }
131
132 /**
133 * Gets the height of the simulated camera image.
134 *
135 * @return The height in pixels
136 */
137 int GetResHeight() const { return resHeight; }
138
139 /**
140 * Gets the area of the simulated camera image.
141 *
142 * @return The area in pixels
143 */
144 int GetResArea() const { return resWidth * resHeight; }
145
146 double GetAspectRatio() const {
147 return static_cast<double>(resWidth) / static_cast<double>(resHeight);
148 }
149
150 Eigen::Matrix<double, 3, 3> GetIntrinsics() const { return camIntrinsics; }
151
152 /**
153 * Returns the camera calibration's distortion coefficients, in OPENCV8 form.
154 * Higher-order terms are set to 0
155 *
156 * @return The distortion coefficients in an 8x1 matrix
157 */
158 Eigen::Matrix<double, 8, 1> GetDistCoeffs() const { return distCoeffs; }
159
160 /**
161 * Gets the FPS of the simulated camera.
162 *
163 * @return The FPS
164 */
165 units::hertz_t GetFPS() const { return 1 / frameSpeed; }
166
167 /**
168 * Gets the time per frame of the simulated camera.
169 *
170 * @return The time per frame
171 */
172 units::second_t GetFrameSpeed() const { return frameSpeed; }
173
174 /**
175 * Gets the exposure time of the simulated camera.
176 *
177 * @return The exposure time
178 */
179 units::second_t GetExposureTime() const { return exposureTime; }
180
181 /**
182 * Gets the average latency of the simulated camera.
183 *
184 * @return The average latency
185 */
186 units::second_t GetAverageLatency() const { return avgLatency; }
187
188 /**
189 * Gets the time per frame of the simulated camera.
190 *
191 * @return The time per frame
192 */
193 units::second_t GetLatencyStdDev() const { return latencyStdDev; }
194
195 /**
196 * The percentage (0 - 100) of this camera's resolution the contour takes up
197 * in pixels of the image.
198 *
199 * @param points Points of the contour
200 * @return The percentage
201 */
202 double GetContourAreaPercent(const std::vector<cv::Point2f>& points) {
203 return cv::contourArea(photon::OpenCVHelp::GetConvexHull(points)) /
204 GetResArea() * 100;
205 }
206
207 /** The yaw from the principal point of this camera to the pixel x value.
208 * Positive values left. */
209 frc::Rotation2d GetPixelYaw(double pixelX) const {
210 double fx = camIntrinsics(0, 0);
211 double cx = camIntrinsics(0, 2);
212 double xOffset = cx - pixelX;
213 return frc::Rotation2d{fx, xOffset};
214 }
215
216 /**
217 * The pitch from the principal point of this camera to the pixel y value.
218 * Pitch is positive down.
219 *
220 * Note that this angle is naively computed and may be incorrect. See
221 * #getCorrectedPixelRot(const cv::Point2d).
222 */
223 frc::Rotation2d GetPixelPitch(double pixelY) const {
224 double fy = camIntrinsics(1, 1);
225 double cy = camIntrinsics(1, 2);
226 double yOffset = cy - pixelY;
227 return frc::Rotation2d{fy, -yOffset};
228 }
229 /**
230 * Finds the yaw and pitch to the given image point. Yaw is positive left, and
231 * pitch is positive down.
232 *
233 * Note that pitch is naively computed and may be incorrect. See
234 * #getCorrectedPixelRot(const cv::Point2d).
235 */
236 frc::Rotation3d GetPixelRot(const cv::Point2d& point) const {
237 return frc::Rotation3d{0_rad, GetPixelPitch(point.y).Radians(),
238 GetPixelYaw(point.x).Radians()};
239 }
240
241 /**
242 * Gives the yaw and pitch of the line intersecting the camera lens and the
243 * given pixel coordinates on the sensor. Yaw is positive left, and pitch
244 * positive down.
245 *
246 * The pitch traditionally calculated from pixel offsets do not correctly
247 * account for non-zero values of yaw because of perspective distortion (not
248 * to be confused with lens distortion)-- for example, the pitch angle is
249 * naively calculated as:
250 *
251 * <pre>pitch = arctan(pixel y offset / focal length y)<pre>
252 *
253 * However, using focal length as a side of the associated right triangle is
254 * not correct when the pixel x value is not 0, because the distance from this
255 * pixel (projected on the x-axis) to the camera lens increases. Projecting a
256 * line back out of the camera with these naive angles will not intersect the
257 * 3d point that was originally projected into this 2d pixel. Instead, this
258 * length should be:
259 *
260 * <pre>focal length y ⟶ (focal length y / cos(arctan(pixel x offset / focal
261 * length x)))</pre>
262 *
263 * @return Rotation3d with yaw and pitch of the line projected out of the
264 * camera from the given pixel (roll is zero).
265 */
266 frc::Rotation3d GetCorrectedPixelRot(const cv::Point2d& point) const {
267 double fx = camIntrinsics(0, 0);
268 double cx = camIntrinsics(0, 2);
269 double xOffset = cx - point.x;
270
271 double fy = camIntrinsics(1, 1);
272 double cy = camIntrinsics(1, 2);
273 double yOffset = cy - point.y;
274
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()};
278 }
279
280 frc::Rotation2d GetHorizFOV() const {
281 frc::Rotation2d left = GetPixelYaw(0);
282 frc::Rotation2d right = GetPixelYaw(resWidth);
283 return left - right;
284 }
285
286 frc::Rotation2d GetVertFOV() const {
287 frc::Rotation2d above = GetPixelPitch(0);
288 frc::Rotation2d below = GetPixelPitch(resHeight);
289 return below - above;
290 }
291
292 frc::Rotation2d GetDiagFOV() const {
293 return frc::Rotation2d{
294 units::math::hypot(GetHorizFOV().Radians(), GetVertFOV().Radians())};
295 }
296
297 /**
298 * Determines where the line segment defined by the two given translations
299 * intersects the camera's frustum/field-of-vision, if at all.
300 *
301 * <p>The line is parametrized so any of its points <code>p = t * (b - a) +
302 * a</code>. This method returns these values of t, minimum first, defining
303 * the region of the line segment which is visible in the frustum. If both
304 * ends of the line segment are visible, this simply returns {0, 1}. If, for
305 * example, point b is visible while a is not, and half of the line segment is
306 * inside the camera frustum, {0.5, 1} would be returned.
307 *
308 * @param camRt The change in basis from world coordinates to camera
309 * coordinates. See RotTrlTransform3d#makeRelativeTo(frc::Pose3d).
310 * @param a The initial translation of the line
311 * @param b The final translation of the line
312 * @return A Pair of Doubles. The values may be empty:
313 * - {double, double} : Two parametrized values(t), minimum first,
314 * representing which segment of the line is visible in the camera frustum.
315 * - {double, std::nullopt} : One value(t) representing a single
316 * intersection point. For example, the line only intersects the intersection
317 * of two adjacent viewplanes.
318 * - {std::nullopt, std::nullopt} : No values. The line segment is not
319 * visible in the camera frustum.
320 */
321 std::pair<std::optional<double>, std::optional<double>> GetVisibleLine(
322 const RotTrlTransform3d& camRt, const frc::Translation3d& a,
323 const frc::Translation3d& b) const;
324
325 /**
326 * Returns these points after applying this camera's estimated noise.
327 *
328 * @param points The points to add noise to
329 * @return The points with noise
330 */
331 std::vector<cv::Point2f> EstPixelNoise(
332 const std::vector<cv::Point2f>& points) {
333 if (avgErrorPx == 0 && errorStdDevPx == 0) {
334 return points;
335 }
336
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;
342 float errorAngle =
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)});
346 }
347 return noisyPts;
348 }
349
350 /**
351 * Returns an estimation of a frame's processing latency with noise added.
352 *
353 * @return The latency estimate
354 */
355 units::second_t EstLatency() {
356 return units::math::max(avgLatency + gaussian(generator) * latencyStdDev,
357 0_s);
358 }
359
360 /**
361 * Estimates how long until the next frame should be processed.
362 *
363 * @return The estimated time until the next frame
364 */
365 units::second_t EstSecUntilNextFrame() {
366 return frameSpeed + units::math::max(0_s, EstLatency() - frameSpeed);
367 }
368
369 /**
370 * Creates a set of camera properties where the camera has a 960x720
371 * resolution, 90 degree FOV, and is a "perfect" lagless camera.
372 *
373 * @return The properties for this theoretical camera
374 */
376
377 /**
378 * Creates a set of camera properties matching those of Microsoft Lifecam
379 * running on a Raspberry Pi 4 at 320x240 resolution.
380 *
381 * Note that this set of properties represents *a camera setup*, not *your
382 * camera setup*. Do not use these camera properties for any non-sim vision
383 * calculations, especially the calibration data. Always use your camera's
384 * calibration data to do vision calculations in non-sim environments. These
385 * properties exist as a sample that may be used to get representative data in
386 * sim.
387 *
388 * @return The properties for this camera setup
389 */
391 SimCameraProperties prop{};
392 prop.SetCalibration(
393 320, 240,
394 (Eigen::MatrixXd(3, 3) << 328.2733242048587, 0.0, 164.8190261141906,
395 0.0, 318.0609794305216, 123.8633838438093, 0.0, 0.0, 1.0)
396 .finished(),
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);
401 prop.SetFPS(30_Hz);
402 prop.SetAvgLatency(30_ms);
403 prop.SetLatencyStdDev(10_ms);
404 return prop;
405 }
406
407 /**
408 * Creates a set of camera properties matching those of Microsoft Lifecam
409 * running on a Raspberry Pi 4 at 640x480 resolution.
410 *
411 * <p>Note that this set of properties represents *a camera setup*, not *your
412 * camera setup*. Do not use these camera properties for any non-sim vision
413 * calculations, especially the calibration data. Always use your camera's
414 * calibration data to do vision calculations in non-sim environments. These
415 * properties exist as a sample that may be used to get representative data in
416 * sim.
417 *
418 * @return The properties for this camera setup
419 */
421 SimCameraProperties prop{};
422 prop.SetCalibration(
423 640, 480,
424 (Eigen::MatrixXd(3, 3) << 669.1428078983059, 0.0, 322.53377249329213,
425 0.0, 646.9843137061716, 241.26567383784163, 0.0, 0.0, 1.0)
426 .finished(),
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);
431 prop.SetFPS(15_Hz);
432 prop.SetAvgLatency(65_ms);
433 prop.SetLatencyStdDev(15_ms);
434 return prop;
435 }
436
437 /**
438 * Creates a set of camera properties matching those of a Limelight 2 running
439 * at 640x480 resolution.
440 *
441 * <p>Note that this set of properties represents *a camera setup*, not *your
442 * camera setup*. Do not use these camera properties for any non-sim vision
443 * calculations, especially the calibration data. Always use your camera's
444 * calibration data to do vision calculations in non-sim environments. These
445 * properties exist as a sample that may be used to get representative data in
446 * sim.
447 *
448 * @return The properties for this camera setup
449 */
451 SimCameraProperties prop{};
452 prop.SetCalibration(
453 640, 480,
454 (Eigen::MatrixXd(3, 3) << 511.22843367007755, 0.0, 323.62049380211096,
455 0.0, 514.5452336723849, 261.8827920543568, 0.0, 0.0, 1.0)
456 .finished(),
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);
461 prop.SetFPS(15_Hz);
462 prop.SetAvgLatency(35_ms);
463 prop.SetLatencyStdDev(8_ms);
464 return prop;
465 }
466
467 /**
468 * Creates a set of camera properties matching those of a Limelight 2 running
469 * at 960x720 resolution.
470 *
471 * <p>Note that this set of properties represents *a camera setup*, not *your
472 * camera setup*. Do not use these camera properties for any non-sim vision
473 * calculations, especially the calibration data. Always use your camera's
474 * calibration data to do vision calculations in non-sim environments. These
475 * properties exist as a sample that may be used to get representative data in
476 * sim.
477 *
478 * @return The properties for this camera setup
479 */
481 SimCameraProperties prop{};
482 prop.SetCalibration(
483 960, 720,
484 (Eigen::MatrixXd(3, 3) << 769.6873145148892, 0.0, 486.1096609458122,
485 0.0, 773.8164483705323, 384.66071662358354, 0.0, 0.0, 1.0)
486 .finished(),
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);
491 prop.SetFPS(10_Hz);
492 prop.SetAvgLatency(50_ms);
493 prop.SetLatencyStdDev(15_ms);
494 return prop;
495 }
496
497 /**
498 * Creates a set of camera properties matching those of a Limelight 2 running
499 * at 1280x720 resolution.
500 *
501 * <p>Note that this set of properties represents *a camera setup*, not *your
502 * camera setup*. Do not use these camera properties for any non-sim vision
503 * calculations, especially the calibration data. Always use your camera's
504 * calibration data to do vision calculations in non-sim environments. These
505 * properties exist as a sample that may be used to get representative data in
506 * sim.
507 *
508 * @return The properties for this camera setup
509 */
511 SimCameraProperties prop{};
512 prop.SetCalibration(
513 1280, 720,
514 (Eigen::MatrixXd(3, 3) << 1011.3749416937393, 0.0, 645.4955139388737,
515 0.0, 1008.5391755084075, 508.32877656020196, 0.0, 0.0, 1.0)
516 .finished(),
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);
521 prop.SetFPS(7_Hz);
522 prop.SetAvgLatency(60_ms);
523 prop.SetLatencyStdDev(20_ms);
524 return prop;
525 }
526
527 private:
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};
531
532 int resWidth;
533 int resHeight;
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{};
543};
544} // namespace photon
Definition RotTrlTransform3d.h:27
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