Skip to content

Commit 65211f8

Browse files
committed
moving to squared sampson error
1 parent e9738c7 commit 65211f8

File tree

4 files changed

+14
-12
lines changed

4 files changed

+14
-12
lines changed

gtsam/geometry/EssentialMatrix.cpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -154,25 +154,27 @@ double EssentialMatrix::error(const Vector3& vA, const Vector3& vB,
154154
Matrix15 numerator_H;
155155
numerator_H << numerator_H_R, numerator_H_D;
156156

157-
*HE = numerator_H / denominator -
158-
algebraic_error * denominator_H / (denominator * denominator);
157+
*HE = 2 * sampson_error * (numerator_H / denominator -
158+
algebraic_error * denominator_H / (denominator * denominator));
159159
}
160160

161161
if (HvA){
162162
Matrix13 numerator_H_vA = vB.transpose() * matrix().transpose();
163163
Matrix13 denominator_H_vA = nA.transpose() * I * matrix().transpose() / denominator;
164164

165-
*HvA = numerator_H_vA / denominator - algebraic_error * denominator_H_vA / (denominator * denominator);
165+
*HvA = 2 * sampson_error * (numerator_H_vA / denominator -
166+
algebraic_error * denominator_H_vA / (denominator * denominator));
166167
}
167168

168169
if (HvB){
169170
Matrix13 numerator_H_vB = vA.transpose() * matrix();
170171
Matrix13 denominator_H_vB = nB.transpose() * I * matrix() / denominator;
171172

172-
*HvB = numerator_H_vB / denominator - algebraic_error * denominator_H_vB / (denominator * denominator);
173+
*HvB = 2 * sampson_error * (numerator_H_vB / denominator -
174+
algebraic_error * denominator_H_vB / (denominator * denominator));
173175
}
174176

175-
return sampson_error;
177+
return sampson_error * sampson_error;
176178
}
177179

178180
/* ************************************************************************* */

gtsam/geometry/EssentialMatrix.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -159,7 +159,7 @@ class EssentialMatrix {
159159
return E.rotate(cRb);
160160
}
161161

162-
/// epipolar error, sampson
162+
/// epipolar error, sampson squared
163163
GTSAM_EXPORT double error(const Vector3& vA, const Vector3& vB,
164164
OptionalJacobian<1, 5> HE = boost::none,
165165
OptionalJacobian<1, 3> HvA = boost::none,

gtsam/geometry/tests/testEssentialMatrix.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -254,8 +254,8 @@ TEST(EssentialMatrix, errorValue) {
254254
// algebraic error = 5
255255
// norm of line for b = 1
256256
// norm of line for a = 1
257-
// sampson error = 5 / sqrt(1^2 + 1^2)
258-
double expected = 3.535533906;
257+
// sampson error = 5^2 / 1^2 + 1^2
258+
double expected = 12.5;
259259

260260
// check the error
261261
double actual = trueE.error(a, b);

gtsam/slam/tests/testEssentialMatrixFactor.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ using namespace gtsam;
2424

2525
// Noise model for first type of factor is evaluating algebraic error
2626
noiseModel::Isotropic::shared_ptr model1 = noiseModel::Isotropic::Sigma(1,
27-
0.01);
27+
1e-4);
2828
// Noise model for second type of factor is evaluating pixel coordinates
2929
noiseModel::Unit::shared_ptr model2 = noiseModel::Unit::Create(2);
3030

@@ -196,9 +196,9 @@ TEST (EssentialMatrixFactor, minimization) {
196196
(Vector(5) << 0.1, -0.1, 0.1, 0.1, -0.1).finished());
197197
initial.insert(1, initialE);
198198
#if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
199-
EXPECT_DOUBLES_EQUAL(313.85, graph.error(initial), 1e-2);
199+
EXPECT_DOUBLES_EQUAL(59403.51, graph.error(initial), 1e-2);
200200
#else
201-
EXPECT_DOUBLES_EQUAL(639.84, graph.error(initial), 1e-2);
201+
EXPECT_DOUBLES_EQUAL(639.84, graph.error(initial), 1e-2); # TODO: redo this error
202202
#endif
203203

204204
// Optimize
@@ -410,7 +410,7 @@ TEST (EssentialMatrixFactor, extraMinimization) {
410410
initial.insert(1, initialE);
411411

412412
#if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
413-
EXPECT_DOUBLES_EQUAL(313.85, graph.error(initial), 1e-2);
413+
EXPECT_DOUBLES_EQUAL(59403.51, graph.error(initial), 1e-2);
414414
#else
415415
EXPECT_DOUBLES_EQUAL(639.84, graph.error(initial), 1e-2);
416416
#endif

0 commit comments

Comments
 (0)