23 #include <gtsam/slam/JacobianFactorQ.h> 24 #include <gtsam/slam/JacobianFactorSVD.h> 31 #include <boost/optional.hpp> 32 #include <boost/serialization/optional.hpp> 33 #include <boost/make_shared.hpp> 46 template<
class CAMERA>
52 typedef typename CAMERA::Measurement Z;
53 typedef typename CAMERA::MeasurementVector ZVector;
59 typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD;
60 typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks;
87 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
100 boost::optional<Pose3> body_P_sensor = boost::none,
101 size_t expectedNumberCameras = 10)
104 if (!sharedNoiseModel)
105 throw std::runtime_error(
"SmartFactorBase: sharedNoiseModel is required");
107 SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast<
110 if (!sharedIsotropic)
111 throw std::runtime_error(
"SmartFactorBase: needs isotropic");
126 void add(
const Z& measured_i,
const Key& cameraKey_i) {
127 this->measured_.push_back(measured_i);
128 this->
keys_.push_back(cameraKey_i);
135 for (
size_t i = 0; i < measurements.size(); i++) {
136 this->measured_.push_back(measurements.at(i));
137 this->
keys_.push_back(cameraKeys.at(i));
145 template<
class SFM_TRACK>
146 void add(
const SFM_TRACK& trackToAdd) {
147 for (
size_t k = 0; k < trackToAdd.number_measurements(); k++) {
148 this->measured_.push_back(trackToAdd.measurements[k].second);
149 this->
keys_.push_back(trackToAdd.measurements[k].first);
154 virtual size_t dim()
const {
155 return ZDim * this->measured_.size();
167 cameras.push_back(values.
at<CAMERA>(k));
177 DefaultKeyFormatter)
const {
178 std::cout << s <<
"SmartFactorBase, z = \n";
179 for (
size_t k = 0; k <
measured_.size(); ++k) {
180 std::cout <<
"measurement, p = " <<
measured_[k] <<
"\t";
190 const This *e = dynamic_cast<const This*>(&p);
192 bool areMeasurementsEqual =
true;
193 for (
size_t i = 0; i <
measured_.size(); i++) {
195 areMeasurementsEqual =
false;
198 return e &&
Base::equals(p, tol) && areMeasurementsEqual;
202 template<
class POINT>
204 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
205 boost::optional<Matrix&> E = boost::none)
const {
208 for(
size_t i=0; i < Fs->size(); i++){
212 Fs->at(i) = Fs->at(i) * J;
224 boost::optional<Matrix&> E = boost::none)
const {}
230 template<
class POINT>
244 template<
class POINT>
246 const POINT& point)
const {
248 return 0.5 * e.dot(e);
253 return (E.transpose() * E).inverse();
262 template<
class POINT>
273 template<
class POINT>
283 Eigen::JacobiSVD<Matrix>
svd(E, Eigen::ComputeFullU);
284 Vector s =
svd.singularValues();
285 size_t m = this->
keys_.size();
286 Enull =
svd.matrixU().block(0, N,
ZDim * m,
ZDim * m - N);
292 bool diagonalDamping =
false)
const {
301 return boost::make_shared<RegularHessianFactor<Dim> >(
keys_,
311 const double lambda,
bool diagonalDamping,
324 for (
size_t i = 0; i < F.size(); i++)
329 boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> >
331 double lambda = 0.0,
bool diagonalDamping =
false)
const {
338 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(
keys_, F, E,
347 bool diagonalDamping =
false)
const {
352 const size_t M = b.size();
355 return boost::make_shared<JacobianFactorQ<Dim, ZDim> >(
keys_, F, E, P, b, n);
364 size_t m = this->
keys_.size();
367 const size_t M =
ZDim * m;
372 return boost::make_shared<JacobianFactorSVD<Dim, ZDim> >(
keys_, F, E0, b, n);
377 size_t m = Fs.size();
380 for (
size_t i = 0; i < m; ++i)
385 Pose3 body_P_sensor()
const{
395 friend class boost::serialization::access;
396 template<
class ARCHIVE>
397 void serialize(ARCHIVE & ar,
const unsigned int ) {
398 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
This is the base class for all factor types.
Definition: Factor.h:54
CameraSet< CAMERA > Cameras
We use the new CameraSte data structure to refer to a set of cameras.
Definition: SmartFactorBase.h:93
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
Vector whitenedError(const Cameras &cameras, const POINT &point) const
Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z] Noise model applied.
Definition: SmartFactorBase.h:231
ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:342
const ZVector & measured() const
return the measurements
Definition: SmartFactorBase.h:159
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
SVD version.
Definition: SmartFactorBase.h:274
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Calculate the error of the factor.
Definition: SmartFactorBase.h:245
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:164
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
SVD computes economy SVD A=U*S*V'.
Definition: Matrix.cpp:555
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
An isotropic noise model corresponds to a scaled diagonal covariance To construct,...
Definition: NoiseModel.h:519
virtual void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
This corrects the Jacobians for the case in which some pixel measurement is missing (nan) In practice...
Definition: SmartFactorBase.h:223
boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > createRegularImplicitSchurFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
Return Jacobians as RegularImplicitSchurFactor with raw access.
Definition: SmartFactorBase.h:330
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:36
HessianFactor class with constant sized blocks.
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
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Compute F, E, and b (called below in both vanilla and SVD versions), where F is a vector of derivativ...
Definition: SmartFactorBase.h:263
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives.
Definition: SmartFactorBase.h:203
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
static const int ZDim
Measurement dimension.
Definition: SmartFactorBase.h:58
void add(const Z &measured_i, const Key &cameraKey_i)
Add a new measurement and pose key.
Definition: SmartFactorBase.h:126
virtual size_t dim() const
get the dimension (number of rows!) of the factor
Definition: SmartFactorBase.h:154
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartFactorBase.h:90
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
void add(ZVector &measurements, KeyVector &cameraKeys)
Add a bunch of measurements, together with the camera keys.
Definition: SmartFactorBase.h:134
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.
static Matrix PointCov(const Matrix &E, const double lambda=0.0, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter, dynamic version.
Definition: CameraSet.h:210
static void UpdateSchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &allKeys, const KeyVector &keys, SymmetricBlockMatrix &augmentedHessian)
Applies Schur complement (exploiting block structure) to get a smart factor on cameras,...
Definition: CameraSet.h:246
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: NonlinearFactor.cpp:26
virtual bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: SmartFactorBase.h:189
Base class for smart factors This base class has no internal point, but it has a measurement,...
Definition: SmartFactorBase.h:47
SmartFactorBase()
Default Constructor, for serialization.
Definition: SmartFactorBase.h:96
SharedIsotropic noiseModel_
As of Feb 22, 2015, the noise model is the same for all measurements and is isotropic.
Definition: SmartFactorBase.h:69
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix G = F' * F - F' * E * P * ...
Definition: CameraSet.h:149
Base class to create smart factors on poses or cameras.
SmartFactorBase(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
Constructor.
Definition: SmartFactorBase.h:99
Definition: SymmetricBlockMatrix.h:51
static Matrix PointCov(Matrix &E)
Computes Point Covariance P from E.
Definition: SmartFactorBase.h:252
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: SmartFactorBase.h:176
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Return Jacobians as JacobianFactorSVD TODO lambda is currently ignored.
Definition: SmartFactorBase.h:362
boost::shared_ptr< JacobianFactorQ< Dim, ZDim > > createJacobianQFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
Return Jacobians as JacobianFactorQ.
Definition: SmartFactorBase.h:345
void add(const SFM_TRACK &trackToAdd)
Adds an entire SfM_track (collection of cameras observing a single point).
Definition: SmartFactorBase.h:146
Vector reprojectionError(const POINT &point, const ZVector &measured, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Calculate vector [project2(point)-z] of re-projection errors.
Definition: CameraSet.h:136
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:57
void updateAugmentedHessian(const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
Add the contribution of the smart factor to a pre-allocated Hessian, using sparse linear algebra.
Definition: SmartFactorBase.h:310
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:561
static void FillDiagonalF(const FBlocks &Fs, Matrix &F)
Create BIG block-diagonal matrix F from Fblocks.
Definition: SmartFactorBase.h:376
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:321
boost::shared_ptr< RegularHessianFactor< Dim > > createHessianFactor(const Cameras &cameras, const Point3 &point, const double lambda=0.0, bool diagonalDamping=false) const
Linearize to a Hessianfactor.
Definition: SmartFactorBase.h:290
boost::optional< Pose3 > body_P_sensor_
Pose of the camera in the body frame.
Definition: SmartFactorBase.h:79
virtual ~SmartFactorBase()
Virtual destructor, subclasses from NonlinearFactor.
Definition: SmartFactorBase.h:117
ZVector measured_
2D measurement and noise model for each of the m views We keep a copy of measurements for I/O and com...
Definition: SmartFactorBase.h:76