30 template<
class CAMERA>
64 using NoiseModelFactor1<Point3>::evaluateError;
68 throwCheirality_(false), verboseCheirality_(false) {
83 Base(model, pointKey), camera_(camera), measured_(measured), throwCheirality_(
86 throw std::invalid_argument(
87 "TriangulationFactor must be created with " 89 +
"-dimensional noise model.");
109 std::cout <<
s <<
"TriangulationFactor,";
110 camera_.print(
"camera");
117 const This *
e =
dynamic_cast<const This*
>(&
p);
129 if (verboseCheirality_)
130 std::cout << e.
what() <<
": Landmark " 133 if (throwCheirality_)
135 return camera_.defaultErrorWhenTriangulatingBehindCamera();
152 return std::shared_ptr<JacobianFactor>();
155 if (Ab.
rows() == 0) {
171 return std::make_shared<JacobianFactor>(this->
keys_,
Ab);
191 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 192 friend class boost::serialization::access; 194 template<
class ARCHIVE>
195 void serialize(ARCHIVE & ar,
const unsigned int ) {
196 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
197 ar & BOOST_SERIALIZATION_NVP(camera_);
198 ar & BOOST_SERIALIZATION_NVP(measured_);
199 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
200 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
TriangulationFactor()
Default constructor.
TriangulationFactor< CAMERA > This
shorthand for this class
Vector evaluateError(const Point3 &point, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
std::string serialize(const T &input)
serializes to a string
const Measurement measured_
2D measurement
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
DenseIndex rows() const
Row size.
TriangulationFactor(const CAMERA &camera, const Measurement &measured, const SharedNoiseModel &model, Key pointKey, bool throwCheirality=false, bool verboseCheirality=false)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
KeyVector keys_
The keys involved in this factor.
bool throwCheirality() const
static const KeyFormatter DefaultKeyFormatter
const gtsam::Key pointKey
VerticalBlockMatrix Ab
thread-safe (?) scratch memory for linearize
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
Matrix * OptionalMatrixType
GenericMeasurement< Point2, Point2 > Measurement
const bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
gtsam::NonlinearFactor::shared_ptr clone() const override
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
const CAMERA camera_
CAMERA in which this landmark was seen.
Calibrated camera for which only pose is unknown.
~TriangulationFactor() override
SharedNoiseModel noiseModel_
Non-linear factor base classes.
virtual bool active(const Values &) const
std::shared_ptr< This > shared_ptr
const Measurement & measured() const
typename CAMERA::Measurement Measurement
shorthand for measurement type, e.g. Point2 or StereoPoint2
static const CalibratedCamera camera(kDefaultPose)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
const std::vector< size_t > dimensions
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
std::uint64_t Key
Integer nonlinear key type.
bool verboseCheirality() const
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
noiseModel::Base::shared_ptr SharedNoiseModel
const bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
const char * what() const noexcept override