Made it more clear that Rotation constructor takes columns.
parent
c394f9a601
commit
f54861f851
|
|
@ -79,12 +79,12 @@ namespace gtsam {
|
||||||
Rot3();
|
Rot3();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Constructor from columns
|
* Constructor from *columns*
|
||||||
* @param r1 X-axis of rotated frame
|
* @param r1 X-axis of rotated frame
|
||||||
* @param r2 Y-axis of rotated frame
|
* @param r2 Y-axis of rotated frame
|
||||||
* @param r3 Z-axis of rotated frame
|
* @param r3 Z-axis of rotated frame
|
||||||
*/
|
*/
|
||||||
Rot3(const Point3& r1, const Point3& r2, const Point3& r3);
|
Rot3(const Point3& col1, const Point3& col2, const Point3& col3);
|
||||||
|
|
||||||
/** constructor from a rotation matrix, as doubles in *row-major* order !!! */
|
/** constructor from a rotation matrix, as doubles in *row-major* order !!! */
|
||||||
Rot3(double R11, double R12, double R13,
|
Rot3(double R11, double R12, double R13,
|
||||||
|
|
@ -97,9 +97,6 @@ namespace gtsam {
|
||||||
/** constructor from a rotation matrix */
|
/** constructor from a rotation matrix */
|
||||||
Rot3(const Matrix& R);
|
Rot3(const Matrix& R);
|
||||||
|
|
||||||
// /** constructor from a fixed size rotation matrix */
|
|
||||||
// Rot3(const Matrix3& R);
|
|
||||||
|
|
||||||
/** Constructor from a quaternion. This can also be called using a plain
|
/** Constructor from a quaternion. This can also be called using a plain
|
||||||
* Vector, due to implicit conversion from Vector to Quaternion
|
* Vector, due to implicit conversion from Vector to Quaternion
|
||||||
* @param q The quaternion
|
* @param q The quaternion
|
||||||
|
|
|
||||||
|
|
@ -36,10 +36,10 @@ static const Matrix3 I3 = Matrix3::Identity();
|
||||||
Rot3::Rot3() : rot_(Matrix3::Identity()) {}
|
Rot3::Rot3() : rot_(Matrix3::Identity()) {}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Rot3::Rot3(const Point3& r1, const Point3& r2, const Point3& r3) {
|
Rot3::Rot3(const Point3& col1, const Point3& col2, const Point3& col3) {
|
||||||
rot_.col(0) = r1.vector();
|
rot_.col(0) = col1.vector();
|
||||||
rot_.col(1) = r2.vector();
|
rot_.col(1) = col2.vector();
|
||||||
rot_.col(2) = r3.vector();
|
rot_.col(2) = col3.vector();
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
||||||
|
|
@ -32,11 +32,11 @@ namespace gtsam {
|
||||||
Rot3::Rot3() : quaternion_(Quaternion::Identity()) {}
|
Rot3::Rot3() : quaternion_(Quaternion::Identity()) {}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Rot3::Rot3(const Point3& r1, const Point3& r2, const Point3& r3) :
|
Rot3::Rot3(const Point3& col1, const Point3& col2, const Point3& col3) :
|
||||||
quaternion_((Eigen::Matrix3d() <<
|
quaternion_((Eigen::Matrix3d() <<
|
||||||
r1.x(), r2.x(), r3.x(),
|
col1.x(), col2.x(), col3.x(),
|
||||||
r1.y(), r2.y(), r3.y(),
|
col1.y(), col2.y(), col3.y(),
|
||||||
r1.z(), r2.z(), r3.z()).finished()) {}
|
col1.z(), col2.z(), col3.z()).finished()) {}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Rot3::Rot3(double R11, double R12, double R13,
|
Rot3::Rot3(double R11, double R12, double R13,
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue