Switch measured/reference language.

release/4.3a0
Frank Dellaert 2024-10-30 12:04:04 -07:00
parent 0c0ae7478c
commit 38ffcc3e5c
5 changed files with 104 additions and 107 deletions

View File

@ -26,16 +26,16 @@ namespace gtsam {
Vector AttitudeFactor::attitudeError(const Rot3& nRb, Vector AttitudeFactor::attitudeError(const Rot3& nRb,
OptionalJacobian<2, 3> H) const { OptionalJacobian<2, 3> H) const {
if (H) { if (H) {
Matrix23 D_nRef_R; Matrix23 D_nRotated_R;
Matrix22 D_e_nRef; Matrix22 D_e_nRotated;
Unit3 nRef = nRb.rotate(bRef_, D_nRef_R); Unit3 nRotated = nRb.rotate(bMeasured_, D_nRotated_R);
Vector e = nZ_.error(nRef, D_e_nRef); Vector e = nRef_.error(nRotated, D_e_nRotated);
(*H) = D_e_nRef * D_nRef_R; (*H) = D_e_nRotated * D_nRotated_R;
return e; return e;
} else { } else {
Unit3 nRef = nRb * bRef_; Unit3 nRotated = nRb * bMeasured_;
return nZ_.error(nRef); return nRef_.error(nRotated);
} }
} }
@ -44,8 +44,8 @@ void Rot3AttitudeFactor::print(const string& s,
const KeyFormatter& keyFormatter) const { const KeyFormatter& keyFormatter) const {
cout << (s.empty() ? "" : s + " ") << "Rot3AttitudeFactor on " cout << (s.empty() ? "" : s + " ") << "Rot3AttitudeFactor on "
<< keyFormatter(this->key()) << "\n"; << keyFormatter(this->key()) << "\n";
nZ_.print(" measured direction in nav frame: "); nRef_.print(" reference direction in nav frame: ");
bRef_.print(" reference direction in body frame: "); bMeasured_.print(" measured direction in body frame: ");
this->noiseModel_->print(" noise model: "); this->noiseModel_->print(" noise model: ");
} }
@ -53,16 +53,16 @@ void Rot3AttitudeFactor::print(const string& s,
bool Rot3AttitudeFactor::equals(const NonlinearFactor& expected, bool Rot3AttitudeFactor::equals(const NonlinearFactor& expected,
double tol) const { double tol) const {
const This* e = dynamic_cast<const This*>(&expected); const This* e = dynamic_cast<const This*>(&expected);
return e != nullptr && Base::equals(*e, tol) && this->nZ_.equals(e->nZ_, tol) return e != nullptr && Base::equals(*e, tol) && this->nRef_.equals(e->nRef_, tol)
&& this->bRef_.equals(e->bRef_, tol); && this->bMeasured_.equals(e->bMeasured_, tol);
} }
//*************************************************************************** //***************************************************************************
void Pose3AttitudeFactor::print(const string& s, void Pose3AttitudeFactor::print(const string& s,
const KeyFormatter& keyFormatter) const { const KeyFormatter& keyFormatter) const {
cout << s << "Pose3AttitudeFactor on " << keyFormatter(this->key()) << "\n"; cout << s << "Pose3AttitudeFactor on " << keyFormatter(this->key()) << "\n";
nZ_.print(" measured direction in nav frame: "); nRef_.print(" reference direction in nav frame: ");
bRef_.print(" reference direction in body frame: "); bMeasured_.print(" measured direction in body frame: ");
this->noiseModel_->print(" noise model: "); this->noiseModel_->print(" noise model: ");
} }
@ -70,8 +70,8 @@ void Pose3AttitudeFactor::print(const string& s,
bool Pose3AttitudeFactor::equals(const NonlinearFactor& expected, bool Pose3AttitudeFactor::equals(const NonlinearFactor& expected,
double tol) const { double tol) const {
const This* e = dynamic_cast<const This*>(&expected); const This* e = dynamic_cast<const This*>(&expected);
return e != nullptr && Base::equals(*e, tol) && this->nZ_.equals(e->nZ_, tol) return e != nullptr && Base::equals(*e, tol) && this->nRef_.equals(e->nRef_, tol)
&& this->bRef_.equals(e->bRef_, tol); && this->bMeasured_.equals(e->bMeasured_, tol);
} }
//*************************************************************************** //***************************************************************************

View File

@ -29,13 +29,13 @@ namespace gtsam {
* @brief Base class for an attitude factor that constrains the rotation between * @brief Base class for an attitude factor that constrains the rotation between
* body and navigation frames. * body and navigation frames.
* *
* This factor enforces that when a known reference direction in the body frame * This factor enforces that when the measured direction in the body frame
* (e.g., accelerometer axis) is rotated into the navigation frame using the * (e.g., from an IMU accelerometer) is rotated into the navigation frame using the
* rotation variable, it should align with a measured direction in the * rotation variable, it should align with a known reference direction in the
* navigation frame (e.g., gravity vector). * navigation frame (e.g., gravity vector).
* *
* Mathematically, the error is zero when: * Mathematically, the error is zero when:
* nRb * bRef == nZ * nRb * bMeasured == nRef
* *
* This is useful for incorporating absolute orientation measurements into the * This is useful for incorporating absolute orientation measurements into the
* factor graph. * factor graph.
@ -44,7 +44,7 @@ namespace gtsam {
*/ */
class AttitudeFactor { class AttitudeFactor {
protected: protected:
Unit3 nZ_, bRef_; ///< Position measurement in Unit3 nRef_, bMeasured_; ///< Position measurement in
public: public:
/** default constructor - only use for serialization */ /** default constructor - only use for serialization */
@ -52,26 +52,34 @@ class AttitudeFactor {
/** /**
* @brief Constructor * @brief Constructor
* @param nZ Measured direction in the navigation frame (e.g., gravity). * @param nRef Reference direction in the navigation frame (e.g., gravity).
* @param bRef Reference direction in the body frame (e.g., accelerometer * @param bMeasured Measured direction in the body frame (e.g., from IMU
* axis). Default is Unit3(0, 0, 1). * accelerometer). Default is Unit3(0, 0, 1).
*/ */
AttitudeFactor(const Unit3& nZ, const Unit3& bRef = Unit3(0, 0, 1)) AttitudeFactor(const Unit3& nRef, const Unit3& bMeasured = Unit3(0, 0, 1))
: nZ_(nZ), bRef_(bRef) {} : nRef_(nRef), bMeasured_(bMeasured) {}
/** vector of errors */ /** vector of errors */
Vector attitudeError(const Rot3& p, OptionalJacobian<2, 3> H = {}) const; Vector attitudeError(const Rot3& p, OptionalJacobian<2, 3> H = {}) const;
const Unit3& nZ() const { return nZ_; } const Unit3& nRef() const { return nRef_; }
const Unit3& bRef() const { return bRef_; } const Unit3& bMeasured() const { return bMeasured_; }
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
[[deprecated("Use nRef() instead")]]
const Unit3& nZ() const { return nRef_; }
[[deprecated("Use bMeasured() instead")]]
const Unit3& bRef() const { return bMeasured_; }
#endif
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
void serialize(ARCHIVE& ar, const unsigned int /*version*/) { void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
ar& boost::serialization::make_nvp("nZ_", nZ_); ar& boost::serialization::make_nvp("nRef_", nRef_);
ar& boost::serialization::make_nvp("bRef_", bRef_); ar& boost::serialization::make_nvp("bMeasured_", bMeasured_);
} }
#endif #endif
}; };
@ -102,13 +110,13 @@ class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN<Rot3>,
/** /**
* @brief Constructor * @brief Constructor
* @param key of the Rot3 variable that will be constrained * @param key of the Rot3 variable that will be constrained
* @param nZ measured direction in navigation frame * @param nRef reference direction in navigation frame
* @param model Gaussian noise model * @param model Gaussian noise model
* @param bRef reference direction in body frame (default Z-axis) * @param bMeasured measured direction in body frame (default Z-axis)
*/ */
Rot3AttitudeFactor(Key key, const Unit3& nZ, const SharedNoiseModel& model, Rot3AttitudeFactor(Key key, const Unit3& nRef, const SharedNoiseModel& model,
const Unit3& bRef = Unit3(0, 0, 1)) const Unit3& bMeasured = Unit3(0, 0, 1))
: Base(model, key), AttitudeFactor(nZ, bRef) {} : Base(model, key), AttitudeFactor(nRef, bMeasured) {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {
@ -178,13 +186,13 @@ class GTSAM_EXPORT Pose3AttitudeFactor : public NoiseModelFactorN<Pose3>,
/** /**
* @brief Constructor * @brief Constructor
* @param key of the Pose3 variable that will be constrained * @param key of the Pose3 variable that will be constrained
* @param nZ measured direction in navigation frame * @param nRef reference direction in navigation frame
* @param model Gaussian noise model * @param model Gaussian noise model
* @param bRef reference direction in body frame (default Z-axis) * @param bMeasured measured direction in body frame (default Z-axis)
*/ */
Pose3AttitudeFactor(Key key, const Unit3& nZ, const SharedNoiseModel& model, Pose3AttitudeFactor(Key key, const Unit3& nRef, const SharedNoiseModel& model,
const Unit3& bRef = Unit3(0, 0, 1)) const Unit3& bMeasured = Unit3(0, 0, 1))
: Base(model, key), AttitudeFactor(nZ, bRef) {} : Base(model, key), AttitudeFactor(nRef, bMeasured) {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -12,24 +12,24 @@ This document explains the mathematical foundation of the `AttitudeFactor` and g
### Concept ### Concept
The `AttitudeFactor` constrains the rotation $\mathbf{R}_{nb}$ (from body frame $b$ to navigation frame $n$) such that a known reference direction in the body frame aligns with a measured direction in the navigation frame when rotated. The factor enforces that: The `AttitudeFactor` constrains the rotation $\mathbf{R}_{nb}$ (from body frame $b$ to navigation frame $n$) such that a known reference direction in the navigation frame aligns with a measured direction in the body frame, when rotated. The factor enforces that:
$$ $$
\mathbf{R}_{nb} \cdot \mathbf{b}_{\text{Ref}} \approx \mathbf{nZ} \text{nRef} \approx \mathbf{R}_{nb} \cdot \text{bMeasured}
$$ $$
where: where:
- $\mathbf{R}_{nb}$ is the rotation matrix representing the orientation from body to navigation frame. - $\mathbf{R}_{nb}$ is the rotation matrix representing the orientation from body to navigation frame.
- $\mathbf{b}_{\text{Ref}}$ is a known reference direction in the body frame (e.g., the accelerometer's sensitive axis). - $\text{bMeasured}$ is the measured direction in the body frame (e.g., the accelerometer reading).
- $\mathbf{nZ}$ is the measured direction in the navigation frame (e.g., the gravity vector measured by an IMU). - $\text{nRef}$ is the known reference direction in the navigation frame (e.g., the gravity vector in nav).
### Error Function ### Error Function
The error function computes the angular difference between the rotated reference direction and the measured direction: The error function computes the angular difference between the rotated reference direction and the measured direction:
$$ $$
\mathbf{e} = \text{error}(\mathbf{nZ}, \mathbf{R}_{nb} \cdot \mathbf{b}_{\text{Ref}}) \mathbf{e} = \text{error}(\text{nRef}, \mathbf{R}_{nb} \cdot \text{bMeasured})
$$ $$
This error is minimal (zero) when the rotated body reference direction aligns perfectly with the measured navigation direction. This error is minimal (zero) when the rotated body reference direction aligns perfectly with the measured navigation direction.
@ -38,19 +38,21 @@ The error is computed internally using the `attitudeError` function:
```cpp ```cpp
Vector AttitudeFactor::attitudeError(const Rot3& nRb) const { Vector AttitudeFactor::attitudeError(const Rot3& nRb) const {
Unit3 nRef = nRb * bRef_; Unit3 nRotated = nRb * bMeasured_;
return nZ_.error(nRef); return nRef_.error(nRotated);
} }
``` ```
#### Explanation: #### Explanation:
- The function computes the rotated reference direction `nRef` and then the error between `nRef` and the measured direction `nZ`. - The function computes the rotated measurement `nRotated` and then the error between `nRef` and `nRotated`.
- `nZ_.error(nRef)` is a 2D vector-valued error between two directions, defined in [Unit3.h](../geometry/Unit3.h). - `nRef_.error(nRotated)` is a 2D vector-valued error between two directions, defined in [Unit3.h](../geometry/Unit3.h).
### Jacobians ### Jacobians
For optimization, the $2 \times 3$ Jacobian of the error function with respect to the rotation parameters is required. The Jacobian is computed using chain rule differentiation, involving the derivative of the rotated vector with respect to the rotation parameters and the derivative of the error with respect to the rotated vector. For optimization, the $2 \times 3$ Jacobian of the error function with respect to the rotation parameters is required. The Jacobian is computed using chain rule differentiation, involving the derivative of the rotated vector with respect to the rotation parameters and the derivative of the error with respect to the rotated vector.
Note the Jacobian for this specific error function vanishes 180 degrees away from the true direction, and the factor is only expected to behave well when the `nRb` value is initialized in the correct hemisphere.
## Usage in GTSAM ## Usage in GTSAM
### Including the Header ### Including the Header
@ -71,55 +73,49 @@ You can create an attitude factor for either a `Rot3` (rotation only) or a `Pose
// Define keys // Define keys
gtsam::Key rotKey = ...; gtsam::Key rotKey = ...;
// Measured direction in navigation frame (e.g., gravity) // Known reference direction in navigation frame (e.g., gravity)
gtsam::Unit3 nZ(0, 0, -1); // Assuming gravity points down in navigation frame gtsam::Unit3 nRef(0, 0, -1); // Assuming gravity points down in navigation frame
// Reference direction in body frame (e.g., accelerometer axis) // Measured direction in body frame (e.g., accelerometer direction)
gtsam::Unit3 bRef(0, 0, 1); // Default is the Z-axis gtsam::Unit3 bMeasured(0, 0, 9.8); // will be normalized automatically
// Noise model // Noise model
auto noiseModel = gtsam::noiseModel::Isotropic::Sigma(2, 0.1); // 2D error, sigma = 0.1 auto noiseModel = gtsam::noiseModel::Isotropic::Sigma(2, 0.1); // 2D error, sigma = 0.1
// Add to factor graph // Add to factor graph
gtsam::NonlinearFactorGraph graph; gtsam::NonlinearFactorGraph graph;
graph.emplace_shared<Rot3AttitudeFactor>(rotKey, nZ, noiseModel, bRef); graph.emplace_shared<Rot3AttitudeFactor>(rotKey, nRef, noiseModel, bMeasured);
``` ```
#### For `Pose3` Variables #### For `Pose3` Variables
There is also a `Pose3AttitudeFactor` that automatically extracts the rotation from the pose, taking into account the chain rule for this operation so the Jacobians with respect to pose are correct. There is also a `Pose3AttitudeFactor` that automatically extracts the rotation from the pose, taking into account the chain rule for this operation so the Jacobians with respect to pose are correct.
The same caveat about vanishing Jacobian holds.
```cpp ```cpp
// Define keys // Define keys
gtsam::Key poseKey = ...; gtsam::Key poseKey = ...;
// Measured direction in navigation frame // Known reference direction in navigation frame (e.g., gravity)
gtsam::Unit3 nZ(0, 0, -1); gtsam::Unit3 nRef(0, 0, -1); // Assuming gravity points down in navigation frame
// Reference direction in body frame // Measured direction in body frame (e.g., accelerometer direction)
gtsam::Unit3 bRef(0, 0, 1); gtsam::Unit3 bMeasured(0, 0, 9.8); // will be normalized automatically
// Noise model // Noise model
auto noiseModel = gtsam::noiseModel::Isotropic::Sigma(2, 0.1); auto noiseModel = gtsam::noiseModel::Isotropic::Sigma(2, 0.1);
// Add to factor graph // Add to factor graph
gtsam::NonlinearFactorGraph graph; gtsam::NonlinearFactorGraph graph;
graph.emplace_shared<Pose3AttitudeFactor>(poseKey, nZ, noiseModel, bRef); graph.emplace_shared<Pose3AttitudeFactor>(poseKey, nRef, noiseModel, bMeasured);
``` ```
### Explanation of Parameters ### Explanation of Parameters
- **Key**: The variable key in the factor graph corresponding to the `Rot3` or `Pose3` variable you are constraining. - **Key**: The variable key in the factor graph corresponding to the `Rot3` or `Pose3` variable you are constraining.
- **nZ**: The measured direction in the navigation frame. This is typically obtained from sensors like accelerometers or magnetometers. - **nRef**: The known direction in the navigation frame. This is typically obtained from sensors like accelerometers or magnetometers.
- **bRef**: The known reference direction in the body frame. By default, this is set to the Z-axis `[0; 0; 1]`, but it should match the direction your sensor measures. - **bMeasured**: The measured direction in the body frame. By default, this is set to the Z-axis `[0; 0; 1]`, but it should match the direction your sensor measures. When constructing a `Unit3`, will be automatically normalized.
- **noiseModel**: The noise model representing the uncertainty in the measurement. - **noiseModel**: The noise model representing the uncertainty in the measurement. Adjust the standard deviation based on the confidence in your measurements.
## Practical Tips
- **Gravity Measurement**: When using an IMU, the accelerometer readings (after removing the dynamic acceleration) can provide the gravity direction in the body frame.
- **Magnetic North Measurement**: A magnetometer can provide the direction of the Earth's magnetic field, which can be used similarly.
- **Reference Direction**: Ensure that `bRef` correctly represents the sensor's measurement axis in the body frame.
- **Noise Model**: The choice of noise model affects the weight of this factor in the optimization. Adjust the standard deviation based on the confidence in your measurements.
## Example in GPS-Denied Navigation ## Example in GPS-Denied Navigation
@ -132,9 +128,7 @@ This factor helps maintain an accurate orientation estimate over time, which is
## Conclusion ## Conclusion
The `AttitudeFactor` is a powerful tool in GTSAM for incorporating orientation measurements into your factor graph. By aligning a known reference direction in the body frame with a measured direction in the navigation frame, it provides a constraint that improves the estimation of the rotation variable. Correct understanding and usage of this factor enhance the performance of navigation algorithms, especially in challenging environments where GPS is unavailable. The `AttitudeFactor` is a useful tool in GTSAM for incorporating orientation measurements into your factor graph. By aligning a measured direction in the body frame with a known reference direction in the navigation frame, it provides a constraint that improves the estimation of the rotation variable. Correct understanding and usage of this factor enhance the performance of navigation algorithms, especially in challenging environments where GPS is unavailable.
Remember to verify the alignment of your reference and measured directions and to adjust the noise model to reflect the reliability of your sensors.
# References # References

View File

@ -256,34 +256,30 @@ virtual class AHRSFactor : gtsam::NonlinearFactor {
}; };
#include <gtsam/navigation/AttitudeFactor.h> #include <gtsam/navigation/AttitudeFactor.h>
//virtual class AttitudeFactor : gtsam::NonlinearFactor { virtual class Rot3AttitudeFactor : gtsam::NoiseModelFactor {
// AttitudeFactor(const Unit3& nZ, const Unit3& bRef); Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nRef, const gtsam::noiseModel::Diagonal* model,
// AttitudeFactor(); const gtsam::Unit3& bMeasured);
//}; Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nRef, const gtsam::noiseModel::Diagonal* model);
virtual class Rot3AttitudeFactor : gtsam::NonlinearFactor{
Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model,
const gtsam::Unit3& bRef);
Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model);
Rot3AttitudeFactor(); Rot3AttitudeFactor();
void print(string s = "", const gtsam::KeyFormatter& keyFormatter = void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const; gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::NonlinearFactor& expected, double tol) const; bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
gtsam::Unit3 nZ() const; gtsam::Unit3 nRef() const;
gtsam::Unit3 bRef() const; gtsam::Unit3 bMeasured() const;
}; };
virtual class Pose3AttitudeFactor : gtsam::NonlinearFactor { virtual class Pose3AttitudeFactor : gtsam::NoiseModelFactor {
Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nRef,
const gtsam::noiseModel::Diagonal* model, const gtsam::noiseModel::Diagonal* model,
const gtsam::Unit3& bRef); const gtsam::Unit3& bMeasured);
Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nRef,
const gtsam::noiseModel::Diagonal* model); const gtsam::noiseModel::Diagonal* model);
Pose3AttitudeFactor(); Pose3AttitudeFactor();
void print(string s = "", const gtsam::KeyFormatter& keyFormatter = void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const; gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::NonlinearFactor& expected, double tol) const; bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
gtsam::Unit3 nZ() const; gtsam::Unit3 nRef() const;
gtsam::Unit3 bRef() const; gtsam::Unit3 bMeasured() const;
}; };
#include <gtsam/navigation/GPSFactor.h> #include <gtsam/navigation/GPSFactor.h>

View File

@ -11,44 +11,44 @@
/** /**
* @file testAttitudeFactor.cpp * @file testAttitudeFactor.cpp
* @brief Unit test for Rot3AttitudeFactor * @brief Unit test for AttitudeFactors (rot3 and Pose3 versions)
* @author Frank Dellaert * @author Frank Dellaert
* @date January 22, 2014 * @date January 22, 2014
*/ */
#include <gtsam/navigation/AttitudeFactor.h> #include <CppUnitLite/TestHarness.h>
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h> #include <gtsam/base/numericalDerivative.h>
#include <gtsam/navigation/AttitudeFactor.h>
#include <functional> #include <functional>
#include "gtsam/base/Matrix.h" #include "gtsam/base/Matrix.h"
#include <CppUnitLite/TestHarness.h>
using namespace std::placeholders; using namespace std::placeholders;
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
// ************************************************************************* // *************************************************************************
TEST( Rot3AttitudeFactor, Constructor ) { TEST(Rot3AttitudeFactor, Constructor) {
// Example: pitch and roll of aircraft in an ENU Cartesian frame. // Example: pitch and roll of aircraft in an ENU Cartesian frame.
// If pitch and roll are zero for an aerospace frame, // If pitch and roll are zero for an aerospace frame,
// that means Z is pointing down, i.e., direction of Z = (0,0,-1) // that means Z is pointing down, i.e., direction of Z = (0,0,-1)
Unit3 bZ(0, 0, 1); // reference direction is body Z axis Unit3 bMeasured(0, 0, 1); // measured direction is body Z axis
Unit3 nDown(0, 0, -1); // down, in ENU navigation frame, is "measurement" Unit3 nDown(0, 0, -1); // down, in ENU navigation frame, is "reference"
// Factor // Factor
Key key(1); Key key(1);
SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25); SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25);
Rot3AttitudeFactor factor0(key, nDown, model); Rot3AttitudeFactor factor0(key, nDown, model);
Rot3AttitudeFactor factor(key, nDown, model, bZ); Rot3AttitudeFactor factor(key, nDown, model, bMeasured);
EXPECT(assert_equal(factor0,factor,1e-5)); EXPECT(assert_equal(factor0, factor, 1e-5));
// Create a linearization point at the zero-error point // Create a linearization point at the zero-error point
Rot3 nRb; Rot3 nRb;
EXPECT(assert_equal((Vector) Z_2x1,factor.evaluateError(nRb),1e-5)); EXPECT(assert_equal((Vector)Z_2x1, factor.evaluateError(nRb), 1e-5));
auto err_fn = [&factor](const Rot3& r){ auto err_fn = [&factor](const Rot3& r) {
return factor.evaluateError(r, OptionalNone); return factor.evaluateError(r, OptionalNone);
}; };
// Calculate numerical derivatives // Calculate numerical derivatives
@ -80,32 +80,31 @@ TEST(Rot3AttitudeFactor, CopyAndMove) {
} }
// ************************************************************************* // *************************************************************************
TEST( Pose3AttitudeFactor, Constructor ) { TEST(Pose3AttitudeFactor, Constructor) {
// Example: pitch and roll of aircraft in an ENU Cartesian frame. // Example: pitch and roll of aircraft in an ENU Cartesian frame.
// If pitch and roll are zero for an aerospace frame, // If pitch and roll are zero for an aerospace frame,
// that means Z is pointing down, i.e., direction of Z = (0,0,-1) // that means Z is pointing down, i.e., direction of Z = (0,0,-1)
Unit3 bZ(0, 0, 1); // reference direction is body Z axis Unit3 bMeasured(0, 0, 1); // measured direction is body Z axis
Unit3 nDown(0, 0, -1); // down, in ENU navigation frame, is "measurement" Unit3 nDown(0, 0, -1); // down, in ENU navigation frame, is "reference"
// Factor // Factor
Key key(1); Key key(1);
SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25); SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25);
Pose3AttitudeFactor factor0(key, nDown, model); Pose3AttitudeFactor factor0(key, nDown, model);
Pose3AttitudeFactor factor(key, nDown, model, bZ); Pose3AttitudeFactor factor(key, nDown, model, bMeasured);
EXPECT(assert_equal(factor0,factor,1e-5)); EXPECT(assert_equal(factor0, factor, 1e-5));
// Create a linearization point at the zero-error point // Create a linearization point at the zero-error point
Pose3 T(Rot3(), Point3(-5.0, 8.0, -11.0)); Pose3 T(Rot3(), Point3(-5.0, 8.0, -11.0));
EXPECT(assert_equal((Vector) Z_2x1,factor.evaluateError(T),1e-5)); EXPECT(assert_equal((Vector)Z_2x1, factor.evaluateError(T), 1e-5));
Matrix actualH1; Matrix actualH1;
auto err_fn = [&factor](const Pose3& p){ auto err_fn = [&factor](const Pose3& p) {
return factor.evaluateError(p, OptionalNone); return factor.evaluateError(p, OptionalNone);
}; };
// Calculate numerical derivatives // Calculate numerical derivatives
Matrix expectedH = numericalDerivative11<Vector,Pose3>(err_fn, T); Matrix expectedH = numericalDerivative11<Vector, Pose3>(err_fn, T);
// Use the factor to calculate the derivative // Use the factor to calculate the derivative
Matrix actualH; Matrix actualH;