diff --git a/gtsam/base/std_optional_serialization.h b/gtsam/base/std_optional_serialization.h index 5c250eab4..ac0c16c87 100644 --- a/gtsam/base/std_optional_serialization.h +++ b/gtsam/base/std_optional_serialization.h @@ -56,6 +56,8 @@ namespace std { template<> struct is_trivially_move_constructible& t, const unsigned int version) { } // namespace serialization } // namespace boost #endif +#endif diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index 38677ed58..70cae8d36 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -91,7 +91,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { -0.00649; } - inline double baroOut(const double& meters) { + inline double baroOut(const double& meters) const { double temp = 15.04 - 0.00649 * meters; return 101.29 * std::pow(((temp + 273.1) / 288.08), 5.256); } diff --git a/gtsam/navigation/navigation.i b/gtsam/navigation/navigation.i index 8e6090e06..92864c18a 100644 --- a/gtsam/navigation/navigation.i +++ b/gtsam/navigation/navigation.i @@ -294,7 +294,7 @@ virtual class GPSFactor : gtsam::NonlinearFactor{ // Testable void print(string s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; - bool equals(const gtsam::GPSFactor& expected, double tol); + bool equals(const gtsam::NonlinearFactor& expected, double tol); // Standard Interface gtsam::Point3 measurementIn() const; @@ -307,12 +307,29 @@ virtual class GPSFactor2 : gtsam::NonlinearFactor { // Testable void print(string s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; - bool equals(const gtsam::GPSFactor2& expected, double tol); + bool equals(const gtsam::NonlinearFactor& expected, double tol); // Standard Interface gtsam::Point3 measurementIn() const; }; +#include +virtual class BarometricFactor : gtsam::NonlinearFactor { + BarometricFactor(); + BarometricFactor(size_t key, size_t baroKey, const double& baroIn, + const gtsam::noiseModel::Base* model); + + // Testable + void print(string s = "", const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol); + + // Standard Interface + const double& measurementIn() const; + double heightOut(double n) const; + double baroOut(const double& meters) const; +}; + #include virtual class Scenario { gtsam::Pose3 pose(double t) const;