AttitudeFactor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include "AttitudeFactor.h"
20 
21 using namespace std;
22 
23 namespace gtsam {
24 
25 //***************************************************************************
26 Vector AttitudeFactor::attitudeError(const Rot3& nRb,
27  OptionalJacobian<2, 3> H) const {
28  if (H) {
29  Matrix23 D_nRef_R;
30  Matrix22 D_e_nRef;
31  Unit3 nRef = nRb.rotate(bRef_, D_nRef_R);
32  Vector e = nZ_.error(nRef, D_e_nRef);
33 
34  (*H) = D_e_nRef * D_nRef_R;
35  return e;
36  } else {
37  Unit3 nRef = nRb * bRef_;
38  return nZ_.error(nRef);
39  }
40 }
41 
42 //***************************************************************************
43 void Rot3AttitudeFactor::print(const string& s,
44  const KeyFormatter& keyFormatter) const {
45  cout << (s.empty() ? "" : s + " ") << "Rot3AttitudeFactor on "
46  << keyFormatter(this->key()) << "\n";
47  nZ_.print(" measured direction in nav frame: ");
48  bRef_.print(" reference direction in body frame: ");
49  this->noiseModel_->print(" noise model: ");
50 }
51 
52 //***************************************************************************
53 bool Rot3AttitudeFactor::equals(const NonlinearFactor& expected,
54  double tol) const {
55  const This* e = dynamic_cast<const This*>(&expected);
56  return e != nullptr && Base::equals(*e, tol) && this->nZ_.equals(e->nZ_, tol)
57  && this->bRef_.equals(e->bRef_, tol);
58 }
59 
60 //***************************************************************************
61 void Pose3AttitudeFactor::print(const string& s,
62  const KeyFormatter& keyFormatter) const {
63  cout << s << "Pose3AttitudeFactor on " << keyFormatter(this->key()) << "\n";
64  nZ_.print(" measured direction in nav frame: ");
65  bRef_.print(" reference direction in body frame: ");
66  this->noiseModel_->print(" noise model: ");
67 }
68 
69 //***************************************************************************
70 bool Pose3AttitudeFactor::equals(const NonlinearFactor& expected,
71  double tol) const {
72  const This* e = dynamic_cast<const This*>(&expected);
73  return e != nullptr && Base::equals(*e, tol) && this->nZ_.equals(e->nZ_, tol)
74  && this->bRef_.equals(e->bRef_, tol);
75 }
76 
77 //***************************************************************************
78 
79 }
H
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Factor
Definition: Factor.h:69
initial::nRb
const Rot3 nRb
Definition: testScenarioRunner.cpp:149
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
AttitudeFactor.h
Header file for Attitude factor.
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
key
const gtsam::Symbol key('X', 0)
gtsam
traits
Definition: chartTesting.h:28
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
std
Definition: BFloat16.h:88
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:29