g2o
types_seven_dof_expmap.cpp
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 H. Strasdat
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 "types_seven_dof_expmap.h"
28 
29 #include "g2o/core/factory.h"
30 #include "g2o/stuff/macros.h"
31 
32 namespace g2o {
33 
34  G2O_USE_TYPE_GROUP(sba);
35 
37 
38  G2O_REGISTER_TYPE(VERTEX_SIM3:EXPMAP, VertexSim3Expmap);
39  G2O_REGISTER_TYPE(EDGE_SIM3:EXPMAP, EdgeSim3);
40  G2O_REGISTER_TYPE(EDGE_PROJECT_SIM3_XYZ:EXPMAP, EdgeSim3ProjectXYZ);
41 
43  {
44  _marginalized=false;
45  _fix_scale = false;
46  _principle_point[0] = 0;
47  _principle_point[1] = 0;
48  _focal_length[0] = 1;
49  _focal_length[1] = 1;
50  }
51 
52 
55  {
56  }
57 
58 
59  bool VertexSim3Expmap::read(std::istream& is)
60  {
61  Vector7d cam2world;
62  for (int i=0; i<6; i++){
63  is >> cam2world[i];
64  }
65  is >> cam2world[6];
66 // if (! is) {
67 // // if the scale is not specified we set it to 1;
68 // std::cerr << "!s";
69 // cam2world[6]=0.;
70 // }
71 
72  for (int i=0; i<2; i++)
73  {
74  is >> _focal_length[i];
75  }
76  for (int i=0; i<2; i++)
77  {
78  is >> _principle_point[i];
79  }
80 
81  setEstimate(Sim3(cam2world).inverse());
82  return true;
83  }
84 
85  bool VertexSim3Expmap::write(std::ostream& os) const
86  {
87  Sim3 cam2world(estimate().inverse());
88  Vector7d lv=cam2world.log();
89  for (int i=0; i<7; i++){
90  os << lv[i] << " ";
91  }
92  for (int i=0; i<2; i++)
93  {
94  os << _focal_length[i] << " ";
95  }
96  for (int i=0; i<2; i++)
97  {
98  os << _principle_point[i] << " ";
99  }
100  return os.good();
101  }
102 
103  bool EdgeSim3::read(std::istream& is)
104  {
105  Vector7d v7;
106  for (int i=0; i<7; i++){
107  is >> v7[i];
108  }
109 
110  Sim3 cam2world(v7);
111  setMeasurement(cam2world.inverse());
112 
113  for (int i=0; i<7; i++)
114  for (int j=i; j<7; j++)
115  {
116  is >> information()(i,j);
117  if (i!=j)
118  information()(j,i)=information()(i,j);
119  }
120  return true;
121  }
122 
123  bool EdgeSim3::write(std::ostream& os) const
124  {
125  Sim3 cam2world(measurement().inverse());
126  Vector7d v7 = cam2world.log();
127  for (int i=0; i<7; i++)
128  {
129  os << v7[i] << " ";
130  }
131  for (int i=0; i<7; i++)
132  for (int j=i; j<7; j++){
133  os << " " << information()(i,j);
134  }
135  return os.good();
136  }
137 
142  {
143  }
144 
145  bool EdgeSim3ProjectXYZ::read(std::istream& is)
146  {
147  for (int i=0; i<2; i++)
148  {
149  is >> _measurement[i];
150  }
151 
152  for (int i=0; i<2; i++)
153  for (int j=i; j<2; j++) {
154  is >> information()(i,j);
155  if (i!=j)
156  information()(j,i)=information()(i,j);
157  }
158  return true;
159  }
160 
161  bool EdgeSim3ProjectXYZ::write(std::ostream& os) const
162  {
163  for (int i=0; i<2; i++){
164  os << _measurement[i] << " ";
165  }
166 
167  for (int i=0; i<2; i++)
168  for (int j=i; j<2; j++){
169  os << " " << information()(i,j);
170  }
171  return os.good();
172  }
173 
174 // void EdgeSim3ProjectXYZ::linearizeOplus()
175 // {
176 // VertexSim3Expmap * vj = static_cast<VertexSim3Expmap *>(_vertices[1]);
177 // Sim3 T = vj->estimate();
178 
179 // VertexPointXYZ* vi = static_cast<VertexPointXYZ*>(_vertices[0]);
180 // Vector3D xyz = vi->estimate();
181 // Vector3D xyz_trans = T.map(xyz);
182 
183 // double x = xyz_trans[0];
184 // double y = xyz_trans[1];
185 // double z = xyz_trans[2];
186 // double z_2 = z*z;
187 
188 // Matrix<double,2,3,Eigen::ColMajor> tmp;
189 // tmp(0,0) = _focal_length(0);
190 // tmp(0,1) = 0;
191 // tmp(0,2) = -x/z*_focal_length(0);
192 
193 // tmp(1,0) = 0;
194 // tmp(1,1) = _focal_length(1);
195 // tmp(1,2) = -y/z*_focal_length(1);
196 
197 // _jacobianOplusXi = -1./z * tmp * T.rotation().toRotationMatrix();
198 
199 // _jacobianOplusXj(0,0) = x*y/z_2 * _focal_length(0);
200 // _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *_focal_length(0);
201 // _jacobianOplusXj(0,2) = y/z *_focal_length(0);
202 // _jacobianOplusXj(0,3) = -1./z *_focal_length(0);
203 // _jacobianOplusXj(0,4) = 0;
204 // _jacobianOplusXj(0,5) = x/z_2 *_focal_length(0);
205 // _jacobianOplusXj(0,6) = 0; // scale is ignored
206 
207 
208 // _jacobianOplusXj(1,0) = (1+y*y/z_2) *_focal_length(1);
209 // _jacobianOplusXj(1,1) = -x*y/z_2 *_focal_length(1);
210 // _jacobianOplusXj(1,2) = -x/z *_focal_length(1);
211 // _jacobianOplusXj(1,3) = 0;
212 // _jacobianOplusXj(1,4) = -1./z *_focal_length(1);
213 // _jacobianOplusXj(1,5) = y/z_2 *_focal_length(1);
214 // _jacobianOplusXj(1,6) = 0; // scale is ignored
215 // }
216 
217 } // end namespace
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
Definition: eigen_types.h:45
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3()
Definition: sim3.h:38
G2O_REGISTER_TYPE(VERTEX_TAG, VertexTag)
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3ProjectXYZ()
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
Sim3 inverse() const
Definition: sim3.h:220
Templatized BaseVertex.
Definition: base_vertex.h:50
virtual void setMeasurement(const Measurement &m)
Definition: base_edge.h:76
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
Point vertex, XYZ.
Definition: types_sba.h:137
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
stuff to open files and other unsorted components Sim3
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
Vector7d log() const
Definition: sim3.h:142
G2O_REGISTER_TYPE_GROUP(data)
G2O_USE_TYPE_GROUP(slam2d)
virtual bool write(std::ostream &os) const
write the vertex to a stream
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75