30 #include <gtsam/base/concepts.h> 39 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 40 #include <boost/serialization/nvp.hpp> 46 namespace serialization {
58 template<
class CAMERA,
class LANDMARK>
61 GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA)
62 GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK)
66 typedef Eigen::Matrix<double, 2, DimC> JacobianC;
67 typedef Eigen::Matrix<double, 2, DimL> JacobianL;
79 using Base::evaluateError;
82 typedef std::shared_ptr<This> shared_ptr;
92 Key cameraKey,
Key landmarkKey)
93 : Base(model, cameraKey, landmarkKey), measured_(measured) {}
104 gtsam::NonlinearFactor::shared_ptr clone()
const override {
106 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));}
113 void print(
const std::string& s =
"SFMFactor",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
122 const This* e =
dynamic_cast<const This*
>(&p);
127 Vector evaluateError(
const CAMERA& camera,
const LANDMARK& point,
130 return camera.project2(point,H1,H2) - measured_;
133 if (H1) *H1 = JacobianC::Zero();
134 if (H2) *H2 = JacobianL::Zero();
141 std::shared_ptr<GaussianFactor> linearize(
const Values& values)
const override {
143 if (!this->active(values))
return std::shared_ptr<JacobianFactor>();
145 const Key key1 = this->key1(), key2 = this->key2();
150 const CAMERA& camera = values.
at<CAMERA>(key1);
151 const LANDMARK& point = values.
at<LANDMARK>(key2);
152 b = measured() - camera.project2(point, H1, H2);
162 if (noiseModel && !noiseModel->isUnit()) {
165 H1 = noiseModel->Whiten(H1);
166 H2 = noiseModel->Whiten(H2);
167 b = noiseModel->Whiten(b);
171 SharedDiagonal model;
172 if (noiseModel && noiseModel->isConstrained()) {
176 return std::make_shared<BinaryJacobianFactor<2, DimC, DimL> >(key1, H1, key2, H2, b, model);
180 inline const Point2 measured()
const {
185 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 187 friend class boost::serialization::access;
188 template<
class Archive>
189 void serialize(Archive & ar,
const unsigned int ) {
191 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
192 boost::serialization::base_object<Base>(*
this));
193 ar & BOOST_SERIALIZATION_NVP(measured_);
198 template<
class CAMERA,
class LANDMARK>
200 GeneralSFMFactor<CAMERA, LANDMARK> > {
207 template<
class CALIBRATION>
210 GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION)
224 typedef std::shared_ptr<This> shared_ptr;
235 Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {}
241 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
243 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));}
250 void print(
const std::string& s =
"SFMFactor2",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
259 const This* e =
dynamic_cast<const This*
>(&p);
267 Camera camera(pose3,calib);
268 return camera.
project(point, H1, H2, H3) - measured_;
271 if (H1) *H1 = Matrix::Zero(2, 6);
272 if (H2) *H2 = Matrix::Zero(2, 3);
273 if (H3) *H3 = Matrix::Zero(2, DimK);
274 std::cout << e.what() <<
": Landmark "<< DefaultKeyFormatter(this->key2())
275 <<
" behind Camera " << DefaultKeyFormatter(this->key1()) << std::endl;
286 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 288 friend class boost::serialization::access;
289 template<
class Archive>
290 void serialize(Archive & ar,
const unsigned int ) {
292 ar & boost::serialization::make_nvp(
"NoiseModelFactor3",
293 boost::serialization::base_object<Base>(*
this));
294 ar & BOOST_SERIALIZATION_NVP(measured_);
299 template<
class CALIBRATION>
301 GeneralSFMFactor2<CALIBRATION> > {
GeneralSFMFactor2()
default constructor
Definition: GeneralSFMFactor.h:236
Definition: GeneralSFMFactor.h:59
Definition: NonlinearFactor.h:431
Typedefs for easier changing of types.
Concept check for values that can be used in unit tests.
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
const ValueType at(Key j) const
Definition: Values-inl.h:204
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GeneralSFMFactor.h:241
Definition: Testable.h:152
Vector2 Point2
Definition: Point2.h:32
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:161
GeneralSFMFactor2(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, Key calibKey)
Definition: GeneralSFMFactor.h:234
const Point2 measured() const
Definition: GeneralSFMFactor.h:281
~GeneralSFMFactor2() override
destructor
Definition: GeneralSFMFactor.h:238
Definition: NonlinearFactor.h:68
A binary JacobianFactor specialization that uses fixed matrix math for speed.
NoiseModelFactorN< CAMERA, LANDMARK > Base
typedef for the base class
Definition: GeneralSFMFactor.h:76
PinholeCamera< CALIBRATION > Camera
typedef for camera type
Definition: GeneralSFMFactor.h:220
NoiseModelFactorN< Pose3, Point3, CALIBRATION > Base
typedef for the base class
Definition: GeneralSFMFactor.h:221
Vector evaluateError(const Pose3 &pose3, const Point3 &point, const CALIBRATION &calib, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
Definition: GeneralSFMFactor.h:264
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: GeneralSFMFactor.h:258
Point2 measured_
the 2D measurement
Definition: GeneralSFMFactor.h:215
GeneralSFMFactor< CAMERA, LANDMARK > This
typedef for this object
Definition: GeneralSFMFactor.h:75
Base class for all pinhole cameras.
Definition: Testable.h:112
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
Base class and basic functions for Manifold types.
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
GeneralSFMFactor(const Point2 &measured, const SharedNoiseModel &model, Key cameraKey, Key landmarkKey)
Definition: GeneralSFMFactor.h:91
Definition: GeneralSFMFactor.h:208
typedef and functions to augment Eigen's MatrixXd
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
GeneralSFMFactor()
constructor that takes a Point2
Definition: GeneralSFMFactor.h:95
Definition: PinholeCamera.h:33
Definition: chartTesting.h:28
typedef and functions to augment Eigen's VectorXd
Non-linear factor base classes.
Definition: CalibratedCamera.h:34
void print(const std::string &s="SFMFactor2", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: GeneralSFMFactor.h:250
Point2 measured_
the 2D measurement
Definition: GeneralSFMFactor.h:71
Vector3 Point3
Definition: Point3.h:38
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Definition: NoiseModel.h:390
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741