WPILibC++ 2025.1.1
Loading...
Searching...
No Matches
homography.h
Go to the documentation of this file.
1/* Copyright (C) 2013-2016, The Regents of The University of Michigan.
2All rights reserved.
3This software was developed in the APRIL Robotics Lab under the
4direction of Edwin Olson, ebolson@umich.edu. This software may be
5available under alternative licensing terms; contact the address above.
6Redistribution and use in source and binary forms, with or without
7modification, are permitted provided that the following conditions are met:
81. Redistributions of source code must retain the above copyright notice, this
9 list of conditions and the following disclaimer.
102. Redistributions in binary form must reproduce the above copyright notice,
11 this list of conditions and the following disclaimer in the documentation
12 and/or other materials provided with the distribution.
13THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
14ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
15WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
16DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
17ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
18(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
19LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
20ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
21(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
22SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23The views and conclusions contained in the software and documentation are those
24of the authors and should not be interpreted as representing official policies,
25either expressed or implied, of the Regents of The University of Michigan.
26*/
27
28#pragma once
29
30#include "matd.h"
31#include "zarray.h"
32
33#ifdef __cplusplus
34extern "C" {
35#endif
36
37 /** Given a 3x3 homography matrix and the focal lengths of the
38 * camera, compute the pose of the tag. The focal lengths should
39 * be given in pixels. For example, if the camera's focal length
40 * is twice the width of the sensor, and the sensor is 600 pixels
41 * across, the focal length in pixels is 2*600. Note that the
42 * focal lengths in the fx and fy direction will be approximately
43 * equal for most lenses, and is not a function of aspect ratio.
44 *
45 * Theory: The homography matrix is the product of the camera
46 * projection matrix and the tag's pose matrix (the matrix that
47 * projects points from the tag's local coordinate system to the
48 * camera's coordinate frame).
49 *
50 * [ h00 h01 h02 h03] = [ fx 0 cx 0 ] [ R00 R01 R02 TX ]
51 * [ h10 h11 h12 h13] = [ 0 fy cy 0 ] [ R10 R11 R12 TY ]
52 * [ h20 h21 h22 h23] = [ 0 0 s 0 ] [ R20 R21 R22 TZ ]
53 * [ 0 0 0 1 ]
54 *
55 * fx is the focal length in the x direction of the camera
56 * (typically measured in pixels), fy is the focal length. cx and
57 * cy give the focal center (usually the middle of the image), and
58 * s is either +1 or -1, depending on the conventions you use. (We
59 * use 1.)
60
61 * When observing a tag, the points we project in world space all
62 * have z=0, so we can form a 3x3 matrix by eliminating the 3rd
63 * column of the pose matrix.
64 *
65 * [ h00 h01 h02 ] = [ fx 0 cx 0 ] [ R00 R01 TX ]
66 * [ h10 h11 h12 ] = [ 0 fy cy 0 ] [ R10 R11 TY ]
67 * [ h20 h21 h22 ] = [ 0 0 s 0 ] [ R20 R21 TZ ]
68 * [ 0 0 1 ]
69 *
70 * (note that these h's are different from the ones above.)
71 *
72 * We can multiply the right-hand side to yield a set of equations
73 * relating the values of h to the values of the pose matrix.
74 *
75 * There are two wrinkles. The first is that the homography matrix
76 * is known only up to scale. We recover the unknown scale by
77 * constraining the magnitude of the first two columns of the pose
78 * matrix to be 1. We use the geometric average scale. The sign of
79 * the scale factor is recovered by constraining the observed tag
80 * to be in front of the camera. Once scaled, we recover the first
81 * two colmuns of the rotation matrix. The third column is the
82 * cross product of these.
83 *
84 * The second wrinkle is that the computed rotation matrix might
85 * not be exactly orthogonal, so we perform a polar decomposition
86 * to find a good pure rotation approximation.
87 *
88 * Tagsize is the size of the tag in your desired units. I.e., if
89 * your tag measures 0.25m along the side, your tag size is
90 * 0.25. (The homography is computed in terms of *half* the tag
91 * size, i.e., that a tag is 2 units wide as it spans from -1 to
92 * +1, but this code makes the appropriate adjustment.)
93 *
94 * A note on signs:
95 *
96 * The code below incorporates no additional negative signs, but
97 * respects the sign of any parameters that you pass in. Flipping
98 * the signs allows you to modify the projection to suit a wide
99 * variety of conditions.
100 *
101 * In the "pure geometry" projection matrix, the image appears
102 * upside down; i.e., the x and y coordinates on the left hand
103 * side are the opposite of those on the right of the camera
104 * projection matrix. This would happen for all parameters
105 * positive: recall that points in front of the camera have
106 * negative Z values, which will cause the sign of all points to
107 * flip.
108 *
109 * However, most cameras flip things so that the image appears
110 * "right side up" as though you were looking through the lens
111 * directly. This means that the projected points should have the
112 * same sign as the points on the right of the camera projection
113 * matrix. To achieve this, flip fx and fy.
114 *
115 * One further complication: cameras typically put y=0 at the top
116 * of the image, instead of the bottom. Thus you generally want to
117 * flip y yet again (so it's now positive again).
118 *
119 * General advice: you probably want fx negative, fy positive, cx
120 * and cy positive, and s=1.
121 **/
122
123// correspondences is a list of float[4]s, consisting of the points x
124// and y concatenated. We will compute a homography such that y = Hx
125// Specifically, float [] { a, b, c, d } where x = [a b], y = [c d].
126
127
128#define HOMOGRAPHY_COMPUTE_FLAG_INVERSE 1
129#define HOMOGRAPHY_COMPUTE_FLAG_SVD 0
130
131matd_t *homography_compute(zarray_t *correspondences, int flags);
132
133//void homography_project(const matd_t *H, double x, double y, double *ox, double *oy);
134static inline void homography_project(const matd_t *H, double x, double y, double *ox, double *oy)
135{
136 double xx = MATD_EL(H, 0, 0)*x + MATD_EL(H, 0, 1)*y + MATD_EL(H, 0, 2);
137 double yy = MATD_EL(H, 1, 0)*x + MATD_EL(H, 1, 1)*y + MATD_EL(H, 1, 2);
138 double zz = MATD_EL(H, 2, 0)*x + MATD_EL(H, 2, 1)*y + MATD_EL(H, 2, 2);
139
140 *ox = xx / zz;
141 *oy = yy / zz;
142}
143
144// assuming that the projection matrix is:
145// [ fx 0 cx 0 ]
146// [ 0 fy cy 0 ]
147// [ 0 0 1 0 ]
148//
149// And that the homography is equal to the projection matrix times the model matrix,
150// recover the model matrix (which is returned). Note that the third column of the model
151// matrix is missing in the expression below, reflecting the fact that the homography assumes
152// all points are at z=0 (i.e., planar) and that the element of z is thus omitted.
153// (3x1 instead of 4x1).
154//
155// [ fx 0 cx 0 ] [ R00 R01 TX ] [ H00 H01 H02 ]
156// [ 0 fy cy 0 ] [ R10 R11 TY ] = [ H10 H11 H12 ]
157// [ 0 0 1 0 ] [ R20 R21 TZ ] = [ H20 H21 H22 ]
158// [ 0 0 1 ]
159//
160// fx*R00 + cx*R20 = H00 (note, H only known up to scale; some additional adjustments required; see code.)
161// fx*R01 + cx*R21 = H01
162// fx*TX + cx*TZ = H02
163// fy*R10 + cy*R20 = H10
164// fy*R11 + cy*R21 = H11
165// fy*TY + cy*TZ = H12
166// R20 = H20
167// R21 = H21
168// TZ = H22
169matd_t *homography_to_pose(const matd_t *H, double fx, double fy, double cx, double cy);
170
171// Similar to above
172// Recover the model view matrix assuming that the projection matrix is:
173//
174// [ F 0 A 0 ] (see glFrustrum)
175// [ 0 G B 0 ]
176// [ 0 0 C D ]
177// [ 0 0 -1 0 ]
178
179matd_t *homography_to_model_view(const matd_t *H, double F, double G, double A, double B);
180
181#ifdef __cplusplus
182}
183#endif
matd_t * homography_compute(zarray_t *correspondences, int flags)
matd_t * homography_to_pose(const matd_t *H, double fx, double fy, double cx, double cy)
matd_t * homography_to_model_view(const matd_t *H, double F, double G, double A, double B)
static void homography_project(const matd_t *H, double x, double y, double *ox, double *oy)
Definition homography.h:134
#define MATD_EL(m, row, col)
A macro to reference a specific matd_t data element given it's zero-based row and column indexes.
Definition matd.h:65
Defines a matrix structure for holding double-precision values with data in row-major order (i....
Definition matd.h:46
Definition zarray.h:44