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 namespace g2o {
30 
32  {
33  _marginalized=false;
34  _fix_scale = false;
35  }
36 
37 
40  {
41  }
42 
43 
44  bool VertexSim3Expmap::read(std::istream& is)
45  {
46  Vector7d cam2world;
47  for (int i=0; i<6; i++){
48  is >> cam2world[i];
49  }
50  is >> cam2world[6];
51 // if (! is) {
52 // // if the scale is not specified we set it to 1;
53 // std::cerr << "!s";
54 // cam2world[6]=0.;
55 // }
56 
57  for (int i=0; i<2; i++)
58  {
59  is >> _focal_length1[i];
60  }
61  for (int i=0; i<2; i++)
62  {
63  is >> _principle_point1[i];
64  }
65 
66  setEstimate(Sim3(cam2world).inverse());
67  return true;
68  }
69 
70  bool VertexSim3Expmap::write(std::ostream& os) const
71  {
72  Sim3 cam2world(estimate().inverse());
73  Vector7d lv=cam2world.log();
74  for (int i=0; i<7; i++){
75  os << lv[i] << " ";
76  }
77  for (int i=0; i<2; i++)
78  {
79  os << _focal_length1[i] << " ";
80  }
81  for (int i=0; i<2; i++)
82  {
83  os << _principle_point1[i] << " ";
84  }
85  return os.good();
86  }
87 
88  bool EdgeSim3::read(std::istream& is)
89  {
90  Vector7d v7;
91  for (int i=0; i<7; i++){
92  is >> v7[i];
93  }
94 
95  Sim3 cam2world(v7);
96  setMeasurement(cam2world.inverse());
97 
98  for (int i=0; i<7; i++)
99  for (int j=i; j<7; j++)
100  {
101  is >> information()(i,j);
102  if (i!=j)
103  information()(j,i)=information()(i,j);
104  }
105  return true;
106  }
107 
108  bool EdgeSim3::write(std::ostream& os) const
109  {
110  Sim3 cam2world(measurement().inverse());
111  Vector7d v7 = cam2world.log();
112  for (int i=0; i<7; i++)
113  {
114  os << v7[i] << " ";
115  }
116  for (int i=0; i<7; i++)
117  for (int j=i; j<7; j++){
118  os << " " << information()(i,j);
119  }
120  return os.good();
121  }
122 
127  {
128  }
129 
130  bool EdgeSim3ProjectXYZ::read(std::istream& is)
131  {
132  for (int i=0; i<2; i++)
133  {
134  is >> _measurement[i];
135  }
136 
137  for (int i=0; i<2; i++)
138  for (int j=i; j<2; j++) {
139  is >> information()(i,j);
140  if (i!=j)
141  information()(j,i)=information()(i,j);
142  }
143  return true;
144  }
145 
146  bool EdgeSim3ProjectXYZ::write(std::ostream& os) const
147  {
148  for (int i=0; i<2; i++){
149  os << _measurement[i] << " ";
150  }
151 
152  for (int i=0; i<2; i++)
153  for (int j=i; j<2; j++){
154  os << " " << information()(i,j);
155  }
156  return os.good();
157  }
158 
163  {
164  }
165 
166  bool EdgeInverseSim3ProjectXYZ::read(std::istream& is)
167  {
168  for (int i=0; i<2; i++)
169  {
170  is >> _measurement[i];
171  }
172 
173  for (int i=0; i<2; i++)
174  for (int j=i; j<2; j++) {
175  is >> information()(i,j);
176  if (i!=j)
177  information()(j,i)=information()(i,j);
178  }
179  return true;
180  }
181 
182  bool EdgeInverseSim3ProjectXYZ::write(std::ostream& os) const
183  {
184  for (int i=0; i<2; i++){
185  os << _measurement[i] << " ";
186  }
187 
188  for (int i=0; i<2; i++)
189  for (int j=i; j<2; j++){
190  os << " " << information()(i,j);
191  }
192  return os.good();
193  }
194 
195 
196 // void EdgeSim3ProjectXYZ::linearizeOplus()
197 // {
198 // VertexSim3Expmap * vj = static_cast<VertexSim3Expmap *>(_vertices[1]);
199 // Sim3 T = vj->estimate();
200 
201 // VertexPointXYZ* vi = static_cast<VertexPointXYZ*>(_vertices[0]);
202 // Vector3d xyz = vi->estimate();
203 // Vector3d xyz_trans = T.map(xyz);
204 
205 // double x = xyz_trans[0];
206 // double y = xyz_trans[1];
207 // double z = xyz_trans[2];
208 // double z_2 = z*z;
209 
210 // Matrix<double,2,3> tmp;
211 // tmp(0,0) = _focal_length(0);
212 // tmp(0,1) = 0;
213 // tmp(0,2) = -x/z*_focal_length(0);
214 
215 // tmp(1,0) = 0;
216 // tmp(1,1) = _focal_length(1);
217 // tmp(1,2) = -y/z*_focal_length(1);
218 
219 // _jacobianOplusXi = -1./z * tmp * T.rotation().toRotationMatrix();
220 
221 // _jacobianOplusXj(0,0) = x*y/z_2 * _focal_length(0);
222 // _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *_focal_length(0);
223 // _jacobianOplusXj(0,2) = y/z *_focal_length(0);
224 // _jacobianOplusXj(0,3) = -1./z *_focal_length(0);
225 // _jacobianOplusXj(0,4) = 0;
226 // _jacobianOplusXj(0,5) = x/z_2 *_focal_length(0);
227 // _jacobianOplusXj(0,6) = 0; // scale is ignored
228 
229 
230 // _jacobianOplusXj(1,0) = (1+y*y/z_2) *_focal_length(1);
231 // _jacobianOplusXj(1,1) = -x*y/z_2 *_focal_length(1);
232 // _jacobianOplusXj(1,2) = -x/z *_focal_length(1);
233 // _jacobianOplusXj(1,3) = 0;
234 // _jacobianOplusXj(1,4) = -1./z *_focal_length(1);
235 // _jacobianOplusXj(1,5) = y/z_2 *_focal_length(1);
236 // _jacobianOplusXj(1,6) = 0; // scale is ignored
237 // }
238 
239 } // end namespace
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3()
Definition: sim3.h:41
const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:77
Matrix< double, 7, 1 > Vector7d
Definition: se3quat.h:39
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:233
Templatized BaseVertex.
Definition: base_vertex.h:53
const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:69
virtual void setMeasurement(const Measurement &m)
Definition: base_edge.h:78
Point vertex, XYZ.
Definition: types_sba.h:40
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
virtual bool write(std::ostream &os) const
write the vertex to a stream
Vector7d log() const
Definition: sim3.h:148
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VertexSim3Expmap()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeInverseSim3ProjectXYZ()
virtual bool write(std::ostream &os) const
write the vertex to a stream


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05