update GPSFactor interface

release/4.3a0
morten 2025-01-14 12:09:27 +01:00
parent 57b8f6b158
commit 7efcb468f5
1 changed files with 6 additions and 2 deletions

View File

@ -329,7 +329,8 @@ virtual class Pose3AttitudeFactor : gtsam::NoiseModelFactor {
#include <gtsam/navigation/GPSFactor.h>
virtual class GPSFactor : gtsam::NonlinearFactor{
GPSFactor(size_t key, const gtsam::Point3& gpsIn,
const gtsam::noiseModel::Base* model);
const gtsam::noiseModel::Base* model,
const gtsam::Point3& leverArm);
// Testable
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
@ -338,6 +339,7 @@ virtual class GPSFactor : gtsam::NonlinearFactor{
// Standard Interface
gtsam::Point3 measurementIn() const;
gtsam::Point3 leverArm() const;
// enable serialization functionality
void serialize() const;
@ -345,7 +347,8 @@ virtual class GPSFactor : gtsam::NonlinearFactor{
virtual class GPSFactor2 : gtsam::NonlinearFactor {
GPSFactor2(size_t key, const gtsam::Point3& gpsIn,
const gtsam::noiseModel::Base* model);
const gtsam::noiseModel::Base* model,
const gtsam::Point3& leverArm);
// Testable
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
@ -354,6 +357,7 @@ virtual class GPSFactor2 : gtsam::NonlinearFactor {
// Standard Interface
gtsam::Point3 measurementIn() const;
gtsam::Point3 leverArm() const;
// enable serialization functionality
void serialize() const;