g2o
Loading...
Searching...
No Matches
sbacam.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2011 Kurt Konolige
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// * Redistributions of source code must retain the above copyright notice,
10// this list of conditions and the following disclaimer.
11// * Redistributions in binary form must reproduce the above copyright
12// notice, this list of conditions and the following disclaimer in the
13// documentation and/or other materials provided with the distribution.
14//
15// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26
27#include "sbacam.h"
28
29#include <Eigen/Core>
30#include <Eigen/Geometry>
31
32#include "g2o/stuff/macros.h"
33#include "g2o/stuff/misc.h"
34
35namespace g2o {
36
37// initialize an object
39 setKcam(1, 1, cst(0.5), cst(0.5), 0); // unit image projection
40}
41
42// set the object pose
43SBACam::SBACam(const Quaternion& r_, const Vector3& t_) : SE3Quat(r_, t_) {
44 Kcam.setZero();
47 setDr();
48}
49
51 Kcam.setZero();
54 setDr();
55}
56
57// update from the linear solution
58// defined in se3quat
59void SBACam::update(const Vector6& update) {
60 // position update
61 _t += update.head(3);
62 // small quaternion update
63 Quaternion qr;
64 qr.vec() = update.segment<3>(3);
65 qr.w() =
66 sqrt(cst(1.0) - qr.vec().squaredNorm()); // should always be positive
67 _r *= qr; // post-multiply
68 _r.normalize();
71 setDr();
72}
73
74// transforms
75void SBACam::transformW2F(Eigen::Matrix<double, 3, 4>& m, const Vector3& trans,
76 const Quaternion& qrot) {
77 m.block<3, 3>(0, 0) = qrot.toRotationMatrix().transpose();
78 m.col(3).setZero(); // make sure there's no translation
79 Vector4 tt;
80 tt.head(3) = trans;
81 tt[3] = 1.0;
82 m.col(3) = -m * tt;
83}
84
85void SBACam::transformF2W(Eigen::Matrix<double, 3, 4>& m, const Vector3& trans,
86 const Quaternion& qrot) {
87 m.block<3, 3>(0, 0) = qrot.toRotationMatrix();
88 m.col(3) = trans;
89}
90
91// set up camera matrix
92void SBACam::setKcam(double fx, double fy, double cx, double cy, double tx) {
93 Kcam.setZero();
94 Kcam(0, 0) = fx;
95 Kcam(1, 1) = fy;
96 Kcam(0, 2) = cx;
97 Kcam(1, 2) = cy;
98 Kcam(2, 2) = cst(1.0);
99 baseline = tx;
100 setTransform();
102 setDr();
103}
104
105// sets angle derivatives
107 // inefficient, just for testing
108 // use simple multiplications and additions for production code in calculating
109 // dRdx,y,z
110 Matrix3 dRidx, dRidy, dRidz;
111 dRidx << cst(0.0), cst(0.0), cst(0.0), cst(0.0), cst(0.0), cst(2.0), cst(0.0),
112 cst(-2.0), cst(0.0);
113 dRidy << cst(0.0), cst(0.0), cst(-2.0), cst(0.0), cst(0.0), cst(0.0),
114 cst(2.0), cst(0.0), cst(0.0);
115 dRidz << cst(0.0), cst(2.0), cst(0.0), cst(-2.0), cst(0.0), cst(0.0),
116 cst(0.0), cst(0.0), cst(0.0);
117
118 // for dS'*R', with dS the incremental change
119 dRdx = dRidx * w2n.block<3, 3>(0, 0);
120 dRdy = dRidy * w2n.block<3, 3>(0, 0);
121 dRdz = dRidz * w2n.block<3, 3>(0, 0);
122}
123
124// human-readable SBACam object
125std::ostream& operator<<(std::ostream& out_str, const SBACam& cam) {
126 out_str << cam.translation().transpose() << std::endl;
127 out_str << cam.rotation().coeffs().transpose() << std::endl << std::endl;
128 out_str << cam.Kcam << std::endl << std::endl;
129 out_str << cam.w2n << std::endl << std::endl;
130 out_str << cam.w2i << std::endl << std::endl;
131 return out_str;
132}
133
134} // namespace g2o
void setTransform()
Definition sbacam.h:85
Matrix3 Kcam
Definition sbacam.h:51
void update(const Vector6 &update)
Definition sbacam.cpp:59
void setProjection()
Definition sbacam.h:89
Eigen::Matrix< double, 3, 4 > w2i
Definition sbacam.h:56
double baseline
Definition sbacam.h:52
Matrix3 dRdx
Definition sbacam.h:60
static void transformF2W(Eigen::Matrix< double, 3, 4 > &m, const Vector3 &trans, const Quaternion &qrot)
Definition sbacam.cpp:85
void setKcam(double fx, double fy, double cx, double cy, double tx)
Definition sbacam.cpp:92
Eigen::Matrix< double, 3, 4 > w2n
Definition sbacam.h:55
Matrix3 dRdy
Definition sbacam.h:60
static void transformW2F(Eigen::Matrix< double, 3, 4 > &m, const Vector3 &trans, const Quaternion &qrot)
Definition sbacam.cpp:75
void setDr()
Definition sbacam.cpp:106
Matrix3 dRdz
Definition sbacam.h:60
Quaternion _r
Definition se3quat.h:44
const Quaternion & rotation() const
Definition se3quat.h:93
const Vector3 & translation() const
Definition se3quat.h:89
Vector3 _t
Definition se3quat.h:45
some general case utility functions
VectorN< 3 > Vector3
Definition eigen_types.h:51
MatrixN< 3 > Matrix3
Definition eigen_types.h:72
VectorN< 4 > Vector4
Definition eigen_types.h:52
constexpr double cst(long double v)
Definition misc.h:60
VectorN< 6 > Vector6
Definition eigen_types.h:53
std::ostream & operator<<(std::ostream &os, const G2OBatchStatistics &st)
Eigen::Quaternion< double > Quaternion
Definition eigen_types.h:81