edge_se3_gravity.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2019, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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 met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING 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 
33 #ifndef RTAB_G2O_EDGE_SE3_GRAVITY_H_
34 #define RTAB_G2O_EDGE_SE3_GRAVITY_H_
35 
36 #include "g2o/core/base_unary_edge.h"
37 #include "g2o/types/slam3d/vertex_se3.h"
38 
39 namespace rtabmap {
40 
44  class EdgeSE3Gravity : public g2o::BaseUnaryEdge<3, Eigen::Matrix<double, 6, 1>, g2o::VertexSE3> {
45  public:
48  information().setIdentity();
49  }
50  virtual bool read(std::istream& is) {return false;} // not implemented
51  virtual bool write(std::ostream& os) const {return false;} // not implemented
52 
53  // return the error estimate as a 3-vector
54  void computeError(){
55  const g2o::VertexSE3* v1 = static_cast<const g2o::VertexSE3*>(_vertices[0]);
56 
57  Eigen::Vector3d direction = _measurement.head<3>();
58  Eigen::Vector3d measurement = _measurement.tail<3>();
59 
60  Eigen::Vector3d ea;
61 
62  Eigen::Matrix3d t = v1->estimate().linear();
63  ea[0] = atan2(t (2, 1), t (2, 2));
64  ea[1] = asin(-t (2, 0));
65  ea[2] = atan2(t (1, 0), t (0, 0));
66 
67  Eigen::Matrix3d rot =
68  (Eigen::AngleAxisd(ea[1], Eigen::Vector3d::UnitY()) *
69  Eigen::AngleAxisd(ea[0], Eigen::Vector3d::UnitX())).toRotationMatrix();
70 
71  Eigen::Vector3d estimate = rot * -direction;
72  _error = estimate - measurement;
73 
74  //printf("%d : measured=%f %f %f est=%f %f %f error=%f %f %f\n", v1->id(),
75  // measurement[0], measurement[1], measurement[2],
76  // estimate[0], estimate[1], estimate[2],
77  // _error[0], _error[1], _error[2]);
78  }
79 
80  // 6 values:
81  // [0:2] Up vector in robot frame
82  // [3:5] Observed gravity vector in world frame
84  _measurement.head<3>() = m.head<3>().normalized();
85  _measurement.tail<3>() = m.tail<3>().normalized();
86  }
87  };
88 }
89 #endif
rtabmap::EdgeSE3Gravity::read
virtual bool read(std::istream &is)
Definition: edge_se3_gravity.h:50
rtabmap::EdgeSE3Gravity
g2o edge with gravity constraint
Definition: edge_se3_gravity.h:44
v1
v1
rtabmap::EdgeSE3Gravity::computeError
void computeError()
Definition: edge_se3_gravity.h:54
glm::asin
GLM_FUNC_DECL genType asin(genType const &x)
rot
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
m
Matrix3f m
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
atan2
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
rtabmap::EdgeSE3Gravity::setMeasurement
virtual void setMeasurement(const Eigen::Matrix< double, 6, 1 > &m)
Definition: edge_se3_gravity.h:83
Eigen::AngleAxisd
AngleAxis< double > AngleAxisd
rtabmap::EdgeSE3Gravity::write
virtual bool write(std::ostream &os) const
Definition: edge_se3_gravity.h:51
rtabmap::EdgeSE3Gravity::EdgeSE3Gravity
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3Gravity()
Definition: edge_se3_gravity.h:47
Eigen::Matrix
t
Point2 t(10, 10)
rtabmap
Definition: CameraARCore.cpp:35


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:09