PhotonVision C++ v2026.0.1-beta
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 {
44 public:
45 SimCameraProperties() { SetCalibration(960, 720, frc::Rotation2d{90_deg}); }
46 SimCameraProperties(std::string path, int width, int height) {}
47
48 void SetCalibration(int width, int height, frc::Rotation2d fovDiag);
49 void SetCalibration(int width, int height,
50 const Eigen::Matrix<double, 3, 3>& newCamIntrinsics,
51 const Eigen::Matrix<double, 8, 1>& newDistCoeffs);
52
53 void SetCalibError(double newAvgErrorPx, double newErrorStdDevPx) {
54 avgErrorPx = newAvgErrorPx;
55 errorStdDevPx = newErrorStdDevPx;
56 }
57
58 void SetFPS(units::hertz_t fps) {
59 frameSpeed = units::math::max(1 / fps, exposureTime);
60 }
61
62 void SetExposureTime(units::second_t newExposureTime) {
63 exposureTime = newExposureTime;
64 frameSpeed = units::math::max(frameSpeed, exposureTime);
65 }
66
67 void SetAvgLatency(units::second_t newAvgLatency) {
68 avgLatency = newAvgLatency;
69 }
70
71 void SetLatencyStdDev(units::second_t newLatencyStdDev) {
72 latencyStdDev = newLatencyStdDev;
73 }
74
75 int GetResWidth() const { return resWidth; }
76
77 int GetResHeight() const { return resHeight; }
78
79 int GetResArea() const { return resWidth * resHeight; }
80
81 double GetAspectRatio() const {
82 return static_cast<double>(resWidth) / static_cast<double>(resHeight);
83 }
84
85 Eigen::Matrix<double, 3, 3> GetIntrinsics() const { return camIntrinsics; }
86
87 Eigen::Matrix<double, 8, 1> GetDistCoeffs() const { return distCoeffs; }
88
89 units::hertz_t GetFPS() const { return 1 / frameSpeed; }
90
91 units::second_t GetFrameSpeed() const { return frameSpeed; }
92
93 units::second_t GetExposureTime() const { return exposureTime; }
94
95 units::second_t GetAverageLatency() const { return avgLatency; }
96
97 units::second_t GetLatencyStdDev() const { return latencyStdDev; }
98
99 double GetContourAreaPercent(const std::vector<cv::Point2f>& points) {
100 return cv::contourArea(photon::OpenCVHelp::GetConvexHull(points)) /
101 GetResArea() * 100;
102 }
103
104 frc::Rotation2d GetPixelYaw(double pixelX) const {
105 double fx = camIntrinsics(0, 0);
106 double cx = camIntrinsics(0, 2);
107 double xOffset = cx - pixelX;
108 return frc::Rotation2d{fx, xOffset};
109 }
110
111 frc::Rotation2d GetPixelPitch(double pixelY) const {
112 double fy = camIntrinsics(1, 1);
113 double cy = camIntrinsics(1, 2);
114 double yOffset = cy - pixelY;
115 return frc::Rotation2d{fy, -yOffset};
116 }
117
118 frc::Rotation3d GetPixelRot(const cv::Point2d& point) const {
119 return frc::Rotation3d{0_rad, GetPixelPitch(point.y).Radians(),
120 GetPixelYaw(point.x).Radians()};
121 }
122
123 frc::Rotation3d GetCorrectedPixelRot(const cv::Point2d& point) const {
124 double fx = camIntrinsics(0, 0);
125 double cx = camIntrinsics(0, 2);
126 double xOffset = cx - point.x;
127
128 double fy = camIntrinsics(1, 1);
129 double cy = camIntrinsics(1, 2);
130 double yOffset = cy - point.y;
131
132 frc::Rotation2d yaw{fx, xOffset};
133 frc::Rotation2d pitch{fy / std::cos(std::atan(xOffset / fx)), -yOffset};
134 return frc::Rotation3d{0_rad, pitch.Radians(), yaw.Radians()};
135 }
136
137 frc::Rotation2d GetHorizFOV() const {
138 frc::Rotation2d left = GetPixelYaw(0);
139 frc::Rotation2d right = GetPixelYaw(resWidth);
140 return left - right;
141 }
142
143 frc::Rotation2d GetVertFOV() const {
144 frc::Rotation2d above = GetPixelPitch(0);
145 frc::Rotation2d below = GetPixelPitch(resHeight);
146 return below - above;
147 }
148
149 frc::Rotation2d GetDiagFOV() const {
150 return frc::Rotation2d{
151 units::math::hypot(GetHorizFOV().Radians(), GetVertFOV().Radians())};
152 }
153
154 std::pair<std::optional<double>, std::optional<double>> GetVisibleLine(
155 const RotTrlTransform3d& camRt, const frc::Translation3d& a,
156 const frc::Translation3d& b) const;
157
158 std::vector<cv::Point2f> EstPixelNoise(
159 const std::vector<cv::Point2f>& points) {
160 if (avgErrorPx == 0 && errorStdDevPx == 0) {
161 return points;
162 }
163
164 std::vector<cv::Point2f> noisyPts;
165 noisyPts.reserve(points.size());
166 for (size_t i = 0; i < points.size(); i++) {
167 cv::Point2f p = points[i];
168 float error = avgErrorPx + gaussian(generator) * errorStdDevPx;
169 float errorAngle =
170 uniform(generator) * 2 * std::numbers::pi - std::numbers::pi;
171 noisyPts.emplace_back(cv::Point2f{p.x + error * std::cos(errorAngle),
172 p.y + error * std::sin(errorAngle)});
173 }
174 return noisyPts;
175 }
176
177 units::second_t EstLatency() {
178 return units::math::max(avgLatency + gaussian(generator) * latencyStdDev,
179 0_s);
180 }
181
182 units::second_t EstSecUntilNextFrame() {
183 return frameSpeed + units::math::max(0_s, EstLatency() - frameSpeed);
184 }
185
187
189 SimCameraProperties prop{};
190 prop.SetCalibration(
191 320, 240,
192 (Eigen::MatrixXd(3, 3) << 328.2733242048587, 0.0, 164.8190261141906,
193 0.0, 318.0609794305216, 123.8633838438093, 0.0, 0.0, 1.0)
194 .finished(),
195 Eigen::Matrix<double, 8, 1>{
196 0.09957946553445934, -0.9166265114485799, 0.0019519890627236526,
197 -0.0036071725380870333, 1.5627234622420942, 0, 0, 0});
198 prop.SetCalibError(0.21, 0.0124);
199 prop.SetFPS(30_Hz);
200 prop.SetAvgLatency(30_ms);
201 prop.SetLatencyStdDev(10_ms);
202 return prop;
203 }
204
206 SimCameraProperties prop{};
207 prop.SetCalibration(
208 640, 480,
209 (Eigen::MatrixXd(3, 3) << 669.1428078983059, 0.0, 322.53377249329213,
210 0.0, 646.9843137061716, 241.26567383784163, 0.0, 0.0, 1.0)
211 .finished(),
212 Eigen::Matrix<double, 8, 1>{
213 0.12788470750464645, -1.2350335805796528, 0.0024990767286192732,
214 -0.0026958287600230705, 2.2951386729115537, 0, 0, 0});
215 prop.SetCalibError(0.26, 0.046);
216 prop.SetFPS(15_Hz);
217 prop.SetAvgLatency(65_ms);
218 prop.SetLatencyStdDev(15_ms);
219 return prop;
220 }
221
223 SimCameraProperties prop{};
224 prop.SetCalibration(
225 640, 480,
226 (Eigen::MatrixXd(3, 3) << 511.22843367007755, 0.0, 323.62049380211096,
227 0.0, 514.5452336723849, 261.8827920543568, 0.0, 0.0, 1.0)
228 .finished(),
229 Eigen::Matrix<double, 8, 1>{0.1917469998873756, -0.5142936883324216,
230 0.012461562046896614, 0.0014084973492408186,
231 0.35160648971214437, 0, 0, 0});
232 prop.SetCalibError(0.25, 0.05);
233 prop.SetFPS(15_Hz);
234 prop.SetAvgLatency(35_ms);
235 prop.SetLatencyStdDev(8_ms);
236 return prop;
237 }
238
240 SimCameraProperties prop{};
241 prop.SetCalibration(
242 960, 720,
243 (Eigen::MatrixXd(3, 3) << 769.6873145148892, 0.0, 486.1096609458122,
244 0.0, 773.8164483705323, 384.66071662358354, 0.0, 0.0, 1.0)
245 .finished(),
246 Eigen::Matrix<double, 8, 1>{0.189462064814501, -0.49903003669627627,
247 0.007468423590519429, 0.002496885298683693,
248 0.3443122090208624, 0, 0, 0});
249 prop.SetCalibError(0.35, 0.10);
250 prop.SetFPS(10_Hz);
251 prop.SetAvgLatency(50_ms);
252 prop.SetLatencyStdDev(15_ms);
253 return prop;
254 }
255
257 SimCameraProperties prop{};
258 prop.SetCalibration(
259 1280, 720,
260 (Eigen::MatrixXd(3, 3) << 1011.3749416937393, 0.0, 645.4955139388737,
261 0.0, 1008.5391755084075, 508.32877656020196, 0.0, 0.0, 1.0)
262 .finished(),
263 Eigen::Matrix<double, 8, 1>{0.13730101577061535, -0.2904345656989261,
264 8.32475714507539E-4, -3.694397782014239E-4,
265 0.09487962227027584, 0, 0, 0});
266 prop.SetCalibError(0.37, 0.06);
267 prop.SetFPS(7_Hz);
268 prop.SetAvgLatency(60_ms);
269 prop.SetLatencyStdDev(20_ms);
270 return prop;
271 }
272
273 private:
274 std::mt19937 generator{std::random_device{}()};
275 std::normal_distribution<float> gaussian{0.0, 1.0};
276 std::uniform_real_distribution<float> uniform{0.0, 1.0};
277
278 int resWidth;
279 int resHeight;
280 Eigen::Matrix<double, 3, 3> camIntrinsics;
281 Eigen::Matrix<double, 8, 1> distCoeffs;
282 double avgErrorPx{0};
283 double errorStdDevPx{0};
284 units::second_t frameSpeed{0};
285 units::second_t exposureTime{0};
286 units::second_t avgLatency{0};
287 units::second_t latencyStdDev{0};
288 std::vector<Eigen::Matrix<double, 3, 1>> viewplanes{};
289};
290} // namespace photon
Definition RotTrlTransform3d.h:27
Definition SimCameraProperties.h:43
frc::Rotation3d GetPixelRot(const cv::Point2d &point) const
Definition SimCameraProperties.h:118
static SimCameraProperties LL2_960_720()
Definition SimCameraProperties.h:239
Eigen::Matrix< double, 8, 1 > GetDistCoeffs() const
Definition SimCameraProperties.h:87
std::vector< cv::Point2f > EstPixelNoise(const std::vector< cv::Point2f > &points)
Definition SimCameraProperties.h:158
SimCameraProperties(std::string path, int width, int height)
Definition SimCameraProperties.h:46
void SetExposureTime(units::second_t newExposureTime)
Definition SimCameraProperties.h:62
void SetFPS(units::hertz_t fps)
Definition SimCameraProperties.h:58
void SetCalibError(double newAvgErrorPx, double newErrorStdDevPx)
Definition SimCameraProperties.h:53
int GetResHeight() const
Definition SimCameraProperties.h:77
int GetResWidth() const
Definition SimCameraProperties.h:75
static SimCameraProperties PERFECT_90DEG()
Definition SimCameraProperties.h:186
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:79
units::second_t GetExposureTime() const
Definition SimCameraProperties.h:93
frc::Rotation2d GetPixelYaw(double pixelX) const
Definition SimCameraProperties.h:104
void SetAvgLatency(units::second_t newAvgLatency)
Definition SimCameraProperties.h:67
void SetLatencyStdDev(units::second_t newLatencyStdDev)
Definition SimCameraProperties.h:71
SimCameraProperties()
Definition SimCameraProperties.h:45
static SimCameraProperties LL2_1280_720()
Definition SimCameraProperties.h:256
double GetAspectRatio() const
Definition SimCameraProperties.h:81
units::second_t EstLatency()
Definition SimCameraProperties.h:177
frc::Rotation3d GetCorrectedPixelRot(const cv::Point2d &point) const
Definition SimCameraProperties.h:123
units::second_t GetFrameSpeed() const
Definition SimCameraProperties.h:91
frc::Rotation2d GetDiagFOV() const
Definition SimCameraProperties.h:149
units::second_t GetAverageLatency() const
Definition SimCameraProperties.h:95
frc::Rotation2d GetHorizFOV() const
Definition SimCameraProperties.h:137
static SimCameraProperties PI4_LIFECAM_320_240()
Definition SimCameraProperties.h:188
units::second_t GetLatencyStdDev() const
Definition SimCameraProperties.h:97
void SetCalibration(int width, int height, frc::Rotation2d fovDiag)
frc::Rotation2d GetPixelPitch(double pixelY) const
Definition SimCameraProperties.h:111
static SimCameraProperties LL2_640_480()
Definition SimCameraProperties.h:222
units::second_t EstSecUntilNextFrame()
Definition SimCameraProperties.h:182
double GetContourAreaPercent(const std::vector< cv::Point2f > &points)
Definition SimCameraProperties.h:99
frc::Rotation2d GetVertFOV() const
Definition SimCameraProperties.h:143
static SimCameraProperties PI4_LIFECAM_640_480()
Definition SimCameraProperties.h:205
Eigen::Matrix< double, 3, 3 > GetIntrinsics() const
Definition SimCameraProperties.h:85
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:89
static std::vector< cv::Point2f > GetConvexHull(const std::vector< cv::Point2f > &points)
Definition OpenCVHelp.h:45
Definition TargetModel.h:27