wrap barometric factor
parent
f724f30388
commit
26f57ce3b2
|
|
@ -56,6 +56,8 @@ namespace std { template<> struct is_trivially_move_constructible<boost::seriali
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// Only for old boost
|
||||||
|
#if BOOST_VERSION < 108000
|
||||||
// function specializations must be defined in the appropriate
|
// function specializations must be defined in the appropriate
|
||||||
// namespace - boost::serialization
|
// namespace - boost::serialization
|
||||||
namespace boost {
|
namespace boost {
|
||||||
|
|
@ -99,3 +101,4 @@ void serialize(Archive& ar, std::optional<T>& t, const unsigned int version) {
|
||||||
} // namespace serialization
|
} // namespace serialization
|
||||||
} // namespace boost
|
} // namespace boost
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
|
|
|
||||||
|
|
@ -91,7 +91,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
|
||||||
-0.00649;
|
-0.00649;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline double baroOut(const double& meters) {
|
inline double baroOut(const double& meters) const {
|
||||||
double temp = 15.04 - 0.00649 * meters;
|
double temp = 15.04 - 0.00649 * meters;
|
||||||
return 101.29 * std::pow(((temp + 273.1) / 288.08), 5.256);
|
return 101.29 * std::pow(((temp + 273.1) / 288.08), 5.256);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -294,7 +294,7 @@ virtual class GPSFactor : gtsam::NonlinearFactor{
|
||||||
// Testable
|
// Testable
|
||||||
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::GPSFactor& expected, double tol);
|
bool equals(const gtsam::NonlinearFactor& expected, double tol);
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
gtsam::Point3 measurementIn() const;
|
gtsam::Point3 measurementIn() const;
|
||||||
|
|
@ -307,12 +307,29 @@ virtual class GPSFactor2 : gtsam::NonlinearFactor {
|
||||||
// Testable
|
// Testable
|
||||||
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::GPSFactor2& expected, double tol);
|
bool equals(const gtsam::NonlinearFactor& expected, double tol);
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
gtsam::Point3 measurementIn() const;
|
gtsam::Point3 measurementIn() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/navigation/BarometricFactor.h>
|
||||||
|
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 <gtsam/navigation/Scenario.h>
|
#include <gtsam/navigation/Scenario.h>
|
||||||
virtual class Scenario {
|
virtual class Scenario {
|
||||||
gtsam::Pose3 pose(double t) const;
|
gtsam::Pose3 pose(double t) const;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue