From 5111215600104a0fad20582419df016abb1a273e Mon Sep 17 00:00:00 2001 From: mkielo3 Date: Thu, 8 May 2025 19:57:32 -0400 Subject: [PATCH] fixed python build error --- gtsam/geometry/Event.h | 2 +- gtsam/geometry/geometry.i | 9 +++++---- gtsam_unstable/gtsam_unstable.i | 8 ++++---- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/gtsam/geometry/Event.h b/gtsam/geometry/Event.h index ebfe8cda7..1bdc39f34 100644 --- a/gtsam/geometry/Event.h +++ b/gtsam/geometry/Event.h @@ -84,7 +84,7 @@ template <> struct traits : internal::Manifold {}; /// Time of arrival to given sensor -class TimeOfArrival { +class GTSAM_EXPORT TimeOfArrival { const double speed_; ///< signal speed public: diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 9e3cf1ad1..1193087ed 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -1514,18 +1514,19 @@ gtsam::TriangulationResult triangulateSafe( const gtsam::Point2Vector& measurements, const gtsam::TriangulationParameters& params); -#include + +#include class Event { Event(); Event(double t, const gtsam::Point3& p); Event(double t, double x, double y, double z); double time() const; gtsam::Point3 location() const; - TimeOfArrival(); - TimeOfArrival(double speed); - double measure(const gtsam::Event& event, const gtsam::Point3& sensor) const; + double height() const; + void print(string s) const; }; + #include template class BearingRange { diff --git a/gtsam_unstable/gtsam_unstable.i b/gtsam_unstable/gtsam_unstable.i index faf834b07..dff099e24 100644 --- a/gtsam_unstable/gtsam_unstable.i +++ b/gtsam_unstable/gtsam_unstable.i @@ -379,11 +379,11 @@ virtual class RangeFactor : gtsam::NoiseModelFactor { typedef gtsam::RangeFactor RangeFactorRTV; - double height() const; - void print(string s) const; -}; - class TimeOfArrival { + TimeOfArrival(); + TimeOfArrival(double speed); + double measure(const gtsam::Event& event, const gtsam::Point3& sensor) const; +}; #include virtual class TOAFactor : gtsam::NonlinearFactor {