20 #include <boost/make_shared.hpp> 21 #include <boost/lexical_cast.hpp> 30 template<
class CAMERA>
64 throwCheirality_(false), verboseCheirality_(false) {
79 Base(model, pointKey), camera_(camera), measured_(measured), throwCheirality_(
82 throw std::invalid_argument(
83 "TriangulationFactor must be created with " 85 +
"-dimensional noise model.");
105 std::cout <<
s <<
"TriangulationFactor,";
106 camera_.print(
"camera");
113 const This *
e =
dynamic_cast<const This*
>(&
p);
120 boost::none)
const override {
126 if (verboseCheirality_)
127 std::cout << e.
what() <<
": Landmark " 130 if (throwCheirality_)
149 return boost::shared_ptr<JacobianFactor>();
152 if (Ab.
rows() == 0) {
168 return boost::make_shared<JacobianFactor>(this->
keys_,
Ab);
190 template<
class ARCHIVE>
192 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
193 ar & BOOST_SERIALIZATION_NVP(camera_);
194 ar & BOOST_SERIALIZATION_NVP(measured_);
195 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
196 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
TriangulationFactor< CAMERA > This
shorthand for this class
TriangulationFactor()
Default constructor.
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
const Measurement measured_
2D measurement
noiseModel::Diagonal::shared_ptr model
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
const Measurement & measured() const
KeyVector keys_
The keys involved in this factor.
vector< size_t > dimensions(L.begin(), L.end())
static const KeyFormatter DefaultKeyFormatter
const gtsam::Key pointKey
virtual bool active(const Values &) const
VerticalBlockMatrix Ab
thread-safe (?) scratch memory for linearize
bool verboseCheirality() const
const ValueType at(Key j) const
void serialize(ARCHIVE &ar, const unsigned int)
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
GenericMeasurement< Point2, Point2 > Measurement
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.
const bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
friend class boost::serialization::access
Serialization function.
gtsam::NonlinearFactor::shared_ptr clone() const override
bool throwCheirality() const
const CAMERA camera_
CAMERA in which this landmark was seen.
Calibrated camera for which only pose is unknown.
~TriangulationFactor() override
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
SharedNoiseModel noiseModel_
CAMERA::Measurement Measurement
shorthand for measurement type, e.g. Point2 or StereoPoint2
Non-linear factor base classes.
NoiseModelFactor1< Point3 > Base
shorthand for base class type
Vector evaluateError(const Point3 &point, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
The matrix class, also used for vectors and row-vectors.
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
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
CAMERA Camera
CAMERA type.
noiseModel::Base::shared_ptr SharedNoiseModel
const char * what() const noexceptoverride
const bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
DenseIndex rows() const
Row size.