Berkeley SfM
camera_extrinsics.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015, The Regents of the University of California (Regents).
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are
7  * met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS AS IS
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * Please contact the author(s) of this library if you have any questions.
34  * Authors: Erik Nelson ( eanelson@eecs.berkeley.edu )
35  * David Fridovich-Keil ( dfk@eecs.berkeley.edu )
36  */
37 
38 ///////////////////////////////////////////////////////////////////////////////
39 //
40 // This class defines a camera's extrinsic parameters according to the OpenCV
41 // camera model:
42 // http://docs.opencv.org/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html
43 //
44 ///////////////////////////////////////////////////////////////////////////////
45 
47 
48 #include "../geometry/rotation.h"
49 
50 namespace bsfm {
51 
52 // Constructor. Initialize to identity.
55 }
56 
57 // Constructor. Initialize world_to_camera_ .
59  : world_to_camera_(world_to_camera) {}
60 
61 // Set world_to_camera_.
62 void CameraExtrinsics::SetWorldToCamera(const Pose& world_to_camera) {
63  world_to_camera_ = world_to_camera;
64 }
65 
66 // Extract poses.
68  return world_to_camera_;
69 }
70 
73 }
74 
75 // For use in the following methods: From H&Z page 156, the extrinsics matrix
76 // can be represented as
77 // [R -Rc]
78 // [0 1 ]
79 // where c is the camera centroid. From this we get t = -Rc and c = -R't
80 void CameraExtrinsics::SetRotation(const Matrix3d& rotation) {
81  const Vector3d t = world_to_camera_.Translation();
82  const Matrix3d R = world_to_camera_.Rotation();
83  const Vector3d c = -R.transpose() * t;
84 
85  world_to_camera_.SetRotation(rotation);
86  world_to_camera_.SetTranslation(-rotation * c);
87 }
88 
89 void CameraExtrinsics::SetRotation(double phi, double theta, double psi) {
90  SetRotation(EulerAnglesToMatrix(phi, theta, psi));
91 }
92 
93 void CameraExtrinsics::Rotate(const Matrix3d& delta) {
94  const Matrix3d R = world_to_camera_.Rotation();
95  SetRotation(delta * R);
96 }
97 
98 void CameraExtrinsics::Rotate(double dphi, double dtheta, double dpsi) {
99  Rotate(EulerAnglesToMatrix(dphi, dtheta, dpsi));
100 }
101 
102 Matrix3d CameraExtrinsics::Rotation() const {
103  return world_to_camera_.Rotation();
104 }
105 
106 void CameraExtrinsics::SetTranslation(const Vector3d& translation) {
107  const Matrix3d R = world_to_camera_.Rotation();
108  world_to_camera_.SetTranslation(-R * translation);
109 }
110 
111 void CameraExtrinsics::SetTranslation(double x, double y, double z) {
112  SetTranslation(Vector3d(x, y, z));
113 }
114 
115 void CameraExtrinsics::Translate(const Vector3d& delta) {
116  const Vector3d t = world_to_camera_.Translation();
117  const Matrix3d R = world_to_camera_.Rotation();
118  Vector3d c = -R.transpose() * t;
119 
120  c += delta;
122 }
123 
124 void CameraExtrinsics::Translate(double dx, double dy, double dz) {
125  Translate(Vector3d(dx, dy, dz));
126 }
127 
129  Translate(Vector3d(dx, 0, 0));
130 }
131 
133  Translate(Vector3d(0, dy, 0));
134 }
135 
137  Translate(Vector3d(0, 0, dz));
138 }
139 
141  const Vector3d t = world_to_camera_.Translation();
142  const Matrix3d R = world_to_camera_.Rotation();
143  return -R.transpose() * t;
144 }
145 
146 // The extrinsics matrix is 3x4 matrix: [R | t].
148  return WorldToCamera().Dehomogenize();
149 }
150 
151 // Convert a world frame point into the camera frame.
152 void CameraExtrinsics::WorldToCamera(double wx, double wy, double wz,
153  double* cx, double* cy, double* cz) const {
154  CHECK_NOTNULL(cx);
155  CHECK_NOTNULL(cy);
156  CHECK_NOTNULL(cz);
157 
158  const Vector4d w_h(wx, wy, wz, 1.0);
159  const Vector4d c_h = CameraExtrinsics::WorldToCamera().Project(w_h);
160 
161  *cx = c_h(0);
162  *cy = c_h(1);
163  *cz = c_h(2);
164 }
165 
166 // Convert a camera frame point into the world frame.
167 void CameraExtrinsics::CameraToWorld(double cx, double cy, double cz,
168  double* wx, double* wy, double* wz) const {
169  CHECK_NOTNULL(wx);
170  CHECK_NOTNULL(wy);
171  CHECK_NOTNULL(wz);
172 
173  const Vector4d c_h(cx, cy, cz, 1.0);
174  const Vector4d w_h = CameraExtrinsics::CameraToWorld().Project(c_h);
175 
176  *wx = w_h(0);
177  *wy = w_h(1);
178  *wz = w_h(2);
179 }
180 
181 } // namespace bsfm
Vector3d Translation() const
Definition: pose.cpp:96
void SetTranslation(const Vector3d &translation)
void SetRotation(const Matrix3d &rotation)
void SetTranslation(const Vector3d &translation)
Definition: pose.cpp:110
Vector3d Translation() const
Matrix3d Rotation() const
Definition: pose.cpp:91
Pose Inverse() const
Definition: pose.cpp:150
void Translate(const Vector3d &delta)
Vector4d Project(const Vector4d &)
Definition: pose.cpp:121
void Rotate(const Matrix3d &delta)
void SetWorldToCamera(const Pose &world_to_camera)
Definition: camera.cpp:50
void SetRotation(const Matrix3d &rotation)
Definition: pose.cpp:106
::Eigen::Matrix< double, 3, 4 > Matrix34d
Definition: types.h:87
Matrix34d Dehomogenize()
Definition: pose.cpp:157
Matrix3d EulerAnglesToMatrix(double phi, double theta, double psi)
Definition: rotation.cpp:49
Matrix3d Rotation() const