Skip to content
Merged
139 changes: 139 additions & 0 deletions gtsam/navigation/PseudorangeFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,4 +134,143 @@ Vector DifferentialPseudorangeFactor::evaluateError(

return Vector1(error);
}
//***************************************************************************
PseudorangeFactorArm::PseudorangeFactorArm(
const Key nTbKey, const Key receiverClockBiasKey,
const double measuredPseudorange, const Point3& satellitePosition,
const Point3& leverArm, const double satelliteClockBias,
const SharedNoiseModel& model)
: Base(model, nTbKey, receiverClockBiasKey),
PseudorangeBase{measuredPseudorange, satellitePosition,
satelliteClockBias},
bL_(leverArm) {}

//***************************************************************************
void PseudorangeFactorArm::print(const std::string& s,
const KeyFormatter& keyFormatter) const {
Base::print(s, keyFormatter);
gtsam::print(pseudorange_, "pseudorange (m): ");
gtsam::print(Vector(satPos_), "sat position (ECEF meters): ");
gtsam::print(satClkBias_, "sat clock bias (s): ");
gtsam::print(Vector(bL_), "lever arm (body frame meters): ");
}

//***************************************************************************
bool PseudorangeFactorArm::equals(const NonlinearFactor& expected,
double tol) const {
const This* e = dynamic_cast<const This*>(&expected);
return e != nullptr && Base::equals(*e, tol) &&
traits<double>::Equals(pseudorange_, e->pseudorange_, tol) &&
traits<Point3>::Equals(satPos_, e->satPos_, tol) &&
traits<double>::Equals(satClkBias_, e->satClkBias_, tol) &&
traits<Point3>::Equals(bL_, e->bL_, tol);
}

//***************************************************************************
Vector PseudorangeFactorArm::evaluateError(
const Pose3& nTb, const double& receiverClockBias,
OptionalMatrixType H_nTb,
OptionalMatrixType HreceiverClockBias) const {
// Compute antenna position in the navigation frame:
const Matrix3 nRb = nTb.rotation().matrix();
const Point3 antennaPos = nTb.translation() + nRb * bL_;

// Apply pseudorange equation: rho = range + c*[dt_u - dt^s]
const Vector3 position_difference = antennaPos - satPos_;
const double range = position_difference.norm();
const double rho = range + CLIGHT * (receiverClockBias - satClkBias_);
const double error = rho - pseudorange_;

// Compute associated derivatives:
if (H_nTb) {
if (range < std::numeric_limits<double>::epsilon()) {
*H_nTb = Matrix16::Zero();
} else {
Comment on lines +189 to +191
Copy link

Copilot AI Mar 4, 2026

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.

Copilot uses AI. Check for mistakes.
// u = unit vector from satellite to antenna
const RowVector3d u = (position_difference / range).transpose();
H_nTb->resize(1, 6);
H_nTb->block<1, 3>(0, 0) = u * (-nRb * skewSymmetric(bL_));
H_nTb->block<1, 3>(0, 3) = u * nRb;
}
}

if (HreceiverClockBias) {
*HreceiverClockBias = I_1x1 * CLIGHT;
}

return Vector1(error);
}

//***************************************************************************
DifferentialPseudorangeFactorArm::DifferentialPseudorangeFactorArm(
const Key nTbKey, const Key receiverClockBiasKey,
const Key differentialCorrectionKey, const double measuredPseudorange,
const Point3& satellitePosition, const Point3& leverArm,
const double satelliteClockBias, const SharedNoiseModel& model)
: Base(model, nTbKey, receiverClockBiasKey, differentialCorrectionKey),
PseudorangeBase{measuredPseudorange, satellitePosition,
satelliteClockBias},
bL_(leverArm) {}

//***************************************************************************
void DifferentialPseudorangeFactorArm::print(
const std::string& s, const KeyFormatter& keyFormatter) const {
Base::print(s, keyFormatter);
gtsam::print(pseudorange_, "pseudorange (m): ");
gtsam::print(Vector(satPos_), "sat position (ECEF meters): ");
gtsam::print(satClkBias_, "sat clock bias (s): ");
gtsam::print(Vector(bL_), "lever arm (body frame meters): ");
}

