32 #include <boost/optional.hpp> 33 #include <boost/serialization/optional.hpp> 34 #include <boost/make_shared.hpp> 47 template<
class CAMERA>
54 typedef typename CAMERA::MeasurementVector
ZVector;
61 typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >
FBlocks;
99 size_t expectedNumberCameras = 10)
102 if (!sharedNoiseModel)
103 throw std::runtime_error(
"SmartFactorBase: sharedNoiseModel is required");
108 if (!sharedIsotropic)
109 throw std::runtime_error(
"SmartFactorBase: needs isotropic");
111 noiseModel_ = sharedIsotropic;
125 throw std::invalid_argument(
126 "SmartFactorBase::add: adding duplicate measurement for key.");
128 this->measured_.push_back(measured);
129 this->
keys_.push_back(key);
136 assert(measurements.size() == cameraKeys.size());
137 for (
size_t i = 0;
i < measurements.size();
i++) {
138 this->
add(measurements[
i], cameraKeys[i]);
146 template<
class SFM_TRACK>
147 void add(
const SFM_TRACK& trackToAdd) {
148 for (
size_t k = 0; k < trackToAdd.number_measurements(); k++) {
149 this->measured_.push_back(trackToAdd.measurements[k].second);
150 this->
keys_.push_back(trackToAdd.measurements[k].first);
155 size_t dim()
const override {
156 return ZDim * this->measured_.size();
168 cameras.push_back(values.
at<CAMERA>(k));
179 std::cout <<
s <<
"SmartFactorBase, z = \n";
180 for (
size_t k = 0; k < measured_.size(); ++k) {
181 std::cout <<
"measurement, p = " << measured_[k] <<
"\t";
182 noiseModel_->print(
"noise model = ");
185 body_P_sensor_->print(
"body_P_sensor_:\n");
191 const This *
e =
dynamic_cast<const This*
>(&
p);
193 bool areMeasurementsEqual =
true;
194 for (
size_t i = 0;
i < measured_.size();
i++) {
196 areMeasurementsEqual =
false;
204 template <
class POINT>
207 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
208 boost::optional<Matrix&>
E = boost::none)
const {
210 if (body_P_sensor_ && Fs) {
215 for (
size_t i = 0;
i < Fs->size();
i++) {
216 const Pose3 world_P_body = cameras[
i].pose() * sensor_P_body;
221 world_P_body.
compose(*body_P_sensor_, H);
223 J.template block<pose_dim, pose_dim>(0, 0) = H;
224 Fs->at(
i) = Fs->at(
i) *
J;
236 boost::optional<Matrix&>
E = boost::none)
const {}
242 template<
class POINT>
246 noiseModel_->whitenInPlace(e);
256 template<
class POINT>
258 const POINT&
point)
const {
260 return 0.5 * e.dot(e);
265 return (E.transpose() *
E).
inverse();
274 template<
class POINT>
285 template<
class POINT>
297 size_t m = this->
keys_.size();
298 Enull = svd.
matrixU().block(0, N, ZDim * m, ZDim * m - N);
304 bool diagonalDamping =
false)
const {
313 return boost::make_shared<RegularHessianFactor<Dim> >(
keys_,
323 const double lambda,
bool diagonalDamping,
334 noiseModel_->WhitenSystem(E, b);
336 for (
size_t i = 0;
i < F.size();
i++)
337 F[
i] = noiseModel_->Whiten(F[
i]);
341 boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> >
343 double lambda = 0.0,
bool diagonalDamping =
false)
const {
350 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(
keys_,
F,
E,
359 bool diagonalDamping =
false)
const {
364 const size_t M = b.size();
367 return boost::make_shared<JacobianFactorQ<Dim, ZDim> >(
keys_,
F,
E,
P,
b,
n);
376 size_t m = this->
keys_.size();
379 const size_t M = ZDim *
m;
383 noiseModel_->sigma());
384 return boost::make_shared<JacobianFactorSVD<Dim, ZDim> >(
keys_,
F, E0,
b,
n);
389 size_t m = Fs.size();
390 F.resize(ZDim * m, Dim * m);
392 for (
size_t i = 0;
i <
m; ++
i)
393 F.block<ZDim, Dim>(ZDim *
i, Dim * i) = Fs.at(i);
407 friend class boost::serialization::access;
408 template<
class ARCHIVE>
410 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
411 ar & BOOST_SERIALIZATION_NVP(noiseModel_);
412 ar & BOOST_SERIALIZATION_NVP(measured_);
413 ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
SmartFactorBase(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
Constructor.
static Matrix PointCov(const Matrix &E, const double lambda=0.0, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter, dynamic version.
void add(const SFM_TRACK &trackToAdd)
Vector whitenedError(const Cameras &cameras, const POINT &point) const
Matrix< RealScalar, Dynamic, Dynamic > M
EIGEN_DEVICE_FUNC Matrix< _Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setZero(Index size)
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
const SingularValuesType & singularValues() const
Base class to create smart factors on poses or cameras.
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Give fixed size dimension of a type, fails at compile time if dynamic.
void serialize(ARCHIVE &ar, const unsigned int)
boost::shared_ptr< JacobianFactorQ< Dim, ZDim > > createJacobianQFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
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.
SmartFactorBase()
Default Constructor, for serialization.
CameraSet< CAMERA > Cameras
We use the new CameraSte data structure to refer to a set of cameras.
KeyVector keys_
The keys involved in this factor.
noiseModel::Isotropic::shared_ptr SharedIsotropic
boost::optional< Pose3 > body_P_sensor_
Pose of the camera in the body frame.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
SharedIsotropic noiseModel_
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
CAMERA::MeasurementVector ZVector
~SmartFactorBase() override
Virtual destructor, subclasses from NonlinearFactor.
A set of cameras, all with their own calibration.
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.
static const KeyFormatter DefaultKeyFormatter
static Matrix PointCov(Matrix &E)
Computes Point Covariance P from E.
Base class for smart factors This base class has no internal point, but it has a measurement, noise model and an optional sensor pose. This class mainly computes the derivatives and returns them as a variety of factors. The methods take a Cameras argument, which should behave like PinholeCamera, and the value of a point, which is kept in the base class.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Class compose(const Class &g) const
Pose3 inverse() const
inverse transformation with derivatives
const ValueType at(Key j) const
static void FillDiagonalF(const FBlocks &Fs, Matrix &F)
Create BIG block-diagonal matrix F from Fblocks.
GenericMeasurement< Point2, Point2 > Measurement
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.)
HessianFactor class with constant sized blocks.
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
const MatrixUType & matrixU() const
JacobiRotation< float > J
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
void add(const ZVector &measurements, const KeyVector &cameraKeys)
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
Pose3 body_P_sensor() const
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Non-linear factor base classes.
size_t dim() const override
get the dimension (number of rows!) of the factor
void add(const Z &measured, const Key &key)
void updateAugmentedHessian(const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
static const int Dim
Camera dimension.
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Two-sided Jacobi SVD decomposition of a rectangular matrix.
SmartFactorBase< CAMERA > This
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Eigen::Matrix< double, ZDim, Dim > MatrixZD
The matrix class, also used for vectors and row-vectors.
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)
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
const ZVector & measured() const
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.
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
std::uint64_t Key
Integer nonlinear key type.
virtual void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
static const int ZDim
Measurement dimension.
noiseModel::Base::shared_ptr SharedNoiseModel
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
SVD version.
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)