46 using Base::evaluateError;
67 Base(model, key), nT_(gpsIn) {
71 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
73 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
78 DefaultKeyFormatter)
const override;
86 inline const Point3 & measurementIn()
const {
95 static std::pair<Pose3, Vector3> EstimateState(
double t1,
const Point3& NED1,
96 double t2,
const Point3& NED2,
double timestamp);
100 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 101 friend class boost::serialization::access; 103 template<
class ARCHIVE>
104 void serialize(ARCHIVE & ar,
const unsigned int ) {
107 & boost::serialization::make_nvp(
"NoiseModelFactor1",
108 boost::serialization::base_object<Base>(*
this));
109 ar & BOOST_SERIALIZATION_NVP(nT_);
129 using Base::evaluateError;
144 Base(model, key), nT_(gpsIn) {
148 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
150 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
155 DefaultKeyFormatter)
const override;
163 inline const Point3 & measurementIn()
const {
169 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 170 friend class boost::serialization::access;
172 template<
class ARCHIVE>
173 void serialize(ARCHIVE & ar,
const unsigned int ) {
176 & boost::serialization::make_nvp(
"NoiseModelFactor1",
177 boost::serialization::base_object<Base>(*
this));
178 ar & BOOST_SERIALIZATION_NVP(nT_);
Definition: NavState.h:34
GPSFactor2()
default constructor - only use for serialization
Definition: GPSFactor.h:138
Definition: NonlinearFactor.h:431
GPSFactor(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
Constructor from a measurement in a Cartesian frame. Use GeographicLib to convert from geographic (la...
Definition: GPSFactor.h:66
GPSFactor()
Definition: GPSFactor.h:55
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
GPSFactor This
Typedef to this class.
Definition: GPSFactor.h:52
Definition: NonlinearFactor.h:68
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:148
Definition: Testable.h:112
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
std::shared_ptr< GPSFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:49
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
Navigation state composing of attitude, position, and velocity.
GPSFactor2 This
Typedef to this class.
Definition: GPSFactor.h:135
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
std::shared_ptr< GPSFactor2 > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:132
Definition: chartTesting.h:28
Definition: GPSFactor.h:118
Non-linear factor base classes.
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:71
Vector3 Point3
Definition: Point3.h:38
GPSFactor2(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
Constructor from a measurement in a Cartesian frame.
Definition: GPSFactor.h:143
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Definition: GPSFactor.h:35
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741