JPLQuat.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_TYPE_TYPE_JPLQUAT_H
23 #define OV_TYPE_TYPE_JPLQUAT_H
24 
25 #include "Type.h"
26 #include "utils/quat_ops.h"
27 
28 namespace ov_type {
29 
92 class JPLQuat : public Type {
93 
94 public:
95  JPLQuat() : Type(3) {
96  Eigen::Vector4d q0 = Eigen::Vector4d::Zero();
97  q0(3) = 1.0;
99  set_fej_internal(q0);
100  }
101 
102  ~JPLQuat() {}
103 
114  void update(const Eigen::VectorXd &dx) override {
115 
116  assert(dx.rows() == _size);
117 
118  // Build perturbing quaternion
119  Eigen::Matrix<double, 4, 1> dq;
120  dq << .5 * dx, 1.0;
121  dq = ov_core::quatnorm(dq);
122 
123  // Update estimate and recompute R
125  }
126 
131  void set_value(const Eigen::MatrixXd &new_value) override { set_value_internal(new_value); }
132 
137  void set_fej(const Eigen::MatrixXd &new_value) override { set_fej_internal(new_value); }
138 
139  std::shared_ptr<Type> clone() override {
140  auto Clone = std::shared_ptr<JPLQuat>(new JPLQuat());
141  Clone->set_value(value());
142  Clone->set_fej(fej());
143  return Clone;
144  }
145 
147  Eigen::Matrix<double, 3, 3> Rot() const { return _R; }
148 
150  Eigen::Matrix<double, 3, 3> Rot_fej() const { return _Rfej; }
151 
152 protected:
153  // Stores the rotation
154  Eigen::Matrix<double, 3, 3> _R;
155 
156  // Stores the first-estimate rotation
157  Eigen::Matrix<double, 3, 3> _Rfej;
158 
163  void set_value_internal(const Eigen::MatrixXd &new_value) {
164 
165  assert(new_value.rows() == 4);
166  assert(new_value.cols() == 1);
167 
168  _value = new_value;
169 
170  // compute associated rotation
171  _R = ov_core::quat_2_Rot(new_value);
172  }
173 
178  void set_fej_internal(const Eigen::MatrixXd &new_value) {
179 
180  assert(new_value.rows() == 4);
181  assert(new_value.cols() == 1);
182 
183  _fej = new_value;
184 
185  // compute associated rotation
186  _Rfej = ov_core::quat_2_Rot(new_value);
187  }
188 };
189 
190 } // namespace ov_type
191 
192 #endif // OV_TYPE_TYPE_JPLQUAT_H
ov_type::JPLQuat::_Rfej
Eigen::Matrix< double, 3, 3 > _Rfej
Definition: JPLQuat.h:157
ov_type::Type::_size
int _size
Dimension of error state.
Definition: Type.h:132
ov_core::quat_multiply
Eigen::Matrix< double, 4, 1 > quat_multiply(const Eigen::Matrix< double, 4, 1 > &q, const Eigen::Matrix< double, 4, 1 > &p)
Multiply two JPL quaternions.
Definition: quat_ops.h:180
ov_type::JPLQuat::clone
std::shared_ptr< Type > clone() override
Create a clone of this variable.
Definition: JPLQuat.h:139
ov_type::JPLQuat::_R
Eigen::Matrix< double, 3, 3 > _R
Definition: JPLQuat.h:154
ov_type::JPLQuat::~JPLQuat
~JPLQuat()
Definition: JPLQuat.h:102
Type.h
ov_type::JPLQuat::Rot
Eigen::Matrix< double, 3, 3 > Rot() const
Rotation access.
Definition: JPLQuat.h:147
ov_type::Type::value
virtual const Eigen::MatrixXd & value() const
Access variable's estimate.
Definition: Type.h:79
ov_type::JPLQuat::update
void update(const Eigen::VectorXd &dx) override
Implements update operation by left-multiplying the current quaternion with a quaternion built from a...
Definition: JPLQuat.h:114
ov_type::JPLQuat
Derived Type class that implements JPL quaternion.
Definition: JPLQuat.h:92
ov_type::JPLQuat::Rot_fej
Eigen::Matrix< double, 3, 3 > Rot_fej() const
FEJ Rotation access.
Definition: JPLQuat.h:150
ov_core::quat_2_Rot
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
Converts JPL quaterion to SO(3) rotation matrix.
Definition: quat_ops.h:152
ov_type::JPLQuat::set_value_internal
void set_value_internal(const Eigen::MatrixXd &new_value)
Sets the value of the estimate and recomputes the internal rotation matrix.
Definition: JPLQuat.h:163
ov_type::JPLQuat::set_fej_internal
void set_fej_internal(const Eigen::MatrixXd &new_value)
Sets the fej value and recomputes the fej rotation matrix.
Definition: JPLQuat.h:178
ov_type::JPLQuat::set_value
void set_value(const Eigen::MatrixXd &new_value) override
Sets the value of the estimate and recomputes the internal rotation matrix.
Definition: JPLQuat.h:131
ov_type::JPLQuat::JPLQuat
JPLQuat()
Definition: JPLQuat.h:95
ov_type
Dynamic type system types.
ov_core::quatnorm
Eigen::Matrix< double, 4, 1 > quatnorm(Eigen::Matrix< double, 4, 1 > q_t)
Normalizes a quaternion to make sure it is unit norm.
Definition: quat_ops.h:496
ov_type::Type::fej
virtual const Eigen::MatrixXd & fej() const
Access variable's first-estimate.
Definition: Type.h:84
ov_type::Type::_fej
Eigen::MatrixXd _fej
First-estimate.
Definition: Type.h:123
ov_type::Type::_value
Eigen::MatrixXd _value
Current best estimate.
Definition: Type.h:126
quat_ops.h
ov_type::JPLQuat::set_fej
void set_fej(const Eigen::MatrixXd &new_value) override
Sets the fej value and recomputes the fej rotation matrix.
Definition: JPLQuat.h:137
ov_type::Type
Base class for estimated variables.
Definition: Type.h:37


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17