-
Notifications
You must be signed in to change notification settings - Fork 919
Add PseudorangeFactorArm and DifferentialPseudorangeFactorArm #2447
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 3 commits
a964316
43549d0
d65e989
607db7b
b5e4a93
6833d66
0e5ba10
f3fc4fc
c792c05
8396ac5
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change | ||||||
|---|---|---|---|---|---|---|---|---|
|
|
@@ -7,6 +7,7 @@ | |||||||
| #pragma once | ||||||||
|
|
||||||||
| #include <gtsam/geometry/Point3.h> | ||||||||
| #include <gtsam/geometry/Pose3.h> | ||||||||
| #include <gtsam/nonlinear/NoiseModelFactorN.h> | ||||||||
| #include <gtsam/nonlinear/NonlinearFactor.h> | ||||||||
|
|
||||||||
|
|
@@ -225,4 +226,201 @@ template <> | |||||||
| struct traits<DifferentialPseudorangeFactor> | ||||||||
| : public Testable<DifferentialPseudorangeFactor> {}; | ||||||||
|
|
||||||||
| /** | ||||||||
| * GNSS pseudorange factor with lever arm correction. | ||||||||
| * | ||||||||
| * Like PseudorangeFactor, but uses a Pose3 (position + attitude) as the | ||||||||
| * receiver state variable, allowing compensation for a lever arm offset | ||||||||
| * between the body frame origin and the GNSS antenna location. | ||||||||
| * | ||||||||
| * The antenna position is computed as: | ||||||||
| * antenna_pos = nTb.translation() + nRb * bL_ | ||||||||
| * | ||||||||
| * where bL_ is the lever arm from the body origin to the antenna in the body | ||||||||
| * frame. The error model is: | ||||||||
| * error = ||antenna_pos - satPos|| + c*(dt_u - dt_s) - pseudorange | ||||||||
| * | ||||||||
| * @ingroup navigation | ||||||||
| */ | ||||||||
| class GTSAM_EXPORT PseudorangeFactorArm | ||||||||
| : public NoiseModelFactorN<Pose3, double>, | ||||||||
| private PseudorangeBase { | ||||||||
| private: | ||||||||
| typedef NoiseModelFactorN<Pose3, double> Base; | ||||||||
|
|
||||||||
| Point3 bL_; ///< Lever arm from body origin to antenna in body frame. | ||||||||
|
|
||||||||
| public: | ||||||||
| // Provide access to the Matrix& version of evaluateError: | ||||||||
| using Base::evaluateError; | ||||||||
|
|
||||||||
| /// shorthand for a smart pointer to a factor | ||||||||
| typedef std::shared_ptr<PseudorangeFactorArm> shared_ptr; | ||||||||
|
|
||||||||
| /// Typedef to this class | ||||||||
| typedef PseudorangeFactorArm This; | ||||||||
|
|
||||||||
| /** default constructor - only use for serialization */ | ||||||||
| PseudorangeFactorArm() : bL_(0, 0, 0) {} | ||||||||
|
|
||||||||
| virtual ~PseudorangeFactorArm() = default; | ||||||||
|
Comment on lines
+267
to
+270
|
||||||||
|
|
||||||||
| /** | ||||||||
| * Construct a PseudorangeFactorArm. | ||||||||
| * | ||||||||
| * @param nTbKey Receiver gtsam::Pose3 key (body pose in navigation frame). | ||||||||
| * @param receiverClockBiasKey Receiver clock bias node. | ||||||||
| * @param measuredPseudorange Receiver-measured pseudorange in meters. | ||||||||
| * @param satellitePosition Satellite ECEF position in meters. | ||||||||
| * @param leverArm Translation from body origin to antenna in body frame. | ||||||||
| * @param satelliteClockBias Satellite clock bias in seconds. | ||||||||
| * @param model 1-D pseudorange noise model. | ||||||||
| */ | ||||||||
| PseudorangeFactorArm( | ||||||||
| Key nTbKey, Key receiverClockBiasKey, | ||||||||
| double measuredPseudorange, const Point3& satellitePosition, | ||||||||
| const Point3& leverArm, double satelliteClockBias = 0.0, | ||||||||
| const SharedNoiseModel& model = noiseModel::Unit::Create(1)); | ||||||||
|
|
||||||||
| /// @return a deep copy of this factor | ||||||||
| gtsam::NonlinearFactor::shared_ptr clone() const override { | ||||||||
| return std::static_pointer_cast<gtsam::NonlinearFactor>( | ||||||||
| gtsam::NonlinearFactor::shared_ptr(new This(*this))); | ||||||||
| } | ||||||||
|
|
||||||||
| void print(const std::string& s = "", const KeyFormatter& keyFormatter = | ||||||||
| DefaultKeyFormatter) const override; | ||||||||
|
|
||||||||
| /// equals | ||||||||
| bool equals(const NonlinearFactor& expected, | ||||||||
| double tol = 1e-9) const override; | ||||||||
|
|
||||||||
| /// vector of errors | ||||||||
| Vector evaluateError(const Pose3& nTb, | ||||||||
| const double& receiverClockBias, | ||||||||
| OptionalMatrixType H_nTb, | ||||||||
| OptionalMatrixType HreceiverClockBias) const override; | ||||||||
|
|
||||||||
| /// return the lever arm, a position in the body frame | ||||||||
| inline const Point3& leverArm() const { return bL_; } | ||||||||
|
|
||||||||
| private: | ||||||||
| #if GTSAM_ENABLE_BOOST_SERIALIZATION /// | ||||||||
| /// Serialization function | ||||||||
| friend class boost::serialization::access; | ||||||||
| template <class ARCHIVE> | ||||||||
| void serialize(ARCHIVE& ar, const unsigned int /*version*/) { | ||||||||
| ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PseudorangeFactorArm::Base); | ||||||||
| ar& BOOST_SERIALIZATION_NVP(pseudorange_); | ||||||||
| ar& BOOST_SERIALIZATION_NVP(satPos_); | ||||||||
| ar& BOOST_SERIALIZATION_NVP(satClkBias_); | ||||||||
| ar& BOOST_SERIALIZATION_NVP(bL_); | ||||||||
| } | ||||||||
| #endif | ||||||||
| }; | ||||||||
|
|
||||||||
| /// traits | ||||||||
| template <> | ||||||||
| struct traits<PseudorangeFactorArm> | ||||||||
| : public Testable<PseudorangeFactorArm> {}; | ||||||||
|
|
||||||||
| /** | ||||||||
| * Differentially-corrected pseudorange factor with lever arm correction. | ||||||||
| * | ||||||||
| * Combines the differential correction model of DifferentialPseudorangeFactor | ||||||||
| * with the lever arm compensation of PseudorangeFactorArm. Uses a Pose3 | ||||||||
| * (position + attitude) as the receiver state variable. | ||||||||
| * | ||||||||
| * The error model is: | ||||||||
| * error = ||antenna_pos - satPos|| + c*(dt_u - dt_s) - pseudorange - correction | ||||||||
| * | ||||||||
| * @ingroup navigation | ||||||||
| */ | ||||||||
| class GTSAM_EXPORT DifferentialPseudorangeFactorArm | ||||||||
| : public NoiseModelFactorN<Pose3, double, double>, | ||||||||
| private PseudorangeBase { | ||||||||
| private: | ||||||||
| typedef NoiseModelFactorN<Pose3, double, double> Base; | ||||||||
|
|
||||||||
| Point3 bL_; ///< Lever arm from body origin to antenna in body frame. | ||||||||
|
|
||||||||
| public: | ||||||||
| // Provide access to the Matrix& version of evaluateError: | ||||||||
| using Base::evaluateError; | ||||||||
|
|
||||||||
| /// shorthand for a smart pointer to a factor | ||||||||
| typedef std::shared_ptr<DifferentialPseudorangeFactorArm> shared_ptr; | ||||||||
|
|
||||||||
| /// Typedef to this class | ||||||||
| typedef DifferentialPseudorangeFactorArm This; | ||||||||
|
|
||||||||
| /** default constructor - only use for serialization */ | ||||||||
| DifferentialPseudorangeFactorArm() : bL_(0, 0, 0) {} | ||||||||
|
||||||||
| DifferentialPseudorangeFactorArm() : bL_(0, 0, 0) {} | |
| DifferentialPseudorangeFactorArm() | |
| : PseudorangeBase{0.0, Point3(0, 0, 0), 0.0}, bL_(0, 0, 0) {} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
std::numeric_limits<double>::epsilon()is used here in the new code path, but this translation unit does not include<limits>directly. It likely compiles today via transitive includes, but it’s brittle; add an explicit#include <limits>in this.cpp(or the relevant header) to make the dependency explicit.