16 using namespace gtsam;
30 EssentialMatrix actual(trueRotation, trueDirection),
expected(trueRotation, trueDirection);
41 Matrix expectedH1 = numericalDerivative11<EssentialMatrix, Rot3>(
42 boost::bind(EssentialMatrix::FromRotationAndDirection, _1,
trueDirection, boost::none,
47 Matrix expectedH2 = numericalDerivative11<EssentialMatrix, Unit3>(
48 boost::bind(EssentialMatrix::FromRotationAndDirection,
trueRotation, _1, boost::none,
80 d << 0.1, 0.2, 0.3, 0, 0, 0;
82 EssentialMatrix::FromPose3(pose.
retract(d)));
110 d << 0.1, 0.2, 0.3, 0.4, 0.5;
122 Rot3 aRb2 = Rot3::Yaw(
M_PI / 3.0) * Rot3::Pitch(M_PI_4)
123 * Rot3::Roll(
M_PI / 6.0);
124 Point3 aTb2(19.2, 3.7, 5.9);
161 bodyE.rotate(cRb, actH1, actH2);
162 }
catch (exception&
e) {
175 Matrix expectedH = numericalDerivative11<EssentialMatrix, Pose3>(
176 boost::bind(EssentialMatrix::FromPose3, _1, boost::none),
pose);
188 Matrix expectedH = numericalDerivative11<EssentialMatrix, Pose3>(
189 boost::bind(EssentialMatrix::FromPose3, _1, boost::none),
pose);
229 Unit3 e1(-
U(0, 2), -
U(1, 2), -
U(2, 2));
240 Unit3 e2(
V(0, 2),
V(1, 2),
V(2, 2));
GTSAM_EXPORT Point3 transformTo(const Point3 &p, OptionalJacobian< 3, 5 > DE=boost::none, OptionalJacobian< 3, 3 > Dpoint=boost::none) const
takes point in world coordinates and transforms it to pose with |t|==1
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
const Matrix3 & matrix() const
Return 3*3 matrix representation.
GTSAM_EXPORT Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H=boost::none) const
The retract function.
gtsam::Point3 bX(1, 0, 0)
gtsam::Point3 bY(0, 1, 0)
Vector5 localCoordinates(const EssentialMatrix &other) const
Compute the coordinates in the tangent space.
EssentialMatrix trueE(trueRotation, trueDirection)
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
Point3 trueTranslation(0.1, 0, 0)
Rot3 inverse() const
inverse of a rotation
Represents a 3D point on a unit sphere.
bool equality(const T &input=T())
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
GTSAM_EXPORT EssentialMatrix rotate(const Rot3 &cRb, OptionalJacobian< 5, 5 > HE=boost::none, OptionalJacobian< 5, 3 > HR=boost::none) const
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
#define EXPECT(condition)
P rotate(const T &r, const P &pt)
EssentialMatrix rotate_(const EssentialMatrix &E, const Rot3 &cRb)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Point3 bZ(0, 0, 1)
static std::stringstream ss
Calibrated camera for which only pose is unknown.
Unit3 trueDirection(trueTranslation)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
Point3 transform_to_(const EssentialMatrix &E, const Point3 &point)
Unit3 epipole_b() const
Return epipole in image_b, as Unit3 to allow for infinity.
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
const Unit3 & epipole_a() const
Return epipole in image_a , as Unit3 to allow for infinity.
#define GTSAM_CONCEPT_TESTABLE_INST(T)
TEST(EssentialMatrix, equality)