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