15 :
Base(model, poseKey, pointKey), measured_(measured)
22 double hx = pose.
z() - point.z();
24 *H1 = Matrix::Zero(1,6);
32 *H2 = Matrix::Zero(1,3);
46 std::cout << s <<
"RelativeElevationFactor, relative elevation = " <<
measured_ << std::endl;
RelativeElevationFactor()
Point3 r1() const
first column
noiseModel::Diagonal::shared_ptr model
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
const gtsam::Key pointKey
Point3 r2() const
second column
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Matrix * OptionalMatrixType
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const 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))
Factor representing a known relative altitude in global frame.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
Point3 r3() const
third column