Go to the documentation of this file.
56 using namespace gtsam;
61 Vector3 axisAngle(0.1, 0.2, 0.3);
62 Matrix3
expected = Rot3::Rodrigues(axisAngle).matrix();
77 double r =
static_cast<double>(rand());
89 for (
int i = 0;
i < 3; ++
i) {
106 if (
operator()(
P.data(),
X.data(),
x.data()))
109 throw std::runtime_error(
"Projective fail");
124 P << 1, 0, 0, 0, 0, 1, 0, 5, 0, 0, 1, 0;
125 Vector4
X(10, 0, 5, 1);
133 Matrix E1 = numericalDerivative21<Vector2, RowMajorMatrix34, Vector4>(
135 Matrix E2 = numericalDerivative22<Vector2, RowMajorMatrix34, Vector4>(
142 double* jacobians[] = {H1.data(), H2.
data()};
143 CHECK((AutoDiff<Projective, double, 12, 4>::Differentiate(
144 projective,
parameters, 2, actual2.data(), jacobians)));
155 if (snavely(
P.data(),
X.data(),
x.data()))
158 throw std::runtime_error(
"Snavely fail");
168 #ifdef GTSAM_POSE3_EXPMAP
181 #ifdef GTSAM_POSE3_EXPMAP
182 Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0.7583528428, 4.9582357859, -0.224941471539, 1, 0, 0).finished();
184 Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0, 5, 0, 1, 0, 0).finished();
208 double* jacobians[] = {H1.data(), H2.
data()};
209 CHECK((AutoDiff<SnavelyProjection, double, 9, 3>::Differentiate(
210 snavely,
parameters, 2, actual2.data(), jacobians)));
static int runAllTests(TestResult &result)
Annotation indicating that a class derives from another given type.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
#define EXPECT_LONGS_EQUAL(expected, actual)
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
The most common 5DOF 3D->2D calibration.
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
T upAligned(T value, unsigned requiredAlignment=TraceAlignment)
double f() const
focal length
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
def retract(a, np.ndarray xi)
Both ManifoldTraits and Testable.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Vector2 adapted(const Vector9 &P, const Vector3 &X)
std::set< Key > keys() const
Return keys that play in this expression.
Cal3Bundler0 retract(const Vector &d) const
T & RowMajorAccess(T *base, int rows, int cols, int i, int j)
Some functions to compute numerical derivatives.
double k1() const
distortion parameter k1
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static ConjugateGradientParameters parameters
Base class for all pinhole cameras.
Calibration used by Bundler.
Vector3 localCoordinates(const Cal3Bundler0 &T2) const
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
double k2() const
distortion parameter k2
double fx() const
focal length x
bool operator()(A const P[12], A const X[4], A x[2]) const
size_t traceSize() const
Return size needed for memory buffer in traceExecution.
Adaptor for Ceres style auto-differentiated functions.
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
Vector2 operator()(const MatrixRowMajor &P, const Vector4 &X) const
PinholeCamera< Cal3Bundler0 > Camera
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
Cal3Bundler0(double f=0, double k1=0, double k2=0, double u0=0, double v0=0)
The matrix class, also used for vectors and row-vectors.
TEST(AdaptAutoDiff, Rotation)
double px() const
image center in x
void AngleAxisToRotationMatrix(const T *angle_axis, T *R)
Expressions for Block Automatic Differentiation.
Calibration used by Bundler.
Vector2 expectedMeasurement(1.2431567, 1.2525694)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:09