//***************************************************************************
bool DifferentialPseudorangeFactorArm::equals(
const NonlinearFactor& expected, double tol) const {
const This* e = dynamic_cast<const This*>(&expected);
return e != nullptr && Base::equals(*e, tol) &&
traits<double>::Equals(pseudorange_, e->pseudorange_, tol) &&
traits<Point3>::Equals(satPos_, e->satPos_, tol) &&
traits<double>::Equals(satClkBias_, e->satClkBias_, tol) &&
traits<Point3>::Equals(bL_, e->bL_, tol);
}

//***************************************************************************
Vector DifferentialPseudorangeFactorArm::evaluateError(
const Pose3& nTb, const double& receiverClockBias,
const double& differentialCorrection, OptionalMatrixType H_nTb,
OptionalMatrixType HreceiverClockBias,
OptionalMatrixType HdifferentialCorrection) const {
// Compute antenna position in the navigation frame:
const Matrix3 nRb = nTb.rotation().matrix();
const Point3 antennaPos = nTb.translation() + nRb * bL_;

// Apply pseudorange equation: rho = range + c*[dt_u - dt^s]
const Vector3 position_difference = antennaPos - satPos_;
const double range = position_difference.norm();
const double rho = range + CLIGHT * (receiverClockBias - satClkBias_);
const double error = rho - pseudorange_ - differentialCorrection;

// Compute associated derivatives:
if (H_nTb) {
if (range < std::numeric_limits<double>::epsilon()) {
*H_nTb = Matrix16::Zero();
} else {
// u = unit vector from satellite to antenna
const RowVector3d u = (position_difference / range).transpose();
H_nTb->resize(1, 6);
H_nTb->block<1, 3>(0, 0) = u * (-nRb * skewSymmetric(bL_));
H_nTb->block<1, 3>(0, 3) = u * nRb;
}
}

if (HreceiverClockBias) {
*HreceiverClockBias = I_1x1 * CLIGHT;
}

if (HdifferentialCorrection) {
*HdifferentialCorrection = -I_1x1;
}

return Vector1(error);
}

} // namespace gtsam
198 changes: 198 additions & 0 deletions gtsam/navigation/PseudorangeFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down Expand Up @@ -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
Copy link

Copilot AI Mar 4, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

PseudorangeFactorArm() only initializes bL_; the inherited PseudorangeBase members (pseudorange_, satPos_, satClkBias_) remain uninitialized. Since print()/equals() access these members (and the tests construct a default factor and call print()/equals()), this is undefined behavior. Initialize the PseudorangeBase subobject in the default constructor (or add default member initializers in PseudorangeBase) so default-constructed factors are safe for these operations.

Copilot uses AI. Check for mistakes.

/**
* 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)));
}

/// print
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) {}
Copy link

Copilot AI Mar 4, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

DifferentialPseudorangeFactorArm() only initializes bL_; the inherited PseudorangeBase members (pseudorange_, satPos_, satClkBias_) remain uninitialized. Because print()/equals() read these fields (and the tests default-construct this factor and call those methods), this is undefined behavior. Initialize the PseudorangeBase subobject (or provide default member initializers) in the default constructor.

Suggested change
DifferentialPseudorangeFactorArm() : bL_(0, 0, 0) {}
DifferentialPseudorangeFactorArm()
: PseudorangeBase{0.0, Point3(0, 0, 0), 0.0}, bL_(0, 0, 0) {}

Copilot uses AI. Check for mistakes.

virtual ~DifferentialPseudorangeFactorArm() = default;

/**
* Construct a DifferentialPseudorangeFactorArm.
*
* @param nTbKey Receiver gtsam::Pose3 key (body pose in navigation frame).
* @param receiverClockBiasKey Receiver clock bias node.
* @param differentialCorrectionKey Differential correction 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.
*/
DifferentialPseudorangeFactorArm(
Key nTbKey, Key receiverClockBiasKey, Key differentialCorrectionKey,
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)));
}

/// print
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,
const double& differentialCorrection,
OptionalMatrixType H_nTb,
OptionalMatrixType HreceiverClockBias,
OptionalMatrixType HdifferentialCorrection) 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(
DifferentialPseudorangeFactorArm::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<DifferentialPseudorangeFactorArm>
: public Testable<DifferentialPseudorangeFactorArm> {};

} // namespace gtsam
Loading