BearingS2.cpp
Go to the documentation of this file.
1 
8 #include <iostream>
9 
11 
12 #include <cassert>
13 
14 namespace gtsam {
15 
16 using namespace std;
17 
18 /* ************************************************************************* */
19 void BearingS2::print(const std::string& s) const {
20  cout << s << " azimuth: " << azimuth_.theta() << " elevation: " << elevation_.theta() << endl;
21 }
22 
23 /* ************************************************************************* */
24 bool BearingS2::equals(const BearingS2& x, double tol) const {
25  return azimuth_.equals(x.azimuth_, tol) && elevation_.equals(x.elevation_, tol);
26 }
27 
28 /* ************************************************************************* */
30  // Cnb = DCMnb(Att);
31  Matrix Cnb = A.rotation().matrix().transpose();
32 
33  // Cbc = [0,0,1;0,1,0;-1,0,0];
34  Matrix Cbc = (Matrix(3,3) <<
35  0.,0.,1.,
36  0.,1.,0.,
37  -1.,0.,0.).finished();
38  // p_rel_c = Cbc*Cnb*(PosObj - Pos);
39  Vector p_rel_c = Cbc*Cnb*(B - A.translation());
40 
41  // FIXME: the matlab code checks for p_rel_c(0) greater than
42 
43  // azi = atan2(p_rel_c(2),p_rel_c(1));
44  double azimuth = atan2(p_rel_c(1),p_rel_c(0));
45  // elev = atan2(p_rel_c(3),sqrt(p_rel_c(1)^2 + p_rel_c(2)^2));
46  double elevation = atan2(p_rel_c(2),sqrt(p_rel_c(0) * p_rel_c(0) + p_rel_c(1) * p_rel_c(1)));
47  return BearingS2(azimuth, elevation);
48 }
49 
50 /* ************************************************************************* */
52  // Cnb = DCMnb(Att);
53  Matrix Cnb = A.rotation().matrix().transpose();
54 
55  Vector p_rel_c = Cnb*(B - A.translation());
56 
57  // FIXME: the matlab code checks for p_rel_c(0) greater than
58 
59  // azi = atan2(p_rel_c(2),p_rel_c(1));
60  double azimuth = atan2(p_rel_c(1),p_rel_c(0));
61  // elev = atan2(p_rel_c(3),sqrt(p_rel_c(1)^2 + p_rel_c(2)^2));
62  double elevation = atan2(p_rel_c(2),sqrt(p_rel_c(0) * p_rel_c(0) + p_rel_c(1) * p_rel_c(1)));
63  return BearingS2(azimuth, elevation);
64 }
65 
66 /* ************************************************************************* */
68  assert(v.size() == 2);
69  return BearingS2(azimuth_.retract(v.head(1)), elevation_.retract(v.tail(1)));
70 }
71 
72 /* ************************************************************************* */
74  return (Vector(2) << azimuth_.localCoordinates(x.azimuth_)(0),
75  elevation_.localCoordinates(x.elevation_)(0)).finished();
76 }
77 
78 } // \namespace gtsam
gtsam::BearingS2::fromForwardObservation
static BearingS2 fromForwardObservation(const Pose3 &A, const Point3 &B)
Definition: BearingS2.cpp:51
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::BearingS2::print
void print(const std::string &s="") const
Definition: BearingS2.cpp:19
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
gtsam::BearingS2::localCoordinates
Vector localCoordinates(const BearingS2 &p2) const
Local coordinates of BearingS2 manifold neighborhood around current pose.
Definition: BearingS2.cpp:73
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
gtsam::Pose3
Definition: Pose3.h:37
gtsam::BearingS2::fromDownwardsObservation
static BearingS2 fromDownwardsObservation(const POSE &A, const TARGET &B)
Definition: BearingS2.h:51
atan2
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:110
BearingS2.h
Manifold measurement between two points on a unit sphere.
gtsam
traits
Definition: SFMdata.h:40
std
Definition: BFloat16.h:88
gtsam::BearingS2::retract
BearingS2 retract(const Vector &v) const
Definition: BearingS2.cpp:67
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::BearingS2
Definition: BearingS2.h:18
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
gtsam::BearingS2::equals
bool equals(const BearingS2 &x, double tol=1e-9) const
Definition: BearingS2.cpp:24


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:11