Merge pull request #1723 from borglab/wrap-barometricfactor

release/4.3a0
Varun Agrawal 2024-02-28 10:37:21 -05:00 committed by GitHub
commit 01490055ff
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
4 changed files with 37 additions and 7 deletions

View File

@ -29,7 +29,7 @@ jobs:
name:
[
ubuntu-20.04-gcc-9,
ubuntu-22.04-gcc-9-tbb,
ubuntu-20.04-gcc-9-tbb,
ubuntu-20.04-clang-9,
macOS-11-xcode-13.4.1,
windows-2019-msbuild,
@ -43,8 +43,8 @@ jobs:
compiler: gcc
version: "9"
- name: ubuntu-22.04-gcc-9-tbb
os: ubuntu-22.04
- name: ubuntu-20.04-gcc-9-tbb
os: ubuntu-20.04
compiler: gcc
version: "9"
flag: tbb
@ -145,6 +145,12 @@ jobs:
echo "GTSAM_WITH_TBB=ON" >> $GITHUB_ENV
echo "GTSAM Uses TBB"
- name: Set Swap Space (Linux)
if: runner.os == 'Linux'
uses: pierotofy/set-swap-space@master
with:
swap-size-gb: 6
- name: Install System Dependencies (Linux, macOS)
if: runner.os != 'Windows'
run: |

View File

@ -57,7 +57,14 @@ namespace std { template<> struct is_trivially_move_constructible<boost::seriali
#endif
#endif
/*
* PR https://github.com/boostorg/serialization/pull/163 was merged
* on September 3rd 2023,
* and so the below code is now a part of Boost 1.84.
* We include it for posterity, hence the check for BOOST_VERSION being less
* than 1.84.
*/
#if BOOST_VERSION < 108400
// function specializations must be defined in the appropriate
// namespace - boost::serialization
namespace boost {

View File

@ -91,7 +91,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
-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);
}

View File

@ -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 <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>
virtual class Scenario {
gtsam::Pose3 pose(double t) const;