State_JPLQuatLocal.cpp
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 #include "State_JPLQuatLocal.h"
23 
24 #include "utils/quat_ops.h"
25 
26 using namespace ov_init;
27 
28 bool State_JPLQuatLocal::Plus(const double *x, const double *delta, double *x_plus_delta) const {
29 
30  // Apply the standard JPL update: q <-- [d_th/2; 1] (x) q
31  Eigen::Map<const Eigen::Vector4d> q(x);
32 
33  // Get delta into eigen
34  Eigen::Map<const Eigen::Vector3d> d_th(delta);
35  Eigen::Matrix<double, 4, 1> d_q;
36  double theta = d_th.norm();
37  if (theta < 1e-8) {
38  d_q << .5 * d_th, 1.0;
39  } else {
40  d_q.block(0, 0, 3, 1) = (d_th / theta) * std::sin(theta / 2);
41  d_q(3, 0) = std::cos(theta / 2);
42  }
43  d_q = ov_core::quatnorm(d_q);
44 
45  // Do the update
46  Eigen::Map<Eigen::Vector4d> q_plus(x_plus_delta);
47  q_plus = ov_core::quat_multiply(d_q, q);
48  return true;
49 }
50 
51 bool State_JPLQuatLocal::ComputeJacobian(const double *x, double *jacobian) const {
52  Eigen::Map<Eigen::Matrix<double, 4, 3, Eigen::RowMajor>> j(jacobian);
53  j.topRows<3>().setIdentity();
54  j.bottomRows<1>().setZero();
55  return true;
56 }
quat_ops.h
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)
ov_init::State_JPLQuatLocal::Plus
bool Plus(const double *x, const double *delta, double *x_plus_delta) const override
State update function for a JPL quaternion representation.
Definition: State_JPLQuatLocal.cpp:28
ov_init
State initialization code.
Definition: Factor_GenericPrior.h:27
State_JPLQuatLocal.h
ov_core::quatnorm
Eigen::Matrix< double, 4, 1 > quatnorm(Eigen::Matrix< double, 4, 1 > q_t)
ov_init::State_JPLQuatLocal::ComputeJacobian
bool ComputeJacobian(const double *x, double *jacobian) const override
Computes the jacobian in respect to the local parameterization.
Definition: State_JPLQuatLocal.cpp:51


ov_init
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:51