aboutsummaryrefslogtreecommitdiffhomepage
diff options
context:
space:
mode:
authorGravatar Gael Guennebaud <g.gael@free.fr>2008-08-30 12:42:06 +0000
committerGravatar Gael Guennebaud <g.gael@free.fr>2008-08-30 12:42:06 +0000
commit236b7a545d139a32b6cd0984044ce91d737094a5 (patch)
tree4392f9104cdaace755cc8a7c56cf70a01f36a891
parent9e7a9cde14fc8d20e9aaf41619a23dfb420fc973 (diff)
update Transform::inverse() to take an optional argument stating whether the transformation is:
NonAffine, Affine (default), contains NoShear, contains NoScaling that allows significant speed improvements. If you like it, this concept could be applied to Transform::extractRotation (or to a more advanced decomposition function) and to Hyperplane::transformed() and maybe to some other places... e.g., I think a Transform::normalMatrix() function would not harm and warn user that the transformation of normals is not that trivial (I saw this mistake much too often)
-rw-r--r--Eigen/Geometry1
-rw-r--r--Eigen/src/Geometry/Scaling.h9
-rw-r--r--Eigen/src/Geometry/Transform.h109
-rw-r--r--Eigen/src/Geometry/Translation.h7
-rw-r--r--doc/QuickStartGuide.dox65
-rw-r--r--test/geometry.cpp14
6 files changed, 178 insertions, 27 deletions
diff --git a/Eigen/Geometry b/Eigen/Geometry
index b5037306d..ab3a9b9d6 100644
--- a/Eigen/Geometry
+++ b/Eigen/Geometry
@@ -25,6 +25,7 @@ namespace Eigen {
// the Geometry module use cwiseCos and cwiseSin which are defined in the Array module
#include "src/Array/CwiseOperators.h"
#include "src/Array/Functors.h"
+#include "src/Array/PartialRedux.h"
#include "src/Geometry/OrthoMethods.h"
#include "src/Geometry/Quaternion.h"
diff --git a/Eigen/src/Geometry/Scaling.h b/Eigen/src/Geometry/Scaling.h
index fcf1c0437..73938ac8b 100644
--- a/Eigen/src/Geometry/Scaling.h
+++ b/Eigen/src/Geometry/Scaling.h
@@ -35,18 +35,23 @@
* \param _Dim the dimension of the space, can be a compile time value or Dynamic
*
*
- * \sa class Translate, class Transform
+ * \sa class Translation, class Transform
*/
template<typename _Scalar, int _Dim>
class Scaling
{
public:
+ /** dimension of the space */
enum { Dim = _Dim };
/** the scalar type of the coefficients */
typedef _Scalar Scalar;
- typedef Matrix<Scalar,Dim,Dim> LinearMatrixType;
+ /** corresponding vector type */
typedef Matrix<Scalar,Dim,1> VectorType;
+ /** corresponding linear transformation matrix type */
+ typedef Matrix<Scalar,Dim,Dim> LinearMatrixType;
+ /** corresponding translation type */
typedef Translation<Scalar,Dim> TranslationType;
+ /** corresponding affine transformation type */
typedef Transform<Scalar,Dim> TransformType;
protected:
diff --git a/Eigen/src/Geometry/Transform.h b/Eigen/src/Geometry/Transform.h
index f32577e88..fd5fd66ba 100644
--- a/Eigen/src/Geometry/Transform.h
+++ b/Eigen/src/Geometry/Transform.h
@@ -25,6 +25,14 @@
#ifndef EIGEN_TRANSFORM_H
#define EIGEN_TRANSFORM_H
+/** Represents some traits of a transformation */
+enum TransformationKnowledge {
+ NoScaling, ///< the transformation is a concatenation of translations, rotations
+ NoShear, ///< the transformation is a concatenation of translations, rotations and scalings
+ GenericAffine, ///< the transformation is affine (linear transformation + translation)
+ NonAffine ///< the transformation might not be affine
+};
+
// Note that we have to pass Dim and HDim because it is not allowed to use a template
// parameter to define a template specialization. To be more precise, in the following
// specializations, it is not allowed to use Dim+1 instead of HDim.
@@ -73,7 +81,9 @@ public:
typedef Matrix<Scalar,Dim,1> VectorType;
/** type of a read/write reference to the translation part of the rotation */
typedef Block<MatrixType,Dim,1> TranslationPart;
+ /** corresponding translation type */
typedef Translation<Scalar,Dim> TranslationType;
+ /** corresponding scaling transformation type */
typedef Scaling<Scalar,Dim> ScalingType;
protected:
@@ -193,8 +203,11 @@ public:
Transform& shear(Scalar sx, Scalar sy);
Transform& preshear(Scalar sx, Scalar sy);
+ inline Transform& operator=(const TranslationType& t);
inline Transform& operator*=(const TranslationType& t) { return translate(t.vector()); }
inline Transform operator*(const TranslationType& t) const;
+
+ inline Transform& operator=(const ScalingType& t);
inline Transform& operator*=(const ScalingType& s) { return scale(s.coeffs()); }
inline Transform operator*(const ScalingType& s) const;
friend inline Transform operator*(const LinearMatrixType& mat, const Transform& t)
@@ -212,9 +225,7 @@ public:
Transform& fromPositionOrientationScale(const MatrixBase<PositionDerived> &position,
const OrientationType& orientation, const MatrixBase<ScaleDerived> &scale);
- /** \sa MatrixBase::inverse() */
- const MatrixType inverse() const
- { return m_matrix.inverse(); }
+ inline const MatrixType inverse(TransformationKnowledge knowledge = GenericAffine) const;
const Scalar* data() const { return m_matrix.data(); }
Scalar* data() { return m_matrix.data(); }
@@ -232,6 +243,10 @@ typedef Transform<double,2> Transform2d;
/** \ingroup GeometryModule */
typedef Transform<double,3> Transform3d;
+/**************************
+*** Optional QT support ***
+**************************/
+
#ifdef EIGEN_QT_SUPPORT
/** Initialises \c *this from a QMatrix assuming the dimension is 2.
*
@@ -271,6 +286,10 @@ QMatrix Transform<Scalar,Dim>::toQMatrix(void) const
}
#endif
+/*********************
+*** Procedural API ***
+*********************/
+
/** Applies on the right the non uniform scale transformation represented
* by the vector \a other to \c *this and returns a reference to \c *this.
* \sa prescale()
@@ -399,6 +418,18 @@ Transform<Scalar,Dim>::preshear(Scalar sx, Scalar sy)
return *this;
}
+/******************************************************
+*** Scaling, Translation and Rotation compatibility ***
+******************************************************/
+
+template<typename Scalar, int Dim>
+inline Transform<Scalar,Dim>& Transform<Scalar,Dim>::operator=(const TranslationType& t)
+{
+ setIdentity();
+ translation() = t.vector();
+ return *this;
+}
+
template<typename Scalar, int Dim>
inline Transform<Scalar,Dim> Transform<Scalar,Dim>::operator*(const TranslationType& t) const
{
@@ -408,6 +439,15 @@ inline Transform<Scalar,Dim> Transform<Scalar,Dim>::operator*(const TranslationT
}
template<typename Scalar, int Dim>
+inline Transform<Scalar,Dim>& Transform<Scalar,Dim>::operator=(const ScalingType& s)
+{
+ m_matrix.setZero();
+ linear().diagonal() = s.coeffs();
+ m_matrix(Dim,Dim) = Scalar(1);
+ return *this;
+}
+
+template<typename Scalar, int Dim>
inline Transform<Scalar,Dim> Transform<Scalar,Dim>::operator*(const ScalingType& s) const
{
Transform res = *this;
@@ -415,6 +455,10 @@ inline Transform<Scalar,Dim> Transform<Scalar,Dim>::operator*(const ScalingType&
return res;
}
+/***************************
+*** Specialial functions ***
+***************************/
+
/** \returns the rotation part of the transformation using a QR decomposition.
* \sa extractRotationNoShear(), class QR
*/
@@ -454,6 +498,65 @@ Transform<Scalar,Dim>::fromPositionOrientationScale(const MatrixBase<PositionDer
return *this;
}
+/** \returns the inverse transformation matrix according to some given knowledge
+ * on \c *this.
+ *
+ * \param knowledge allozs to optimize the inversion process when the transformion
+ * is known to be not a general transformation. The possible values are:
+ * - NonAffine if the transformation is not necessarily affines, i.e., if the
+ * last row is not guaranteed to be [0 ... 0 1]
+ * - GenericAffine is the default, the last row is assumed to be [0 ... 0 1]
+ * - NoShear if the transformation is only a concatenations of translations,
+ * rotations, and scalings.
+ * - NoScaling if the transformation is only a concatenations of translations
+ * and rotations.
+ *
+ * \sa MatrixBase::inverse()
+ */
+template<typename Scalar, int Dim>
+inline const typename Transform<Scalar,Dim>::MatrixType
+Transform<Scalar,Dim>::inverse(TransformationKnowledge knowledge) const
+{
+ if (knowledge == NonAffine)
+ {
+ return m_matrix.inverse();
+ }
+ else
+ {
+ MatrixType res;
+ if (knowledge == GenericAffine)
+ {
+ res.template corner<Dim,Dim>(TopLeft) = linear().inverse();
+ }
+ else if (knowledge == NoShear)
+ {
+ // extract linear = rotation * scaling
+ // then inv(linear) = inv(scaling) * inv(rotation)
+ // = inv(scaling) * trans(rotation)
+ // = inv(scaling) * trans(inv(scaling)) * trans(A)
+ // = inv(scaling) * inv(scaling) * trans(A)
+ // = inv(scaling)^2 * trans(A)
+ // = scaling^-2 * trans(A)
+ // with scaling[i] = A.col(i).norm()
+ VectorType invScaling2 = linear().colwise().norm2().cwise().inverse();
+ res.template corner<Dim,Dim>(TopLeft) = (invScaling2.asDiagonal() * linear().transpose()).lazy();
+ }
+ else if (knowledge == NoScaling)
+ {
+ res.template corner<Dim,Dim>(TopLeft) = linear().transpose();
+ }
+ else
+ {
+ ei_assert("invalid knowledge value in Transform::inverse()");
+ }
+ // translation and remaining parts
+ res.template corner<Dim,1>(TopRight) = - res.template corner<Dim,Dim>(TopLeft) * translation();
+ res.template corner<1,Dim>(BottomLeft).setZero();
+ res.coeffRef(Dim,Dim) = Scalar(1);
+ return res;
+ }
+}
+
/***********************************
*** Specializations of operator* ***
***********************************/
diff --git a/Eigen/src/Geometry/Translation.h b/Eigen/src/Geometry/Translation.h
index ad63b835f..b65aca9eb 100644
--- a/Eigen/src/Geometry/Translation.h
+++ b/Eigen/src/Geometry/Translation.h
@@ -41,12 +41,17 @@ template<typename _Scalar, int _Dim>
class Translation
{
public:
+ /** dimension of the space */
enum { Dim = _Dim };
/** the scalar type of the coefficients */
typedef _Scalar Scalar;
- typedef Matrix<Scalar,Dim,Dim> LinearMatrixType;
+ /** corresponding vector type */
typedef Matrix<Scalar,Dim,1> VectorType;
+ /** corresponding linear transformation matrix type */
+ typedef Matrix<Scalar,Dim,Dim> LinearMatrixType;
+ /** corresponding scaling transformation type */
typedef Scaling<Scalar,Dim> ScalingType;
+ /** corresponding affine transformation type */
typedef Transform<Scalar,Dim> TransformType;
protected:
diff --git a/doc/QuickStartGuide.dox b/doc/QuickStartGuide.dox
index 62be8ec21..cf37f02be 100644
--- a/doc/QuickStartGuide.dox
+++ b/doc/QuickStartGuide.dox
@@ -569,8 +569,8 @@ m = AngleAxisf(angle1, Vector3f::UnitZ())
<a href="#" class="top">top</a>\section TutorialGeoTransformation Affine transformations
In Eigen we have chosen to not distinghish between points and vectors such that all points are
-actually represented by displacement vector from the origine (pt \~ pt-0). With that in mind,
-real points and vector distinguish when the rotation is applied.
+actually represented by displacement vectors from the origine ( \f$ \mathbf{p} \equiv \mathbf{p}-0 \f$ ).
+With that in mind, real points and vector distinguish when the rotation is applied.
<table class="tutorial_code">
<tr><td></td><td>\b 3D </td><td>\b 2D </td></tr>
<tr><td>Creation \n <span class="note">rot2D can also be an angle in radian</span></td><td>\code
@@ -606,6 +606,17 @@ aux.linear().corner<2,2>(TopLeft) = t.linear();
aux.translation().start<2>() = t.translation();
glLoadMatrixf(aux.data());\endcode</td></tr>
<tr><td colspan="3">\b Component \b accessors</td></tr>
+<tr><td>full read-write access to the internal matrix</td><td>\code
+t.matrix() = mat4x4;
+mat4x4 = t.matrix();
+\endcode</td><td>\code
+t.matrix() = mat3x3;
+mat3x3 = t.matrix();
+\endcode</td></tr>
+<tr><td>coefficient accessors</td><td colspan="2">\code
+t(i,j) = scalar; <=> t.matrix()(i,j) = scalar;
+scalar = t(i,j); <=> scalar = t.matrix()(i,j);
+\endcode</td></tr>
<tr><td>translation part</td><td>\code
t.translation() = vec3;
vec3 = t.translation();
@@ -620,36 +631,50 @@ mat3x3 = t.linear();
t.linear() = mat2x2;
mat2x2 = t.linear();
\endcode</td></tr>
-<tr><td colspan="3">\b Editing \b shortcuts</td></tr>
+</table>
+
+\b Transformation \b creation \n
+Eigen's geometry module offer two different ways to build and update transformation objects.
+<table class="tutorial_code">
+<tr><td></td><td>\b procedurale \b API </td><td>\b natural \b API </td></tr>
<tr><td>Applies a translation</td><td>\code
-t.translate(Vector3f(tx, ty, tz));
-t.pretranslate(Vector3f(tx, ty, tz));
+t.translate(Vector3(tx, ty, ...));
+t.pretranslate(Vector3(tx, ty, ...));
\endcode</td><td>\code
-t.translate(Vector2f(tx, ty));
-t.pretranslate(Vector2f(tx, ty));
+t *= Translation(tx, ty, ...);
+t = Translation(tx, ty, ...) * t;
\endcode</td></tr>
-<tr><td>Applies a rotation \n <span class="note">rot2D can also be an angle in radian</span></td><td>\code
-t.rotate(rot3D);
-t.prerotate(rot3D);
+<tr><td>Applies a rotation \n <span class="note">In 2D, any_rotation can also be \n an angle in radian</span></td><td>\code
+t.rotate(any_rotation);
+t.prerotate(any_rotation);
\endcode</td><td>\code
-t.rotate(rot2D);
-t.prerotate(rot2D);
+t *= any_rotation;
+t = any_rotation * t;
\endcode</td></tr>
<tr><td>Applies a scaling</td><td>\code
-t.scale(Vector3f(sx, sy, sz));
-t.scale(Vector3f::Constant(s));
-t.prescale(Vector3f(sx, sy, sz));
+t.scale(Vector(sx, sy, ...));
+t.scale(Vector::Constant(s));
+t.prescale(Vector3f(sx, sy, ...));
\endcode</td><td>\code
-t.scale(Vector2f(sx, sy));
-t.scale(Vector2f::Constant(s));
-t.prescale(Vector2f(sx, sy));
+t *= Scaling(sx, sy, ...);
+t *= Scaling(s);
+t = Scaling(sx, sy, ...) * t;
\endcode</td></tr>
-<tr><td>Applies a shear transformation \n(2D only)</td><td></td><td>\code
+<tr><td>Applies a shear transformation \n ( \b 2D \b only ! )</td><td>\code
t.shear(sx,sy);
t.preshear(sx,sy);
-\endcode</td></tr>
+\endcode</td><td></td></tr>
</table>
+Note that in both API, any many transformations can be concatenated in a single lines as shown in the two following equivalent examples:
+<table class="tutorial_code">
+<tr><td>\code
+t.pretranslate(..).rotate(..).translate(..).scale(..);
+\endcode</td></tr>
+<tr><td>\code
+t = Translation(..) * t * RotationType(..) * Translation(..) * Scaling(..);
+\endcode</td></tr>
+</table>
*/
diff --git a/test/geometry.cpp b/test/geometry.cpp
index af9accb63..7b9784134 100644
--- a/test/geometry.cpp
+++ b/test/geometry.cpp
@@ -219,12 +219,24 @@ template<typename Scalar> void geometry(void)
t0.setIdentity();
t0.scale(v0);
VERIFY_IS_APPROX(t0 * v1, Scaling3(v0) * v1);
+
+ // test transform inversion
+ t0.setIdentity();
+ t0.translate(v0);
+ t0.linear().setRandom();
+ VERIFY_IS_APPROX(t0.inverse(GenericAffine), t0.matrix().inverse());
+ t0.setIdentity();
+ t0.translate(v0).rotate(q1).scale(v1);
+ VERIFY_IS_APPROX(t0.inverse(NoShear), t0.matrix().inverse());
+ t0.setIdentity();
+ t0.translate(v0).rotate(q1);
+ VERIFY_IS_APPROX(t0.inverse(NoScaling), t0.matrix().inverse());
}
void test_geometry()
{
for(int i = 0; i < g_repeat; i++) {
CALL_SUBTEST( geometry<float>() );
-// CALL_SUBTEST( geometry<double>() );
+ CALL_SUBTEST( geometry<double>() );
}
}