pose_graph_3d/types.h
Go to the documentation of this file.
1 // Ceres Solver - A fast non-linear least squares minimizer
2 // Copyright 2016 Google Inc. All rights reserved.
3 // http://ceres-solver.org/
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * 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.
13 // * Neither the name of Google Inc. nor the names of its contributors may be
14 // used to endorse or promote products derived from this software without
15 // specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 // Author: vitus@google.com (Michael Vitus)
30 
31 #ifndef EXAMPLES_CERES_TYPES_H_
32 #define EXAMPLES_CERES_TYPES_H_
33 
34 #include <istream>
35 #include <map>
36 #include <string>
37 #include <vector>
38 
39 #include "Eigen/Core"
40 #include "Eigen/Geometry"
41 
42 namespace ceres {
43 namespace examples {
44 
45 struct Pose3d {
46  Eigen::Vector3d p;
47  Eigen::Quaterniond q;
48 
49  // The name of the data type in the g2o file format.
50  static std::string name() {
51  return "VERTEX_SE3:QUAT";
52  }
53 
54  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55 };
56 
57 inline std::istream& operator>>(std::istream& input, Pose3d& pose) {
58  input >> pose.p.x() >> pose.p.y() >> pose.p.z() >> pose.q.x() >>
59  pose.q.y() >> pose.q.z() >> pose.q.w();
60  // Normalize the quaternion to account for precision loss due to
61  // serialization.
62  pose.q.normalize();
63  return input;
64 }
65 
66 typedef std::map<int, Pose3d, std::less<int>,
67  Eigen::aligned_allocator<std::pair<const int, Pose3d> > >
69 
70 // The constraint between two vertices in the pose graph. The constraint is the
71 // transformation from vertex id_begin to vertex id_end.
72 struct Constraint3d {
73  int id_begin;
74  int id_end;
75 
76  // The transformation that represents the pose of the end frame E w.r.t. the
77  // begin frame B. In other words, it transforms a vector in the E frame to
78  // the B frame.
80 
81  // The inverse of the covariance matrix for the measurement. The order of the
82  // entries are x, y, z, delta orientation.
83  Eigen::Matrix<double, 6, 6> information;
84 
85  // The name of the data type in the g2o file format.
86  static std::string name() {
87  return "EDGE_SE3:QUAT";
88  }
89 
90  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
91 };
92 
93 inline std::istream& operator>>(std::istream& input, Constraint3d& constraint) {
94  Pose3d& t_be = constraint.t_be;
95  input >> constraint.id_begin >> constraint.id_end >> t_be;
96 
97  for (int i = 0; i < 6 && input.good(); ++i) {
98  for (int j = i; j < 6 && input.good(); ++j) {
99  input >> constraint.information(i, j);
100  if (i != j) {
101  constraint.information(j, i) = constraint.information(i, j);
102  }
103  }
104  }
105  return input;
106 }
107 
108 typedef std::vector<Constraint3d, Eigen::aligned_allocator<Constraint3d> >
110 
111 } // namespace examples
112 } // namespace ceres
113 
114 #endif // EXAMPLES_CERES_TYPES_H_
std::istream & operator>>(std::istream &input, Pose2d &pose)
Eigen::Matrix< double, 6, 6 > information
static std::string name()
std::map< int, Pose3d, std::less< int >, Eigen::aligned_allocator< std::pair< const int, Pose3d > > > MapOfPoses
std::vector< Constraint3d, Eigen::aligned_allocator< Constraint3d > > VectorOfConstraints


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:06