Skip to content

Commit af03caa

Browse files
committed
Copy files in
1 parent 5210129 commit af03caa

File tree

3 files changed

+546
-0
lines changed

3 files changed

+546
-0
lines changed
Lines changed: 177 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,177 @@
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+
#include "cpnp/constrained_pnp.h"
26+
#include <gtest/gtest.h>
27+
28+
#include <iostream>
29+
#include <vector>
30+
31+
#include <frc/geometry/Transform2d.h>
32+
#include <frc/geometry/Translation2d.h>
33+
#include <units/length.h>
34+
35+
/// @brief Get the positions of the corners of a tag relative to the tag origin, in homogeneous coordinates.
36+
/// @return A 4x4 matrix where the first three rows are the x, y, and z coordinates of the corners, and the last row is all ones.
37+
Eigen::Matrix4d tagCenterToCorners() {
38+
const units::meter_t width{6.0_in};
39+
const units::meter_t height{6.0_in};
40+
41+
Eigen::Matrix<double, 4, 3> corners {};
42+
corners << 0, -width.value(), -height.value(),
43+
0, width.value(), -height.value(),
44+
0, width.value(), height.value(),
45+
0, -width.value(), height.value();
46+
47+
Eigen::Matrix4d ret {};
48+
ret.block(0, 0, 3, 4) = corners.transpose();
49+
ret.row(3) = Eigen::Matrix<double, 1, 4>::Ones();
50+
51+
return ret;
52+
}
53+
54+
/// @brief Get a list of test tags' corners in homogeneous coordinates. The locations of these tags is hard-coded, because I'm lazy
55+
/// @return A 4xN matrix where the first three rows are the x, y, and z coordinates of the corners, and the last row is all ones.
56+
Eigen::Matrix<double, 4, Eigen::Dynamic> getTestTags() {
57+
// change me to add more tags
58+
Eigen::Matrix<double, 4, Eigen::Dynamic> ret(4, 8);
59+
60+
auto tagCorners = tagCenterToCorners();
61+
62+
// Add all the corners of tag 1, located at (2, 0, 1) and rotated 180 degrees
63+
// about +Z
64+
auto tag1pose = frc::Pose3d{frc::Translation3d{2_m, 0_m, 1_m},
65+
frc::Rotation3d{0_deg, 0_deg, 180_deg}}
66+
.ToMatrix();
67+
68+
ret.block(0, 0, 4, 4) = tag1pose * tagCorners;
69+
70+
// Add all the corners of tag 2, located at (2, 1, 1) and rotated 180 degrees
71+
// about +Z
72+
auto tag2pose = frc::Pose3d{frc::Translation3d{2_m, 1_m, 1_m},
73+
frc::Rotation3d{0_deg, 0_deg, 180_deg}}
74+
.ToMatrix();
75+
76+
ret.block(0, 4, 4, 4) = tag2pose * tagCorners;
77+
78+
return ret;
79+
}
80+
81+
82+
/// @brief Project the corners of the tags into the camera frame.
83+
/// @param K OpenCV camera calibration matrix
84+
/// @param field2camera_wpi The location of the camera in the field frame. This is the "wpi" camera pose, with X forward, Y left, and Z up.
85+
/// @param field2corners The locations of the corners of the tags in the field frame
86+
/// @return Observed pixel locations
87+
Eigen::Matrix<double, 2, Eigen::Dynamic>
88+
projectPoints(double f_x,
89+
double f_y,
90+
double c_x,
91+
double c_y,
92+
Eigen::Matrix4d field2camera_wpi,
93+
Eigen::Matrix<double, 4, Eigen::Dynamic> field2corners) {
94+
// robot is ENU, cameras are SDE
95+
Eigen::Matrix4d camera2opencv{
96+
{0, 0, 1, 0},
97+
{-1, 0, 0, 0},
98+
{0, -1, 0, 0},
99+
{0, 0, 0, 1},
100+
};
101+
Eigen::Matrix4d field2camera = field2camera_wpi * camera2opencv;
102+
103+
// transform the points to camera space
104+
auto camera2corners = field2camera.inverse() * field2corners;
105+
106+
// project the points. This is verbose but whatever
107+
Eigen::Matrix<double, 3, 3> K;
108+
K << f_x, 0, c_x, 0, f_y, c_y, 0, 0, 1;
109+
auto pointsUnnormalized =
110+
K * camera2corners.block(0, 0, 3, camera2corners.cols());
111+
auto u =
112+
pointsUnnormalized.row(0).array() / pointsUnnormalized.row(2).array();
113+
auto v =
114+
pointsUnnormalized.row(1).array() / pointsUnnormalized.row(2).array();
115+
116+
Eigen::Matrix<double, 2, Eigen::Dynamic> ret(2, camera2corners.cols());
117+
ret.row(0) = u;
118+
ret.row(1) = v;
119+
return ret;
120+
}
121+
122+
TEST(PoseTest, Projection) {
123+
// cpnp::ProblemParams params(4);
124+
125+
// params.K << 599.375, 0., 479.5, 0., 599.16666667, 359.5, 0., 0., 1.;
126+
// params.K << 100, 0., 0, 0., 100, 0, 0., 0., 1.;
127+
128+
// params.f_x = 100;
129+
// params.f_y = 100;
130+
// params.c_x = 0;
131+
// params.c_y = 0;
132+
133+
// params.worldPoints = getTestTags();
134+
135+
// frc::Transform3d robot2camera {};
136+
// params.imagePoints = projectPoints(params.f_x, params.f_y, params.c_x, params.c_y, robot2camera.ToMatrix(), params.worldPoints);
137+
138+
// std::cout << "world points:\n" << params.worldPoints << std::endl;
139+
// std::cout << "image points:\n" << params.imagePoints << std::endl;
140+
}
141+
142+
TEST(PoseTest, Naive) {
143+
cpnp::ProblemParams params;
144+
145+
params.f_x = 100;
146+
params.f_y = 100;
147+
params.c_x = 0;
148+
params.c_y = 0;
149+
150+
auto tags = getTestTags();
151+
frc::Transform3d robot2camera {frc::Pose3d{}, frc::Pose3d{frc::Translation3d{-1.3_m, 0.25_m, 0_m}, frc::Rotation3d{0_rad, 0_rad, -1.5_rad}}};
152+
auto imgpoints = projectPoints(params.f_x, params.f_y, params.c_x, params.c_y, robot2camera.ToMatrix(), tags);
153+
154+
for (int i = 0; i < tags.cols(); ++i) {
155+
params.imagePoints.push_back(imgpoints(0, i));
156+
params.imagePoints.push_back(imgpoints(1, i));
157+
158+
params.worldPoints.push_back(tags(0, i));
159+
params.worldPoints.push_back(tags(1, i));
160+
params.worldPoints.push_back(tags(2, i));
161+
}
162+
163+
auto t0 = std::chrono::high_resolution_clock::now();
164+
auto polynomial_ret = cpnp::solve_polynomial(params);
165+
auto t1 = std::chrono::high_resolution_clock::now();
166+
167+
fmt::println("Polynomial solve time: {}ms", std::chrono::duration_cast<std::chrono::nanoseconds>(t1-t0).count() / 1e6);
168+
169+
auto t2 = std::chrono::high_resolution_clock::now();
170+
auto naive_ret = cpnp::solve_naive(params);
171+
auto t3 = std::chrono::high_resolution_clock::now();
172+
173+
fmt::println("Naive solve time: {}ms", std::chrono::duration_cast<std::chrono::nanoseconds>(t3-t2).count() / 1e6);
174+
175+
fmt::println("Polynomial method says robot is at:\n{}", polynomial_ret.ToMatrix());
176+
fmt::println("Naive method says robot is at:\n{}", naive_ret.ToMatrix());
177+
}

0 commit comments

Comments
 (0)