Skip to content

Commit 0149005

Browse files
authored
Merge pull request #1723 from borglab/wrap-barometricfactor
2 parents 5b96684 + d947ffb commit 0149005

File tree

4 files changed

+37
-7
lines changed

4 files changed

+37
-7
lines changed

.github/workflows/build-python.yml

+9-3
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ jobs:
2929
name:
3030
[
3131
ubuntu-20.04-gcc-9,
32-
ubuntu-22.04-gcc-9-tbb,
32+
ubuntu-20.04-gcc-9-tbb,
3333
ubuntu-20.04-clang-9,
3434
macOS-11-xcode-13.4.1,
3535
windows-2019-msbuild,
@@ -43,8 +43,8 @@ jobs:
4343
compiler: gcc
4444
version: "9"
4545

46-
- name: ubuntu-22.04-gcc-9-tbb
47-
os: ubuntu-22.04
46+
- name: ubuntu-20.04-gcc-9-tbb
47+
os: ubuntu-20.04
4848
compiler: gcc
4949
version: "9"
5050
flag: tbb
@@ -145,6 +145,12 @@ jobs:
145145
echo "GTSAM_WITH_TBB=ON" >> $GITHUB_ENV
146146
echo "GTSAM Uses TBB"
147147
148+
- name: Set Swap Space (Linux)
149+
if: runner.os == 'Linux'
150+
uses: pierotofy/set-swap-space@master
151+
with:
152+
swap-size-gb: 6
153+
148154
- name: Install System Dependencies (Linux, macOS)
149155
if: runner.os != 'Windows'
150156
run: |

gtsam/base/std_optional_serialization.h

+8-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,14 @@ namespace std { template<> struct is_trivially_move_constructible<boost::seriali
5757
#endif
5858
#endif
5959

60-
60+
/*
61+
* PR https://github.com/boostorg/serialization/pull/163 was merged
62+
* on September 3rd 2023,
63+
* and so the below code is now a part of Boost 1.84.
64+
* We include it for posterity, hence the check for BOOST_VERSION being less
65+
* than 1.84.
66+
*/
67+
#if BOOST_VERSION < 108400
6168
// function specializations must be defined in the appropriate
6269
// namespace - boost::serialization
6370
namespace boost {

gtsam/navigation/BarometricFactor.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
9191
-0.00649;
9292
}
9393

94-
inline double baroOut(const double& meters) {
94+
inline double baroOut(const double& meters) const {
9595
double temp = 15.04 - 0.00649 * meters;
9696
return 101.29 * std::pow(((temp + 273.1) / 288.08), 5.256);
9797
}

gtsam/navigation/navigation.i

+19-2
Original file line numberDiff line numberDiff line change
@@ -294,7 +294,7 @@ virtual class GPSFactor : gtsam::NonlinearFactor{
294294
// Testable
295295
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
296296
gtsam::DefaultKeyFormatter) const;
297-
bool equals(const gtsam::GPSFactor& expected, double tol);
297+
bool equals(const gtsam::NonlinearFactor& expected, double tol);
298298

299299
// Standard Interface
300300
gtsam::Point3 measurementIn() const;
@@ -307,12 +307,29 @@ virtual class GPSFactor2 : gtsam::NonlinearFactor {
307307
// Testable
308308
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
309309
gtsam::DefaultKeyFormatter) const;
310-
bool equals(const gtsam::GPSFactor2& expected, double tol);
310+
bool equals(const gtsam::NonlinearFactor& expected, double tol);
311311

312312
// Standard Interface
313313
gtsam::Point3 measurementIn() const;
314314
};
315315

316+
#include <gtsam/navigation/BarometricFactor.h>
317+
virtual class BarometricFactor : gtsam::NonlinearFactor {
318+
BarometricFactor();
319+
BarometricFactor(size_t key, size_t baroKey, const double& baroIn,
320+
const gtsam::noiseModel::Base* model);
321+
322+
// Testable
323+
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
324+
gtsam::DefaultKeyFormatter) const;
325+
bool equals(const gtsam::NonlinearFactor& expected, double tol);
326+
327+
// Standard Interface
328+
const double& measurementIn() const;
329+
double heightOut(double n) const;
330+
double baroOut(const double& meters) const;
331+
};
332+
316333
#include <gtsam/navigation/Scenario.h>
317334
virtual class Scenario {
318335
gtsam::Pose3 pose(double t) const;

0 commit comments

Comments
 (0)