Go to the documentation of this file.
30 using namespace std::placeholders;
32 using namespace gtsam;
36 static const Cal3_S2 K(625, 625, 0, 0, 0);
69 std::bind(Camera::Create, std::placeholders::_1, std::placeholders::_2,
71 Matrix numericalH1 = numericalDerivative21<Camera,Pose3,Cal3_S2>(
f,
pose,
K);
73 Matrix numericalH2 = numericalDerivative22<Camera,Pose3,Cal3_S2>(
f,
pose,
K);
86 Matrix numericalH = numericalDerivative11<Pose3,Camera>(
f,
camera);
112 Point3 xc(0,1,0),yc(0,0,-1),zc(-1,0,0);
155 Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.);
171 Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.);
186 Rot3 rot(1., 0., 0., 0., 1., 0., 0., 0., 1.);
205 Matrix Dpose, Dpoint, Dcal;
223 Matrix Dpose, Dpoint, Dcal;
227 Point2 actual =
camera.project(point3D, Dpose, Dpoint, Dcal);
234 Matrix numerical_point2x2 = Hexpected2.block(0,0,2,2);
static int runAllTests(TestResult &result)
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Camera camera1(pose1, K)
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
The most common 5DOF 3D->2D calibration.
static double range2(const Camera &camera, const Camera2 &camera2)
static const CalibratedCamera camera3(pose1)
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
static const Unit3 point1_inf(-0.16,-0.16, -1.0)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Unit3 point2_inf(-0.16, 0.16, -1.0)
static Point2 projectInfinity3(const Pose3 &pose, const Unit3 &point3D, const Cal3_S2 &cal)
static Point3 backproject(const Pose3 &pose, const Point2 &point, const double &depth)
static const Cal3Bundler K2(625, 1e-3, 1e-3)
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
const Cal3_S2 cal(focalLength, focalLength, 0.0, principalPoint.x(), principalPoint.y())
static const Unit3 point3_inf(0.16, 0.16, -1.0)
Some functions to compute numerical derivatives.
static Point2 project3(const Pose3 &pose, const Point3 &point, const Cal3_S2 &cal)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
static double range0(const Camera &camera, const Point3 &point)
const Pose3 & pose() const
return pose
Base class for all pinhole cameras.
Calibration used by Bundler.
PinholeCamera< Cal3_S2 > Camera
TEST(PinholeCamera, constructor)
static const Point3 point3(0.08, 0.08, 0.0)
PinholeCamera< Cal3Bundler > Camera2
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
static const Cal3_S2 K(625, 625, 0, 0, 0)
static const Point3 point1(-0.08,-0.08, 0.0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Pose3_ getPose(const Expression< PinholeCamera< CALIBRATION > > &cam)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Matrix< Scalar, Dynamic, Dynamic > C
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Camera camera(pose, K)
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 origin
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static Point2 project4(const Camera &camera, const Point3 &point)
static const Point3 point2(-0.08, 0.08, 0.0)
The most common 5DOF 3D->2D calibration.
static double range3(const Camera &camera, const CalibratedCamera &camera3)
Represents a 3D point on a unit sphere.
static double range1(const Camera &camera, const Pose3 &pose)
static const Unit3 point4_inf(0.16,-0.16, -1.0)
static const Camera2 camera2(pose1, K2)
double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian< 1, 3 > H1, OptionalJacobian< 1, 3 > H2)
distance between two points
static const Point3 point4(0.08,-0.08, 0.0)
Calibration used by Bundler.
Rot2 R(Rot2::fromAngle(0.1))
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:06