Landmark.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 "Landmark.h"
23 
24 using namespace ov_type;
25 
26 Eigen::Matrix<double, 3, 1> Landmark::get_xyz(bool getfej) const {
27 
28  // CASE: Global 3d feature representation
29  // CASE: Anchored 3D feature representation
30  if (_feat_representation == LandmarkRepresentation::Representation::GLOBAL_3D ||
31  _feat_representation == LandmarkRepresentation::Representation::ANCHORED_3D) {
32  return (getfej) ? fej() : value();
33  }
34 
35  // CASE: Global inverse depth feature representation
36  // CASE: Anchored full inverse depth feature representation
37  if (_feat_representation == LandmarkRepresentation::Representation::GLOBAL_FULL_INVERSE_DEPTH ||
38  _feat_representation == LandmarkRepresentation::Representation::ANCHORED_FULL_INVERSE_DEPTH) {
39  Eigen::Matrix<double, 3, 1> p_invFinG = (getfej) ? fej() : value();
40  Eigen::Matrix<double, 3, 1> p_FinG;
41  p_FinG << (1 / p_invFinG(2)) * std::cos(p_invFinG(0)) * std::sin(p_invFinG(1)),
42  (1 / p_invFinG(2)) * std::sin(p_invFinG(0)) * std::sin(p_invFinG(1)), (1 / p_invFinG(2)) * std::cos(p_invFinG(1));
43  return p_FinG;
44  }
45 
46  // CASE: Anchored MSCKF inverse depth feature representation
47  if (_feat_representation == LandmarkRepresentation::Representation::ANCHORED_MSCKF_INVERSE_DEPTH) {
48  Eigen::Matrix<double, 3, 1> p_FinA;
49  Eigen::Matrix<double, 3, 1> p_invFinA = value();
50  p_FinA << (1 / p_invFinA(2)) * p_invFinA(0), (1 / p_invFinA(2)) * p_invFinA(1), 1 / p_invFinA(2);
51  return p_FinA;
52  }
53 
54  // CASE: Estimate single depth of the feature using the initial bearing
55  if (_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
56  // if(getfej) return 1.0/fej()(0)*uv_norm_zero_fej;
57  return 1.0 / value()(0) * uv_norm_zero;
58  }
59 
60  // Failure
61  assert(false);
62  return Eigen::Vector3d::Zero();
63 }
64 
65 void Landmark::set_from_xyz(Eigen::Matrix<double, 3, 1> p_FinG, bool isfej) {
66 
67  // CASE: Global 3d feature representation
68  // CASE: Anchored 3d feature representation
69  if (_feat_representation == LandmarkRepresentation::Representation::GLOBAL_3D ||
70  _feat_representation == LandmarkRepresentation::Representation::ANCHORED_3D) {
71  if (isfej)
72  set_fej(p_FinG);
73  else
74  set_value(p_FinG);
75  return;
76  }
77 
78  // CASE: Global inverse depth feature representation
79  // CASE: Anchored inverse depth feature representation
80  if (_feat_representation == LandmarkRepresentation::Representation::GLOBAL_FULL_INVERSE_DEPTH ||
81  _feat_representation == LandmarkRepresentation::Representation::ANCHORED_FULL_INVERSE_DEPTH) {
82 
83  // Feature inverse representation
84  // NOTE: This is not the MSCKF inverse form, but the standard form
85  // NOTE: Thus we go from p_FinG and convert it to this form
86  double g_rho = 1 / p_FinG.norm();
87  double g_phi = std::acos(g_rho * p_FinG(2));
88  // double g_theta = std::asin(g_rho*p_FinG(1)/std::sin(g_phi));
89  double g_theta = std::atan2(p_FinG(1), p_FinG(0));
90  Eigen::Matrix<double, 3, 1> p_invFinG;
91  p_invFinG(0) = g_theta;
92  p_invFinG(1) = g_phi;
93  p_invFinG(2) = g_rho;
94 
95  // Set our feature value
96  if (isfej)
97  set_fej(p_invFinG);
98  else
99  set_value(p_invFinG);
100  return;
101  }
102 
103  // CASE: MSCKF anchored inverse depth representation
104  if (_feat_representation == LandmarkRepresentation::Representation::ANCHORED_MSCKF_INVERSE_DEPTH) {
105 
106  // MSCKF representation
107  Eigen::Matrix<double, 3, 1> p_invFinA_MSCKF;
108  p_invFinA_MSCKF(0) = p_FinG(0) / p_FinG(2);
109  p_invFinA_MSCKF(1) = p_FinG(1) / p_FinG(2);
110  p_invFinA_MSCKF(2) = 1 / p_FinG(2);
111 
112  // Set our feature value
113  if (isfej)
114  set_fej(p_invFinA_MSCKF);
115  else
116  set_value(p_invFinA_MSCKF);
117  return;
118  }
119 
120  // CASE: Estimate single depth of the feature using the initial bearing
121  if (_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
122 
123  // Get the inverse depth
124  Eigen::VectorXd temp;
125  temp.resize(1, 1);
126  temp(0) = 1.0 / p_FinG(2);
127 
128  // Set our bearing vector
129  if (!isfej)
130  uv_norm_zero = 1.0 / p_FinG(2) * p_FinG;
131  else
132  uv_norm_zero_fej = 1.0 / p_FinG(2) * p_FinG;
133 
134  // Set our feature value
135  if (isfej)
136  set_fej(temp);
137  else
138  set_value(temp);
139  return;
140  }
141 
142  // Failure
143  assert(false);
144 }
ov_type::Type::set_value
virtual void set_value(const Eigen::MatrixXd &new_value)
Overwrite value of state's estimate.
Definition: Type.h:90
ov_type::Landmark::uv_norm_zero
Eigen::Vector3d uv_norm_zero
First normalized uv coordinate bearing of this measurement (used for single depth representation)
Definition: Landmark.h:67
ov_type::Landmark::set_from_xyz
void set_from_xyz(Eigen::Matrix< double, 3, 1 > p_FinG, bool isfej)
Will set the current value based on the representation.
Definition: Landmark.cpp:65
ov_type::Landmark::_feat_representation
LandmarkRepresentation::Representation _feat_representation
What feature representation this feature currently has.
Definition: Landmark.h:73
ov_type::Type::value
virtual const Eigen::MatrixXd & value() const
Access variable's estimate.
Definition: Type.h:79
Landmark.h
ov_type
Dynamic type system types.
ov_type::Type::fej
virtual const Eigen::MatrixXd & fej() const
Access variable's first-estimate.
Definition: Type.h:84
ov_type::Type::set_fej
virtual void set_fej(const Eigen::MatrixXd &new_value)
Overwrite value of first-estimate.
Definition: Type.h:100
ov_type::Landmark::uv_norm_zero_fej
Eigen::Vector3d uv_norm_zero_fej
First estimate normalized uv coordinate bearing of this measurement (used for single depth representa...
Definition: Landmark.h:70
ov_type::Landmark::get_xyz
Eigen::Matrix< double, 3, 1 > get_xyz(bool getfej) const
Will return the position of the feature in the global frame of reference.
Definition: Landmark.cpp:26


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