53 Base(model, posekey, biaskey), measured_(measured) {
62 std::cout << s <<
"BiasedGPSFactor(" 63 << keyFormatter(this->key<1>()) <<
"," 64 << keyFormatter(this->key<2>()) <<
")\n" 65 <<
" measured: " << measured_.transpose() << std::endl;
71 const This *
e =
dynamic_cast<const This*
> (&
expected);
97 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 99 friend class boost::serialization::access;
100 template<
class ARCHIVE>
101 void serialize(ARCHIVE & ar,
const unsigned int ) {
103 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
104 boost::serialization::base_object<Base>(*
this));
105 ar & BOOST_SERIALIZATION_NVP(measured_);
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
std::shared_ptr< BiasedGPSFactor > shared_ptr
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
const Point3 measured() const
NoiseModelFactorN< Pose3, Point3 > Base
BiasedGPSFactor(Key posekey, Key biaskey, const Point3 measured, const SharedNoiseModel &model)
static const KeyFormatter DefaultKeyFormatter
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Matrix * OptionalMatrixType
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector evaluateError(const Pose3 &pose, const Point3 &bias, OptionalMatrixType H1, OptionalMatrixType H2) const override
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
SharedNoiseModel noiseModel_
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
std::uint64_t Key
Integer nonlinear key type.
~BiasedGPSFactor() override
noiseModel::Base::shared_ptr SharedNoiseModel