32 #include <boost/assign/list_of.hpp> 33 using boost::assign::list_of;
34 using boost::assign::map_list_of;
59 using namespace gtsam;
64 Vector3 axisAngle(0.1, 0.2, 0.3);
76 return base[cols * i +
j];
80 double r =
static_cast<double>(rand());
92 for (
int i = 0;
i < 3; ++
i) {
100 x[1] = PX[1] / PX[2];
109 if (
operator()(P.
data(), X.data(), x.data()))
112 throw std::runtime_error(
"Projective fail");
127 P << 1, 0, 0, 0, 0, 1, 0, 5, 0, 0, 1, 0;
128 Vector4
X(10, 0, 5, 1);
132 Vector2 actual = projective(P, X);
136 Matrix E1 = numericalDerivative21<Vector2, RowMajorMatrix34, Vector4>(
138 Matrix E2 = numericalDerivative22<Vector2, RowMajorMatrix34, Vector4>(
145 double* jacobians[] = {H1.data(), H2.
data()};
146 CHECK((AutoDiff<Projective, double, 12, 4>::Differentiate(
147 projective, parameters, 2, actual2.data(), jacobians)));
158 if (snavely(P.data(), X.data(), x.data()))
161 throw std::runtime_error(
"Snavely fail");
169 Vector9
P =
Camera().localCoordinates(camera);
171 #ifdef GTSAM_POSE3_EXPMAP 184 #ifdef GTSAM_POSE3_EXPMAP 185 Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0.7583528428, 4.9582357859, -0.224941471539, 1, 0, 0).finished();
187 Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0, 5, 0, 1, 0, 0).finished();
211 double* jacobians[] = {H1.data(), H2.
data()};
212 CHECK((AutoDiff<SnavelyProjection, double, 9, 3>::Differentiate(
213 snavely, parameters, 2, actual2.data(), jacobians)));
233 Vector2 actual2 = snavely(P,
X, H1, H2);
Both ManifoldTraits and Testable.
Adaptor for Ceres style auto-differentiated functions.
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
double k1() const
distorsion parameter k1
PinholeCamera< Cal3Bundler0 > Camera
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
Vector2 adapted(const Vector9 &P, const Vector3 &X)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Vector2 operator()(const MatrixRowMajor &P, const Vector4 &X) const
T & RowMajorAccess(T *base, int rows, int cols, int i, int j)
double k2() const
distorsion parameter k2
Some functions to compute numerical derivatives.
Cal3Bundler0 retract(const Vector &d) const
T upAligned(T value, unsigned requiredAlignment=TraceAlignment)
Cal3Bundler0(double f=0, double k1=0, double k2=0, double u0=0, double v0=0)
Expressions for Block Automatic Differentiation.
Base class for all pinhole cameras.
bool operator()(A const P[12], A const X[4], A x[2]) const
static Rot3 Rodrigues(const Vector3 &w)
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector3 localCoordinates(const Cal3Bundler0 &T2) const
std::set< Key > keys() const
Return keys that play in this expression.
static ConjugateGradientParameters parameters
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
double px() const
image center in x
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define EXPECT_LONGS_EQUAL(expected, actual)
TEST(LPInitSolver, InfiniteLoopSingleVar)
size_t traceSize() const
Return size needed for memory buffer in traceExecution.
Vector2 expectedMeasurement(1.2431567, 1.2525694)
double fx() const
focal length x
Annotation indicating that a class derives from another given type.
The matrix class, also used for vectors and row-vectors.
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
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
double py() const
image center in y
Calibration used by Bundler.
The most common 5DOF 3D->2D calibration.
void AngleAxisToRotationMatrix(const T *angle_axis, T *R)