17 #include <boost/assign/list_of.hpp> 18 #include <boost/assign/std/vector.hpp> 23 using namespace gtsam;
28 #define NUM_ITERATIONS 1000 31 ofstream
os(
"timeSchurFactors.csv");
34 template<
typename CAMERA>
40 static const int D = CAMERA::dimension;
43 vector <Matrix2D, Eigen::aligned_allocator<Matrix2D>> Fblocks;
44 for (
size_t i = 0;
i <
m;
i++) {
46 Fblocks.push_back((
i + 1) * Matrix::Ones(2, D));
51 for (
size_t i = 0;
i <
m;
i++)
52 E.block < 2, 3 > (2 *
i, 0) = Matrix::Ones(2, 3);
58 const Vector b = Vector::Constant(2*m,1);
64 for (
size_t i = 0;
i <
m;
i++)
65 xvalues.
insert(
i, Vector::Constant(D,2));
76 #define TIME(label,factor,xx,yy) {\ 77 for (size_t t = 0; t < N; t++) \ 78 factor.multiplyHessianAdd(alpha, xx, yy);\ 80 for (size_t t = 0; t < N; t++) {\ 81 factor.multiplyHessianAdd(alpha, xx, yy);\ 84 tictoc_getNode(timer, label)\ 85 os << timer->secs()/NUM_ITERATIONS << ", ";\ 89 TIME(Implicit, implicitFactor, xvalues, yvalues)
90 TIME(Jacobian, jf, xvalues, yvalues)
91 TIME(JacobianQR, jqr, xvalues, yvalues)
95 TIME(Hessian, hessianFactor, xvalues, yvalues)
100 TIME(Overhead,dummy,xvalues,yvalues)
106 for (
size_t i = 0;
i <
m;
i++)
109 double* xdata = x.data();
112 Vector y = Vector::Zero(m * D);
113 TIME(RawImplicit, implicitFactor, xdata, y.data())
114 TIME(RawJacobianQ, jf, xdata, y.data())
115 TIME(RawJacobianQR, jqr, xdata, y.data())
137 os <<
"RawImplicit,";
138 os <<
"RawJacobianQ,";
139 os <<
"RawJacobianQR,";
143 vector < size_t >
ms;
149 for (
size_t m = 2;
m <= 50;
m += 2)
Pinhole camera with known calibration.
noiseModel::Diagonal::shared_ptr model
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
noiseModel::Diagonal::shared_ptr SharedDiagonal
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
#define TIME(label, factor, xx, yy)
ofstream os("timeSchurFactors.csv")
void timeAll(size_t m, size_t N)
A Gaussian factor using the canonical parameters (information form)
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
The matrix class, also used for vectors and row-vectors.
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
iterator insert(const std::pair< Key, Vector > &key_value)
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Calibration used by Bundler.