edge_sbacam_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 
32 #ifndef RTAB_G2O_EDGE_SBACAM_GRAVITY_H_
33 #define RTAB_G2O_EDGE_SBACAM_GRAVITY_H_
34 
35 #include "g2o/types/sba/types_sba.h"
36 #include "g2o/core/base_unary_edge.h"
37 namespace rtabmap {
42 class EdgeSBACamGravity : public g2o::BaseUnaryEdge<3, Eigen::Matrix<double, 6, 1>, g2o::VertexCam> {
43  public:
44  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46  information().setIdentity();
47  }
48  virtual bool read(std::istream& is) {return false;} // not implemented
49  virtual bool write(std::ostream& os) const {return false;} // not implemented
50 
51  void setCameraInvLocalTransform(const Eigen::Matrix3d & t)
52  {
54  }
55 
56  // return the error estimate as a 3-vector
57  void computeError(){
58  const g2o::VertexCam* v1 = static_cast<const g2o::VertexCam*>(_vertices[0]);
59 
60  Eigen::Vector3d direction = _measurement.head<3>();
61  Eigen::Vector3d measurement = _measurement.tail<3>();
62 
63  Eigen::Vector3d ea;
64 
65  // Transform pose from camera frame to world frame
66  Eigen::Matrix3d t = v1->estimate().rotation().toRotationMatrix() * cameraInvLocalTransform_;
67  ea[0] = atan2(t (2, 1), t (2, 2));
68  ea[1] = asin(-t (2, 0));
69  ea[2] = atan2(t (1, 0), t (0, 0));
70 
71  Eigen::Matrix3d rot =
72  (Eigen::AngleAxisd(ea[1], Eigen::Vector3d::UnitY()) *
73  Eigen::AngleAxisd(ea[0], Eigen::Vector3d::UnitX())).toRotationMatrix();
74 
75  Eigen::Vector3d estimate = rot * -direction;
76  _error = estimate - measurement;
77 
78  /*printf("%d : measured=%f %f %f est=%f %f %f error=%f %f %f\n", v1->id(),
79  measurement[0], measurement[1], measurement[2],
80  estimate[0], estimate[1], estimate[2],
81  _error[0], _error[1], _error[2]);*/
82  }
83 
84  // 6 values:
85  // [0:2] Up vector in robot frame
86  // [3:5] Observed gravity vector in world frame
87  virtual void setMeasurement(const Eigen::Matrix<double, 6, 1>& m){
88  _measurement.head<3>() = m.head<3>().normalized();
89  _measurement.tail<3>() = m.tail<3>().normalized();
90  }
91 
92  private:
93  Eigen::Matrix3d cameraInvLocalTransform_;
94  };
95 
96 }
97 #endif
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSBACamGravity()
virtual bool write(std::ostream &os) const
virtual bool read(std::istream &is)
GLM_FUNC_QUALIFIER T atan2(T x, T y)
Arc tangent. Returns an angle whose tangent is y/x. The signs of x and y are used to determine what q...
Eigen::Matrix3d cameraInvLocalTransform_
GLM_FUNC_DECL genType asin(genType const &x)
virtual void setMeasurement(const Eigen::Matrix< double, 6, 1 > &m)
void setCameraInvLocalTransform(const Eigen::Matrix3d &t)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58