12 #include <gtsam_unstable/dllexport.h> 39 using Base::evaluateError;
58 inline double measured()
const {
return measured_; }
68 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 70 friend class boost::serialization::access;
71 template<
class ARCHIVE>
72 void serialize(ARCHIVE & ar,
const unsigned int ) {
74 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
75 boost::serialization::base_object<Base>(*
this));
76 ar & BOOST_SERIALIZATION_NVP(measured_);
void print(const Matrix &A, const string &s, ostream &stream)
RelativeElevationFactor This
RelativeElevationFactor()
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
NoiseModelFactorN< Pose3, Point3 > Base
static const KeyFormatter DefaultKeyFormatter
const gtsam::Key pointKey
Matrix * OptionalMatrixType
~RelativeElevationFactor() override
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
gtsam::NonlinearFactor::shared_ptr clone() const override
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel