30 #include <gtsam/base/concepts.h> 39 #include <boost/none.hpp> 40 #include <boost/optional/optional.hpp> 41 #include <boost/serialization/nvp.hpp> 42 #include <boost/smart_ptr/shared_ptr.hpp> 47 namespace serialization {
59 template<
class CAMERA,
class LANDMARK>
62 GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA);
63 GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK);
67 typedef Eigen::Matrix<double, 2, DimC> JacobianC;
68 typedef Eigen::Matrix<double, 2, DimL> JacobianL;
80 typedef boost::shared_ptr<This> shared_ptr;
99 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
100 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
101 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));}
108 void print(
const std::string& s =
"SFMFactor",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const {
117 const This* e = dynamic_cast<const This*>(&p);
123 boost::optional<Matrix&> H1=boost::none, boost::optional<Matrix&> H2=boost::none)
const {
125 return camera.project2(point,H1,H2) -
measured_;
128 if (H1) *H1 = JacobianC::Zero();
129 if (H2) *H2 = JacobianL::Zero();
138 if (!this->
active(values))
return boost::shared_ptr<JacobianFactor>();
140 const Key key1 = this->
key1(), key2 = this->key2();
145 const CAMERA& camera = values.
at<CAMERA>(
key1);
146 const LANDMARK& point = values.
at<LANDMARK>(key2);
147 b =
measured() - camera.project2(point, H1, H2);
166 SharedDiagonal model;
168 model = boost::static_pointer_cast<noiseModel::Constrained>(
noiseModel)->unit();
171 return boost::make_shared<BinaryJacobianFactor<2, DimC, DimL> >(
key1, H1, key2, H2, b, model);
182 template<
class Archive>
183 void serialize(Archive & ar,
const unsigned int ) {
184 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
185 boost::serialization::base_object<Base>(*
this));
190 template<
class CAMERA,
class LANDMARK>
192 GeneralSFMFactor<CAMERA, LANDMARK> > {
199 template<
class CALIBRATION>
202 GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION);
216 typedef boost::shared_ptr<This> shared_ptr;
233 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
234 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
235 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));}
242 void print(
const std::string& s =
"SFMFactor2",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const {
251 const This* e = dynamic_cast<const This*>(&p);
257 boost::optional<Matrix&> H1=boost::none,
258 boost::optional<Matrix&> H2=boost::none,
259 boost::optional<Matrix&> H3=boost::none)
const 262 Camera camera(pose3,calib);
266 if (H1) *H1 = Matrix::Zero(2, 6);
267 if (H2) *H2 = Matrix::Zero(2, 3);
268 if (H3) *H3 = Matrix::Zero(2, DimK);
269 std::cout << e.what() <<
": Landmark "<< DefaultKeyFormatter(this->key2())
270 <<
" behind Camera " << DefaultKeyFormatter(this->
key1()) << std::endl;
283 template<
class Archive>
284 void serialize(Archive & ar,
const unsigned int ) {
285 ar & boost::serialization::make_nvp(
"NoiseModelFactor3",
286 boost::serialization::base_object<Base>(*
this));
291 template<
class CALIBRATION>
293 GeneralSFMFactor2<CALIBRATION> > {
Point2 measured_
the 2D measurement
Definition: GeneralSFMFactor.h:207
bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: GeneralSFMFactor.h:116
Base class and basic functions for Manifold types.
This is the base class for all factor types.
Definition: Factor.h:54
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:345
GeneralSFMFactor< CAMERA, LANDMARK > This
typedef for this object
Definition: GeneralSFMFactor.h:76
void print(const std::string &s="SFMFactor2", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: GeneralSFMFactor.h:242
ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:342
virtual ~GeneralSFMFactor()
destructor
Definition: GeneralSFMFactor.h:96
PinholeCamera< CALIBRATION > Camera
typedef for camera type
Definition: GeneralSFMFactor.h:212
Definition: PinholeCamera.h:33
A binary JacobianFactor specialization that uses fixed matrix math for speed.
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Print.
Definition: NonlinearFactor.cpp:63
GeneralSFMFactor2()
default constructor
Definition: GeneralSFMFactor.h:228
NoiseModelFactor3< Pose3, Point3, CALIBRATION > Base
typedef for the base class
Definition: GeneralSFMFactor.h:213
friend class boost::serialization::access
Serialization function.
Definition: GeneralSFMFactor.h:282
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
Non-linear factor for a constraint derived from a 2D measurement.
Definition: GeneralSFMFactor.h:200
friend class boost::serialization::access
Serialization function.
Definition: GeneralSFMFactor.h:181
Point2 measured_
the 2D measurement
Definition: GeneralSFMFactor.h:72
bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: GeneralSFMFactor.h:250
Vector evaluateError(const Pose3 &pose3, const Point3 &point, const CALIBRATION &calib, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
h(x)-z
Definition: GeneralSFMFactor.h:256
Vector evaluateError(const CAMERA &camera, const LANDMARK &point, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const
h(x)-z
Definition: GeneralSFMFactor.h:122
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
const Point2 measured() const
return the measured
Definition: GeneralSFMFactor.h:276
Definition: CalibratedCamera.h:32
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
Base class for all pinhole cameras.
NoiseModelFactor2< CAMERA, LANDMARK > Base
typedef for the base class
Definition: GeneralSFMFactor.h:77
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
GeneralSFMFactor(const Point2 &p)
constructor that takes a Point2
Definition: GeneralSFMFactor.h:93
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:210
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:377
void print(const std::string &s="SFMFactor", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: GeneralSFMFactor.h:108
GeneralSFMFactor2(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, Key calibKey)
Constructor.
Definition: GeneralSFMFactor.h:226
GeneralSFMFactor(double x, double y)
constructor that takes doubles x,y to make a Point2
Definition: GeneralSFMFactor.h:94
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: GeneralSFMFactor.h:233
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:420
Access to matrices via blocks of pre-defined sizes.
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Non-linear factor base classes.
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: GeneralSFMFactor.h:99
Definition: GeneralSFMFactor.h:60
virtual bool active(const Values &) const
Checks whether a factor should be used based on a set of values.
Definition: NonlinearFactor.h:113
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Key key1() const
methods to retrieve keys
Definition: NonlinearFactor.h:454
Concept check for values that can be used in unit tests.
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
typedef and functions to augment Eigen's MatrixXd
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
GeneralSFMFactor(const Point2 &measured, const SharedNoiseModel &model, Key cameraKey, Key landmarkKey)
Constructor.
Definition: GeneralSFMFactor.h:89
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:71
virtual ~GeneralSFMFactor2()
destructor
Definition: GeneralSFMFactor.h:230
typedef and functions to augment Eigen's VectorXd
const Point2 measured() const
return the measured
Definition: GeneralSFMFactor.h:175
GeneralSFMFactor()
default constructor
Definition: GeneralSFMFactor.h:92
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const
Linearize using fixed-size matrices.
Definition: GeneralSFMFactor.h:136
Typedefs for easier changing of types.