Closest
parent
6eefc56e17
commit
6c00ff163f
|
@ -52,7 +52,6 @@ Pose3 Pose3::inverse() const {
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// Calculate Adjoint map
|
// Calculate Adjoint map
|
||||||
// Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
|
// Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
|
||||||
// Experimental - unit tests of derivatives based on it do not check out yet
|
|
||||||
Matrix6 Pose3::AdjointMap() const {
|
Matrix6 Pose3::AdjointMap() const {
|
||||||
const Matrix3 R = R_.matrix();
|
const Matrix3 R = R_.matrix();
|
||||||
Matrix3 A = skewSymmetric(t_.x(), t_.y(), t_.z()) * R;
|
Matrix3 A = skewSymmetric(t_.x(), t_.y(), t_.z()) * R;
|
||||||
|
@ -418,24 +417,11 @@ boost::optional<Pose3> Pose3::Align(const std::vector<Point3Pair>& abPointPairs)
|
||||||
for(const Point3Pair& abPair: abPointPairs) {
|
for(const Point3Pair& abPair: abPointPairs) {
|
||||||
Point3 da = abPair.first - aCentroid;
|
Point3 da = abPair.first - aCentroid;
|
||||||
Point3 db = abPair.second - bCentroid;
|
Point3 db = abPair.second - bCentroid;
|
||||||
H += db * da.transpose();
|
H += da * db.transpose();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Compute SVD
|
// ClosestTo finds rotation matrix closest to H in Frobenius sense
|
||||||
Eigen::JacobiSVD<Matrix> svd(H, Eigen::ComputeThinU | Eigen::ComputeThinV);
|
Rot3 aRb = Rot3::ClosestTo(H);
|
||||||
Matrix U = svd.matrixU();
|
|
||||||
Vector S = svd.singularValues();
|
|
||||||
Matrix V = svd.matrixV();
|
|
||||||
|
|
||||||
// Check rank
|
|
||||||
if (S[1] < 1e-10)
|
|
||||||
return boost::none;
|
|
||||||
|
|
||||||
// Recover transform with correction from Eggert97machinevisionandapplications
|
|
||||||
Matrix3 UVtranspose = U * V.transpose();
|
|
||||||
Matrix3 detWeighting = I_3x3;
|
|
||||||
detWeighting(2, 2) = UVtranspose.determinant();
|
|
||||||
Rot3 aRb(Matrix(V * detWeighting * U.transpose()));
|
|
||||||
Point3 aTb = Point3(aCentroid) - aRb * Point3(bCentroid);
|
Point3 aTb = Point3(aCentroid) - aRb * Point3(bCentroid);
|
||||||
return Pose3(aRb, aTb);
|
return Pose3(aRb, aTb);
|
||||||
}
|
}
|
||||||
|
|
|
@ -228,6 +228,9 @@ namespace gtsam {
|
||||||
static Rot3 AlignTwoPairs(const Unit3& a_p, const Unit3& b_p, //
|
static Rot3 AlignTwoPairs(const Unit3& a_p, const Unit3& b_p, //
|
||||||
const Unit3& a_q, const Unit3& b_q);
|
const Unit3& a_q, const Unit3& b_q);
|
||||||
|
|
||||||
|
/// Static, named constructor that finds Rot3 element closest to M in Frobenius norm.
|
||||||
|
static Rot3 ClosestTo(const Matrix3& M) { return Rot3(SO3::ClosestTo(M)); }
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
/// @name Testable
|
/// @name Testable
|
||||||
/// @{
|
/// @{
|
||||||
|
|
|
@ -645,6 +645,23 @@ TEST(Rot3 , ChartDerivatives) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST(Rot3, ClosestTo) {
|
||||||
|
// Example top-left of SO(4) matrix not quite on SO(3) manifold
|
||||||
|
Matrix3 M;
|
||||||
|
M << 0.79067393, 0.6051136, -0.0930814, //
|
||||||
|
0.4155925, -0.64214347, -0.64324489, //
|
||||||
|
-0.44948549, 0.47046326, -0.75917576;
|
||||||
|
|
||||||
|
Matrix expected(3, 3);
|
||||||
|
expected << 0.790687, 0.605096, -0.0931312, //
|
||||||
|
0.415746, -0.642355, -0.643844, //
|
||||||
|
-0.449411, 0.47036, -0.759468;
|
||||||
|
|
||||||
|
auto actual = Rot3::ClosestTo(3*M);
|
||||||
|
EXPECT(assert_equal(expected, actual.matrix(), 1e-6));
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main() {
|
int main() {
|
||||||
TestResult tr;
|
TestResult tr;
|
||||||
|
|
|
@ -75,27 +75,15 @@ Values InitializePose3::normalizeRelaxedRotations(
|
||||||
const VectorValues& relaxedRot3) {
|
const VectorValues& relaxedRot3) {
|
||||||
gttic(InitializePose3_computeOrientationsChordal);
|
gttic(InitializePose3_computeOrientationsChordal);
|
||||||
|
|
||||||
Matrix ppm = Z_3x3; // plus plus minus
|
|
||||||
ppm(0,0) = 1; ppm(1,1) = 1; ppm(2,2) = -1;
|
|
||||||
|
|
||||||
Values validRot3;
|
Values validRot3;
|
||||||
for(const auto& it: relaxedRot3) {
|
for(const auto& it: relaxedRot3) {
|
||||||
Key key = it.first;
|
Key key = it.first;
|
||||||
if (key != kAnchorKey) {
|
if (key != kAnchorKey) {
|
||||||
Matrix3 R;
|
Matrix3 M;
|
||||||
R << Eigen::Map<const Matrix3>(it.second.data()); // Recover M from vectorized
|
M << Eigen::Map<const Matrix3>(it.second.data()); // Recover M from vectorized
|
||||||
|
|
||||||
// ClosestTo finds rotation matrix closest to H in Frobenius sense
|
// ClosestTo finds rotation matrix closest to H in Frobenius sense
|
||||||
// Rot3 initRot = Rot3::ClosestTo(M.transpose());
|
Rot3 initRot = Rot3::ClosestTo(M.transpose());
|
||||||
|
|
||||||
Matrix U, V; Vector s;
|
|
||||||
svd(R.transpose(), U, s, V);
|
|
||||||
Matrix3 normalizedRotMat = U * V.transpose();
|
|
||||||
|
|
||||||
if(normalizedRotMat.determinant() < 0)
|
|
||||||
normalizedRotMat = U * ppm * V.transpose();
|
|
||||||
|
|
||||||
Rot3 initRot = Rot3(normalizedRotMat);
|
|
||||||
validRot3.insert(key, initRot);
|
validRot3.insert(key, initRot);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue