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>
90 Key cameraKey,
Key landmarkKey)
91 : Base(model, cameraKey, landmarkKey), measured_(measured) {}
120 const This*
e =
dynamic_cast<const This*
>(&
p);
126 boost::optional<Matrix&> H1=boost::none, boost::optional<Matrix&> H2=boost::none)
const override {
128 return camera.project2(point,H1,H2) - measured_;
131 if (H1) *H1 = JacobianC::Zero();
132 if (H2) *H2 = JacobianL::Zero();
139 boost::shared_ptr<GaussianFactor> linearize(
const Values&
values)
const override {
141 if (!this->active(values))
return boost::shared_ptr<JacobianFactor>();
148 const CAMERA& camera = values.
at<CAMERA>(
key1);
149 const LANDMARK& point = values.
at<LANDMARK>(
key2);
150 b =
measured() - camera.project2(point, H1, H2);
160 if (noiseModel && !noiseModel->isUnit()) {
163 H1 = noiseModel->Whiten(H1);
164 H2 = noiseModel->Whiten(H2);
165 b = noiseModel->Whiten(b);
170 if (noiseModel && noiseModel->isConstrained()) {
174 return boost::make_shared<BinaryJacobianFactor<2, DimC, DimL> >(
key1, H1,
key2, H2,
b,
model);
184 friend class boost::serialization::access;
185 template<
class Archive>
186 void serialize(Archive & ar,
const unsigned int ) {
187 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
188 boost::serialization::base_object<Base>(*
this));
189 ar & BOOST_SERIALIZATION_NVP(measured_);
193 template<
class CAMERA,
class LANDMARK>
195 GeneralSFMFactor<CAMERA, LANDMARK> > {
202 template<
class CALIBRATION>
230 Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {}
254 const This*
e =
dynamic_cast<const This*
>(&
p);
260 boost::optional<Matrix&> H1=boost::none,
261 boost::optional<Matrix&> H2=boost::none,
262 boost::optional<Matrix&> H3=boost::none)
const override 265 Camera
camera(pose3,calib);
266 return camera.
project(point, H1, H2, H3) - measured_;
269 if (H1) *H1 = Matrix::Zero(2, 6);
270 if (H2) *H2 = Matrix::Zero(2, 3);
271 if (H3) *H3 = Matrix::Zero(2, DimK);
285 friend class boost::serialization::access;
286 template<
class Archive>
288 ar & boost::serialization::make_nvp(
"NoiseModelFactor3",
289 boost::serialization::base_object<Base>(*
this));
290 ar & BOOST_SERIALIZATION_NVP(measured_);
294 template<
class CALIBRATION>
296 GeneralSFMFactor2<CALIBRATION> > {
void print(const Matrix &A, const string &s, ostream &stream)
GeneralSFMFactor2()
default constructor
NoiseModelFactor2< CAMERA, LANDMARK > Base
typedef for the base class
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Typedefs for easier changing of types.
void serialize(Archive &ar, Eigen::Matrix< Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_ > &m, const unsigned int version)
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.
noiseModel::Diagonal::shared_ptr model
gtsam::NonlinearFactor::shared_ptr clone() const override
Give fixed size dimension of a type, fails at compile time if dynamic.
GeneralSFMFactor2(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, Key calibKey)
~GeneralSFMFactor2() override
destructor
A binary JacobianFactor specialization that uses fixed matrix math for speed.
Eigen::Matrix< double, 2, DimC > JacobianC
boost::shared_ptr< This > shared_ptr
static const KeyFormatter DefaultKeyFormatter
PinholeCamera< CALIBRATION > Camera
typedef for camera type
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Point2 measured_
the 2D measurement
const Symbol key1('v', 1)
GeneralSFMFactor< CAMERA, LANDMARK > This
typedef for this object
Base class for all pinhole cameras.
const ValueType at(Key j) const
Base class and basic functions for Manifold types.
Eigen::Matrix< double, 2, DimL > JacobianL
static Pose3 pose3(rt3, pt3)
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.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
GeneralSFMFactor(const Point2 &measured, const SharedNoiseModel &model, Key cameraKey, Key landmarkKey)
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 override
NoiseModelFactor3< Pose3, Point3, CALIBRATION > Base
typedef for the base class
GeneralSFMFactor()
constructor that takes a Point2
const Point2 measured() const
noiseModel::Diagonal::shared_ptr SharedDiagonal
typedef and functions to augment Eigen's VectorXd
Non-linear factor base classes.
boost::shared_ptr< This > shared_ptr
const Symbol key2('v', 2)
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
#define GTSAM_CONCEPT_MANIFOLD_TYPE(T)
void serialize(Archive &ar, const unsigned int)
void print(const std::string &s="SFMFactor2", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
GeneralSFMFactor2< CALIBRATION > This
Point2 measured_
the 2D measurement
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
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
noiseModel::Base::shared_ptr SharedNoiseModel
const char * what() const noexceptoverride