Skip to content
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

C++11 Absolute Value #115

Merged
merged 1 commit into from
Sep 19, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion gtsam/base/Matrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ bool equal_with_abs_tol(const Eigen::DenseBase<MATRIX>& A, const Eigen::DenseBas
for(size_t j=0; j<n1; j++) {
if(boost::math::isnan(A(i,j)) ^ boost::math::isnan(B(i,j)))
return false;
else if(fabs(A(i,j) - B(i,j)) > tol)
else if(std::abs(A(i,j) - B(i,j)) > tol)
return false;
}
return true;
Expand Down
10 changes: 5 additions & 5 deletions gtsam/base/Vector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ bool equal_with_abs_tol(const Vector& vec1, const Vector& vec2, double tol) {
for(size_t i=0; i<m; ++i) {
if(std::isnan(vec1[i]) ^ std::isnan(vec2[i]))
return false;
if(fabs(vec1[i] - vec2[i]) > tol)
if(std::abs(vec1[i] - vec2[i]) > tol)
return false;
}
return true;
Expand All @@ -97,7 +97,7 @@ bool equal_with_abs_tol(const SubVector& vec1, const SubVector& vec2, double tol
for(size_t i=0; i<m; ++i) {
if(std::isnan(vec1[i]) ^ std::isnan(vec2[i]))
return false;
if(fabs(vec1[i] - vec2[i]) > tol)
if(std::abs(vec1[i] - vec2[i]) > tol)
return false;
}
return true;
Expand Down Expand Up @@ -145,14 +145,14 @@ bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol) {
bool flag = false; double scale = 1.0;
size_t m = vec1.size();
for(size_t i=0; i<m; i++) {
if((fabs(vec1[i])>tol&&fabs(vec2[i])<tol) || (fabs(vec1[i])<tol&&fabs(vec2[i])>tol))
if((std::abs(vec1[i])>tol && std::abs(vec2[i])<tol) || (std::abs(vec1[i])<tol && std::abs(vec2[i])>tol))
return false;
if(vec1[i] == 0 && vec2[i] == 0) continue;
if (!flag) {
scale = vec1[i] / vec2[i];
flag = true ;
}
else if (fabs(vec1[i] - vec2[i]*scale) > tol) return false;
else if (std::abs(vec1[i] - vec2[i]*scale) > tol) return false;
}
return flag;
}
Expand Down Expand Up @@ -213,7 +213,7 @@ double weightedPseudoinverse(const Vector& a, const Vector& weights,

// Check once for zero entries of a. TODO: really needed ?
vector<bool> isZero;
for (size_t i = 0; i < m; ++i) isZero.push_back(fabs(a[i]) < 1e-9);
for (size_t i = 0; i < m; ++i) isZero.push_back(std::abs(a[i]) < 1e-9);

// If there is a valid (a!=0) constraint (sigma==0) return the first one
for (size_t i = 0; i < m; ++i) {
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/deprecated/LieScalar.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ namespace gtsam {
std::cout << name << ": " << d_ << std::endl;
}
bool equals(const LieScalar& expected, double tol = 1e-5) const {
return fabs(expected.d_ - d_) <= tol;
return std::abs(expected.d_ - d_) <= tol;
}
/// @}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/tests/testVector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ TEST(Vector, weightedPseudoinverse )

// verify
EXPECT(assert_equal(expected,actual));
EXPECT(fabs(expPrecision-precision) < 1e-5);
EXPECT(std::abs(expPrecision-precision) < 1e-5);
}

/* ************************************************************************* */
Expand Down
2 changes: 1 addition & 1 deletion gtsam/discrete/DecisionTree-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ namespace gtsam {
bool equals(const Node& q, double tol) const {
const Leaf* other = dynamic_cast<const Leaf*> (&q);
if (!other) return false;
return fabs(double(this->constant_ - other->constant_)) < tol;
return std::abs(double(this->constant_ - other->constant_)) < tol;
}

/** print */
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/Cal3Bundler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,9 @@ void Cal3Bundler::print(const std::string& s) const {

/* ************************************************************************* */
bool Cal3Bundler::equals(const Cal3Bundler& K, double tol) const {
if (fabs(f_ - K.f_) > tol || fabs(k1_ - K.k1_) > tol
|| fabs(k2_ - K.k2_) > tol || fabs(u0_ - K.u0_) > tol
|| fabs(v0_ - K.v0_) > tol)
if (std::abs(f_ - K.f_) > tol || std::abs(k1_ - K.k1_) > tol
|| std::abs(k2_ - K.k2_) > tol || std::abs(u0_ - K.u0_) > tol
|| std::abs(v0_ - K.v0_) > tol)
return false;
return true;
}
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/Cal3DS2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@ void Cal3DS2::print(const std::string& s_) const {

/* ************************************************************************* */
bool Cal3DS2::equals(const Cal3DS2& K, double tol) const {
if (fabs(fx_ - K.fx_) > tol || fabs(fy_ - K.fy_) > tol || fabs(s_ - K.s_) > tol ||
fabs(u0_ - K.u0_) > tol || fabs(v0_ - K.v0_) > tol || fabs(k1_ - K.k1_) > tol ||
fabs(k2_ - K.k2_) > tol || fabs(p1_ - K.p1_) > tol || fabs(p2_ - K.p2_) > tol)
if (std::abs(fx_ - K.fx_) > tol || std::abs(fy_ - K.fy_) > tol || std::abs(s_ - K.s_) > tol ||
std::abs(u0_ - K.u0_) > tol || std::abs(v0_ - K.v0_) > tol || std::abs(k1_ - K.k1_) > tol ||
std::abs(k2_ - K.k2_) > tol || std::abs(p1_ - K.p1_) > tol || std::abs(p2_ - K.p2_) > tol)
return false;
return true;
}
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/Cal3DS2_Base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@ void Cal3DS2_Base::print(const std::string& s_) const {

/* ************************************************************************* */
bool Cal3DS2_Base::equals(const Cal3DS2_Base& K, double tol) const {
if (fabs(fx_ - K.fx_) > tol || fabs(fy_ - K.fy_) > tol || fabs(s_ - K.s_) > tol ||
fabs(u0_ - K.u0_) > tol || fabs(v0_ - K.v0_) > tol || fabs(k1_ - K.k1_) > tol ||
fabs(k2_ - K.k2_) > tol || fabs(p1_ - K.p1_) > tol || fabs(p2_ - K.p2_) > tol)
if (std::abs(fx_ - K.fx_) > tol || std::abs(fy_ - K.fy_) > tol || std::abs(s_ - K.s_) > tol ||
std::abs(u0_ - K.u0_) > tol || std::abs(v0_ - K.v0_) > tol || std::abs(k1_ - K.k1_) > tol ||
std::abs(k2_ - K.k2_) > tol || std::abs(p1_ - K.p1_) > tol || std::abs(p2_ - K.p2_) > tol)
return false;
return true;
}
Expand Down
8 changes: 4 additions & 4 deletions gtsam/geometry/Cal3Unified.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,10 @@ void Cal3Unified::print(const std::string& s) const {

/* ************************************************************************* */
bool Cal3Unified::equals(const Cal3Unified& K, double tol) const {
if (fabs(fx_ - K.fx_) > tol || fabs(fy_ - K.fy_) > tol || fabs(s_ - K.s_) > tol ||
fabs(u0_ - K.u0_) > tol || fabs(v0_ - K.v0_) > tol || fabs(k1_ - K.k1_) > tol ||
fabs(k2_ - K.k2_) > tol || fabs(p1_ - K.p1_) > tol || fabs(p2_ - K.p2_) > tol ||
fabs(xi_ - K.xi_) > tol)
if (std::abs(fx_ - K.fx_) > tol || std::abs(fy_ - K.fy_) > tol || std::abs(s_ - K.s_) > tol ||
std::abs(u0_ - K.u0_) > tol || std::abs(v0_ - K.v0_) > tol || std::abs(k1_ - K.k1_) > tol ||
std::abs(k2_ - K.k2_) > tol || std::abs(p1_ - K.p1_) > tol || std::abs(p2_ - K.p2_) > tol ||
std::abs(xi_ - K.xi_) > tol)
return false;
return true;
}
Expand Down
10 changes: 5 additions & 5 deletions gtsam/geometry/Cal3_S2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,15 +64,15 @@ void Cal3_S2::print(const std::string& s) const {

/* ************************************************************************* */
bool Cal3_S2::equals(const Cal3_S2& K, double tol) const {
if (fabs(fx_ - K.fx_) > tol)
if (std::abs(fx_ - K.fx_) > tol)
return false;
if (fabs(fy_ - K.fy_) > tol)
if (std::abs(fy_ - K.fy_) > tol)
return false;
if (fabs(s_ - K.s_) > tol)
if (std::abs(s_ - K.s_) > tol)
return false;
if (fabs(u0_ - K.u0_) > tol)
if (std::abs(u0_ - K.u0_) > tol)
return false;
if (fabs(v0_ - K.v0_) > tol)
if (std::abs(v0_ - K.v0_) > tol)
return false;
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3_S2Stereo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ void Cal3_S2Stereo::print(const std::string& s) const {

/* ************************************************************************* */
bool Cal3_S2Stereo::equals(const Cal3_S2Stereo& other, double tol) const {
if (fabs(b_ - other.b_) > tol) return false;
if (std::abs(b_ - other.b_) > tol) return false;
return K_.equals(other.K_,tol);
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/OrientedPlane3.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class GTSAM_EXPORT OrientedPlane3 {

/// The equals function with tolerance
bool equals(const OrientedPlane3& s, double tol = 1e-9) const {
return (n_.equals(s.n_, tol) && (fabs(d_ - s.d_) < tol));
return (n_.equals(s.n_, tol) && (std::abs(d_ - s.d_) < tol));
}

/// @}
Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/Point2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace gtsam {
double norm2(const Point2& p, OptionalJacobian<1,2> H) {
double r = std::sqrt(p.x() * p.x() + p.y() * p.y());
if (H) {
if (fabs(r) > 1e-10)
if (std::abs(r) > 1e-10)
*H << p.x() / r, p.y() / r;
else
*H << 1, 1; // really infinity, why 1 ?
Expand Down Expand Up @@ -59,7 +59,7 @@ void Point2::print(const string& s) const {

/* ************************************************************************* */
bool Point2::equals(const Point2& q, double tol) const {
return (fabs(x() - q.x()) < tol && fabs(y() - q.y()) < tol);
return (std::abs(x() - q.x()) < tol && std::abs(y() - q.y()) < tol);
}

/* ************************************************************************* */
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/Point3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ namespace gtsam {

#ifndef GTSAM_TYPEDEF_POINTS_TO_VECTORS
bool Point3::equals(const Point3 &q, double tol) const {
return (fabs(x() - q.x()) < tol && fabs(y() - q.y()) < tol &&
fabs(z() - q.z()) < tol);
return (std::abs(x() - q.x()) < tol && std::abs(y() - q.y()) < tol &&
std::abs(z() - q.z()) < tol);
}

void Point3::print(const string& s) const {
Expand Down Expand Up @@ -98,7 +98,7 @@ double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian<1, 3> H1,
double norm3(const Point3 &p, OptionalJacobian<1, 3> H) {
double r = sqrt(p.x() * p.x() + p.y() * p.y() + p.z() * p.z());
if (H) {
if (fabs(r) > 1e-10)
if (std::abs(r) > 1e-10)
*H << p.x() / r, p.y() / r, p.z() / r;
else
*H << 1, 1, 1; // really infinity, why 1 ?
Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/Pose2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ Matrix3 Pose2::adjointMap(const Vector3& v) {
Matrix3 Pose2::ExpmapDerivative(const Vector3& v) {
double alpha = v[2];
Matrix3 J;
if (fabs(alpha) > 1e-5) {
if (std::abs(alpha) > 1e-5) {
// Chirikjian11book2, pg. 36
/* !!!Warning!!! Compare Iserles05an, formula 2.42 and Chirikjian11book2 pg.26
* Iserles' right-trivialization dexpR is actually the left Jacobian J_l in Chirikjian's notation
Expand Down Expand Up @@ -174,7 +174,7 @@ Matrix3 Pose2::LogmapDerivative(const Pose2& p) {
Vector3 v = Logmap(p);
double alpha = v[2];
Matrix3 J;
if (fabs(alpha) > 1e-5) {
if (std::abs(alpha) > 1e-5) {
double alphaInv = 1/alpha;
double halfCotHalfAlpha = 0.5*sin(alpha)/(1-cos(alpha));
double v1 = v[0], v2 = v[1];
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Pose3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ static Matrix3 computeQforExpmapDerivative(const Vector6& xi) {
#else
// The closed-form formula in Barfoot14tro eq. (102)
double phi = w.norm();
if (fabs(phi)>1e-5) {
if (std::abs(phi)>1e-5) {
const double sinPhi = sin(phi), cosPhi = cos(phi);
const double phi2 = phi * phi, phi3 = phi2 * phi, phi4 = phi3 * phi, phi5 = phi4 * phi;
// Invert the sign of odd-order terms to have the right Jacobian
Expand Down
8 changes: 4 additions & 4 deletions gtsam/geometry/Rot2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace gtsam {

/* ************************************************************************* */
Rot2 Rot2::fromCosSin(double c, double s) {
if (fabs(c * c + s * s - 1.0) > 1e-9) {
if (std::abs(c * c + s * s - 1.0) > 1e-9) {
double norm_cs = sqrt(c*c + s*s);
c = c/norm_cs;
s = s/norm_cs;
Expand All @@ -46,13 +46,13 @@ void Rot2::print(const string& s) const {

/* ************************************************************************* */
bool Rot2::equals(const Rot2& R, double tol) const {
return fabs(c_ - R.c_) <= tol && fabs(s_ - R.s_) <= tol;
return std::abs(c_ - R.c_) <= tol && std::abs(s_ - R.s_) <= tol;
}

/* ************************************************************************* */
Rot2& Rot2::normalize() {
double scale = c_*c_ + s_*s_;
if(fabs(scale-1.0)>1e-10) {
if(std::abs(scale-1.0)>1e-10) {
scale = pow(scale, -0.5);
c_ *= scale;
s_ *= scale;
Expand Down Expand Up @@ -115,7 +115,7 @@ Point2 Rot2::unrotate(const Point2& p,
/* ************************************************************************* */
Rot2 Rot2::relativeBearing(const Point2& d, OptionalJacobian<1, 2> H) {
double x = d.x(), y = d.y(), d2 = x * x + y * y, n = sqrt(d2);
if(fabs(n) > 1e-5) {
if(std::abs(n) > 1e-5) {
if (H) {
*H << -y / d2, x / d2;
}
Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/StereoPoint2.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,8 @@ class GTSAM_EXPORT StereoPoint2 {

/** equals */
bool equals(const StereoPoint2& q, double tol = 1e-9) const {
return (fabs(uL_ - q.uL_) < tol && fabs(uR_ - q.uR_) < tol
&& fabs(v_ - q.v_) < tol);
return (std::abs(uL_ - q.uL_) < tol && std::abs(uR_ - q.uR_) < tol
&& std::abs(v_ - q.v_) < tol);
}

/// @}
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Unit3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ Unit3 Unit3::Random(boost::mt19937 & rng) {
/* ************************************************************************* */
// Get the axis of rotation with the minimum projected length of the point
static Point3 CalculateBestAxis(const Point3& n) {
double mx = fabs(n.x()), my = fabs(n.y()), mz = fabs(n.z());
double mx = std::abs(n.x()), my = std::abs(n.y()), mz = std::abs(n.z());
if ((mx <= my) && (mx <= mz)) {
return Point3(1.0, 0.0, 0.0);
} else if ((my <= mx) && (my <= mz)) {
Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/tests/testEssentialMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,10 +218,10 @@ TEST (EssentialMatrix, epipoles) {
}

// check rank 2 constraint
CHECK(fabs(S(2))<1e-10);
CHECK(std::abs(S(2))<1e-10);

// check epipoles not at infinity
CHECK(fabs(U(2,2))>1e-10 && fabs(V(2,2))>1e-10);
CHECK(std::abs(U(2,2))>1e-10 && std::abs(V(2,2))>1e-10);

// Check epipoles

Expand Down
6 changes: 3 additions & 3 deletions gtsam/linear/NoiseModel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -847,7 +847,7 @@ void GemanMcClure::print(const std::string &s="") const {
bool GemanMcClure::equals(const Base &expected, double tol) const {
const GemanMcClure* p = dynamic_cast<const GemanMcClure*>(&expected);
if (p == NULL) return false;
return fabs(c_ - p->c_) < tol;
return std::abs(c_ - p->c_) < tol;
}

GemanMcClure::shared_ptr GemanMcClure::Create(double c, const ReweightScheme reweight) {
Expand Down Expand Up @@ -879,7 +879,7 @@ void DCS::print(const std::string &s="") const {
bool DCS::equals(const Base &expected, double tol) const {
const DCS* p = dynamic_cast<const DCS*>(&expected);
if (p == NULL) return false;
return fabs(c_ - p->c_) < tol;
return std::abs(c_ - p->c_) < tol;
}

DCS::shared_ptr DCS::Create(double c, const ReweightScheme reweight) {
Expand All @@ -903,7 +903,7 @@ void L2WithDeadZone::print(const std::string &s="") const {
bool L2WithDeadZone::equals(const Base &expected, double tol) const {
const L2WithDeadZone* p = dynamic_cast<const L2WithDeadZone*>(&expected);
if (p == NULL) return false;
return fabs(k_ - p->k_) < tol;
return std::abs(k_ - p->k_) < tol;
}

L2WithDeadZone::shared_ptr L2WithDeadZone::Create(double k, const ReweightScheme reweight) {
Expand Down
8 changes: 4 additions & 4 deletions gtsam/linear/NoiseModel.h
Original file line number Diff line number Diff line change
Expand Up @@ -750,7 +750,7 @@ namespace gtsam {

Fair(double c = 1.3998, const ReweightScheme reweight = Block);
double weight(double error) const {
return 1.0 / (1.0 + fabs(error) / c_);
return 1.0 / (1.0 + std::abs(error) / c_);
}
void print(const std::string &s) const;
bool equals(const Base& expected, double tol=1e-8) const;
Expand Down Expand Up @@ -832,7 +832,7 @@ namespace gtsam {

Tukey(double c = 4.6851, const ReweightScheme reweight = Block);
double weight(double error) const {
if (std::fabs(error) <= c_) {
if (std::abs(error) <= c_) {
double xc2 = error*error/csquared_;
return (1.0-xc2)*(1.0-xc2);
}
Expand Down Expand Up @@ -952,14 +952,14 @@ namespace gtsam {

L2WithDeadZone(double k, const ReweightScheme reweight = Block);
double residual(double error) const {
const double abs_error = fabs(error);
const double abs_error = std::abs(error);
return (abs_error < k_) ? 0.0 : 0.5*(k_-abs_error)*(k_-abs_error);
}
double weight(double error) const {
// note that this code is slightly uglier than above, because there are three distinct
// cases to handle (left of deadzone, deadzone, right of deadzone) instead of the two
// cases (deadzone, non-deadzone) above.
if (fabs(error) <= k_) return 0.0;
if (std::abs(error) <= k_) return 0.0;
else if (error > k_) return (-k_+error)/error;
else return (k_+error)/error;
}
Expand Down
2 changes: 1 addition & 1 deletion gtsam/navigation/ManifoldPreintegration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ void ManifoldPreintegration::resetIntegration() {
//------------------------------------------------------------------------------
bool ManifoldPreintegration::equals(const ManifoldPreintegration& other,
double tol) const {
return p_->equals(*other.p_, tol) && fabs(deltaTij_ - other.deltaTij_) < tol
return p_->equals(*other.p_, tol) && std::abs(deltaTij_ - other.deltaTij_) < tol
&& biasHat_.equals(other.biasHat_, tol)
&& deltaXij_.equals(other.deltaXij_, tol)
&& equal_with_abs_tol(delRdelBiasOmega_, other.delRdelBiasOmega_, tol)
Expand Down
2 changes: 1 addition & 1 deletion gtsam/navigation/PreintegratedRotation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ bool PreintegratedRotation::equals(const PreintegratedRotation& other,
double tol) const {
return this->matchesParamsWith(other)
&& deltaRij_.equals(other.deltaRij_, tol)
&& fabs(deltaTij_ - other.deltaTij_) < tol
&& std::abs(deltaTij_ - other.deltaTij_) < tol
&& equal_with_abs_tol(delRdelBiasOmega_, other.delRdelBiasOmega_, tol);
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/navigation/TangentPreintegration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ void TangentPreintegration::resetIntegration() {
//------------------------------------------------------------------------------
bool TangentPreintegration::equals(const TangentPreintegration& other,
double tol) const {
return p_->equals(*other.p_, tol) && fabs(deltaTij_ - other.deltaTij_) < tol
return p_->equals(*other.p_, tol) && std::abs(deltaTij_ - other.deltaTij_) < tol
&& biasHat_.equals(other.biasHat_, tol)
&& equal_with_abs_tol(preintegrated_, other.preintegrated_, tol)
&& equal_with_abs_tol(preintegrated_H_biasAcc_,
Expand Down
Loading