Go to the documentation of this file.
   62       std::cout << 
s << 
"BiasedGPSFactor(" 
   63           << keyFormatter(this->key<1>()) << 
"," 
   64           << keyFormatter(this->key<2>()) << 
")\n" 
   65           << 
"  measured: " << 
measured_.transpose() << std::endl;
 
   83         (*H1) << Z_3x3,  
pose.rotation().matrix();
 
   97 #if 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));
 
  
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
const Point3 measured() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
const Vector3 bias(1, 2, 3)
std::shared_ptr< BiasedGPSFactor > shared_ptr
SharedNoiseModel noiseModel_
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Vector evaluateError(const Pose3 &pose, const Point3 &bias, OptionalMatrixType H1, OptionalMatrixType H2) const override
~BiasedGPSFactor() override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
noiseModel::Base::shared_ptr SharedNoiseModel
noiseModel::Diagonal::shared_ptr model
Non-linear factor base classes.
Matrix * OptionalMatrixType
NoiseModelFactorN< Pose3, Point3 > Base
std::uint64_t Key
Integer nonlinear key type.
3D Pose manifold SO(3) x R^3 and group SE(3)
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
BiasedGPSFactor(Key posekey, Key biaskey, const Point3 measured, const SharedNoiseModel &model)
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:00:55