39 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 40 #include <boost/serialization/nvp.hpp> 46 namespace serialization {
58 template<
class CAMERA,
class LANDMARK>
79 using Base::evaluateError;
92 Key cameraKey,
Key landmarkKey)
93 : Base(model, cameraKey, landmarkKey), measured_(measured) {}
122 const This*
e =
dynamic_cast<const This*
>(&
p);
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>();
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);
172 if (noiseModel && noiseModel->isConstrained()) {
176 return std::make_shared<BinaryJacobianFactor<2, DimC, DimL> >(
key1, H1,
key2, H2,
b,
model);
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>
235 Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {}
259 const This*
e =
dynamic_cast<const This*
>(&
p);
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);
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
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
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
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
gtsam::NonlinearFactor::shared_ptr clone() const override
Give fixed size dimension of a type, fails at compile time if dynamic.
const Point2 measured() const
~GeneralSFMFactor2() override
destructor
A binary JacobianFactor specialization that uses fixed matrix math for speed.
Namespace containing all symbols from the Eigen library.
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
static const KeyFormatter DefaultKeyFormatter
Vector evaluateError(const Pose3 &pose3, const Point3 &point, const CALIBRATION &calib, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Base class for all pinhole cameras.
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
Matrix * OptionalMatrixType
const Symbol key1('v', 1)
Base class and basic functions for Manifold types.
static Pose3 pose3(rt3, pt3)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
GeneralSFMFactor()
constructor that takes a Point2
noiseModel::Diagonal::shared_ptr SharedDiagonal
typedef and functions to augment Eigen's VectorXd
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
#define GTSAM_CONCEPT_MANIFOLD_TYPE(T)
void print(const std::string &s="SFMFactor2", const KeyFormatter &keyFormatter=DefaultKeyFormatter) 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
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 Symbol key2('v', 2)
const char * what() const noexcept override