PhotonVision C++ dev-v2025.0.0-beta-8-2-gbd1c5c03
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
28
29#include <algorithm>
30#include <random>
31#include <string>
32#include <utility>
33#include <vector>
34
35#include <Eigen/Core>
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>
42
43namespace photon {
45 public:
46 SimCameraProperties() { SetCalibration(960, 720, frc::Rotation2d{90_deg}); }
47 SimCameraProperties(std::string path, int width, int height) {}
48
49 void SetCalibration(int width, int height, frc::Rotation2d fovDiag);
50 void SetCalibration(int width, int height,
51 const Eigen::Matrix<double, 3, 3>& newCamIntrinsics,
52 const Eigen::Matrix<double, 8, 1>& newDistCoeffs);
53
54 void SetCalibError(double newAvgErrorPx, double newErrorStdDevPx) {
55 avgErrorPx = newAvgErrorPx;
56 errorStdDevPx = newErrorStdDevPx;
57 }
58
59 void SetFPS(units::hertz_t fps) {
60 frameSpeed = units::math::max(1 / fps, exposureTime);
61 }
62
63 void SetExposureTime(units::second_t newExposureTime) {
64 exposureTime = newExposureTime;
65 frameSpeed = units::math::max(frameSpeed, exposureTime);
66 }
67
68 void SetAvgLatency(units::second_t newAvgLatency) {
69 avgLatency = newAvgLatency;
70 }
71
72 void SetLatencyStdDev(units::second_t newLatencyStdDev) {
73 latencyStdDev = newLatencyStdDev;
74 }
75
76 int GetResWidth() const { return resWidth; }
77
78 int GetResHeight() const { return resHeight; }
79
80 int GetResArea() const { return resWidth * resHeight; }
81
82 double GetAspectRatio() const {
83 return static_cast<double>(resWidth) / static_cast<double>(resHeight);
84 }
85
86 Eigen::Matrix<double, 3, 3> GetIntrinsics() const { return camIntrinsics; }
87
88 Eigen::Matrix<double, 8, 1> GetDistCoeffs() const { return distCoeffs; }
89
90 units::hertz_t GetFPS() const { return 1 / frameSpeed; }
91
92 units::second_t GetFrameSpeed() const { return frameSpeed; }
93
94 units::second_t GetExposureTime() const { return exposureTime; }
95
96 units::second_t GetAverageLatency() const { return avgLatency; }
97
98 units::second_t GetLatencyStdDev() const { return latencyStdDev; }
99
100 double GetContourAreaPercent(const std::vector<cv::Point2f>& points) {
101 return cv::contourArea(photon::OpenCVHelp::GetConvexHull(points)) /
102 GetResArea() * 100;
103 }
104
105 frc::Rotation2d GetPixelYaw(double pixelX) const {
106 double fx = camIntrinsics(0, 0);
107 double cx = camIntrinsics(0, 2);
108 double xOffset = cx - pixelX;
109 return frc::Rotation2d{fx, xOffset};
110 }
111
112 frc::Rotation2d GetPixelPitch(double pixelY) const {
113 double fy = camIntrinsics(1, 1);
114 double cy = camIntrinsics(1, 2);
115 double yOffset = cy - pixelY;
116 return frc::Rotation2d{fy, -yOffset};
117 }
118
119 frc::Rotation3d GetPixelRot(const cv::Point2d& point) const {
120 return frc::Rotation3d{0_rad, GetPixelPitch(point.y).Radians(),
121 GetPixelYaw(point.x).Radians()};
122 }
123
124 frc::Rotation3d GetCorrectedPixelRot(const cv::Point2d& point) const {
125 double fx = camIntrinsics(0, 0);
126 double cx = camIntrinsics(0, 2);
127 double xOffset = cx - point.x;
128
129 double fy = camIntrinsics(1, 1);
130 double cy = camIntrinsics(1, 2);
131 double yOffset = cy - point.y;
132
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()};
136 }
137
138 frc::Rotation2d GetHorizFOV() const {
139 frc::Rotation2d left = GetPixelYaw(0);
140 frc::Rotation2d right = GetPixelYaw(resWidth);
141 return left - right;
142 }
143
144 frc::Rotation2d GetVertFOV() const {
145 frc::Rotation2d above = GetPixelPitch(0);
146 frc::Rotation2d below = GetPixelPitch(resHeight);
147 return below - above;
148 }
149
150 frc::Rotation2d GetDiagFOV() const {
151 return frc::Rotation2d{
152 units::math::hypot(GetHorizFOV().Radians(), GetVertFOV().Radians())};
153 }
154
155 std::pair<std::optional<double>, std::optional<double>> GetVisibleLine(
156 const RotTrlTransform3d& camRt, const frc::Translation3d& a,
157 const frc::Translation3d& b) const;
158
159 std::vector<cv::Point2f> EstPixelNoise(
160 const std::vector<cv::Point2f>& points) {
161 if (avgErrorPx == 0 && errorStdDevPx == 0) {
162 return points;
163 }
164
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;
170 float errorAngle =
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)});
174 }
175 return noisyPts;
176 }
177
178 units::second_t EstLatency() {
179 return units::math::max(avgLatency + gaussian(generator) * latencyStdDev,
180 0_s);
181 }
182
183 units::second_t EstSecUntilNextFrame() {
184 return frameSpeed + units::math::max(0_s, EstLatency() - frameSpeed);
185 }
186
188
190 SimCameraProperties prop{};
191 prop.SetCalibration(
192 320, 240,
193 (Eigen::MatrixXd(3, 3) << 328.2733242048587, 0.0, 164.8190261141906,
194 0.0, 318.0609794305216, 123.8633838438093, 0.0, 0.0, 1.0)
195 .finished(),
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);
200 prop.SetFPS(30_Hz);
201 prop.SetAvgLatency(30_ms);
202 prop.SetLatencyStdDev(10_ms);
203 return prop;
204 }
205
207 SimCameraProperties prop{};
208 prop.SetCalibration(
209 640, 480,
210 (Eigen::MatrixXd(3, 3) << 669.1428078983059, 0.0, 322.53377249329213,
211 0.0, 646.9843137061716, 241.26567383784163, 0.0, 0.0, 1.0)
212 .finished(),
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);
217 prop.SetFPS(15_Hz);
218 prop.SetAvgLatency(65_ms);
219 prop.SetLatencyStdDev(15_ms);
220 return prop;
221 }
222
224 SimCameraProperties prop{};
225 prop.SetCalibration(
226 640, 480,
227 (Eigen::MatrixXd(3, 3) << 511.22843367007755, 0.0, 323.62049380211096,
228 0.0, 514.5452336723849, 261.8827920543568, 0.0, 0.0, 1.0)
229 .finished(),
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);
234 prop.SetFPS(15_Hz);
235 prop.SetAvgLatency(35_ms);
236 prop.SetLatencyStdDev(8_ms);
237 return prop;
238 }
239
241 SimCameraProperties prop{};
242 prop.SetCalibration(
243 960, 720,
244 (Eigen::MatrixXd(3, 3) << 769.6873145148892, 0.0, 486.1096609458122,
245 0.0, 773.8164483705323, 384.66071662358354, 0.0, 0.0, 1.0)
246 .finished(),
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);
251 prop.SetFPS(10_Hz);
252 prop.SetAvgLatency(50_ms);
253 prop.SetLatencyStdDev(15_ms);
254 return prop;
255 }
256
258 SimCameraProperties prop{};
259 prop.SetCalibration(
260 1280, 720,
261 (Eigen::MatrixXd(3, 3) << 1011.3749416937393, 0.0, 645.4955139388737,
262 0.0, 1008.5391755084075, 508.32877656020196, 0.0, 0.0, 1.0)
263 .finished(),
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);
268 prop.SetFPS(7_Hz);
269 prop.SetAvgLatency(60_ms);
270 prop.SetLatencyStdDev(20_ms);
271 return prop;
272 }
273
274 private:
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};
278
279 int resWidth;
280 int resHeight;
281 Eigen::Matrix<double, 3, 3> camIntrinsics;
282 Eigen::Matrix<double, 8, 1> distCoeffs;
283 double avgErrorPx;
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{};
290};
291} // namespace photon
Definition RotTrlTransform3d.h:27
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