diff --git a/gtsam/geometry/OrientedPlane3.cpp b/gtsam/geometry/OrientedPlane3.cpp index f40ad1c49..51d7a903b 100644 --- a/gtsam/geometry/OrientedPlane3.cpp +++ b/gtsam/geometry/OrientedPlane3.cpp @@ -13,6 +13,7 @@ * @file OrientedPlane3.cpp * @date Dec 19, 2013 * @author Alex Trevor + * @author Zhaoyang Lv * @brief A plane, represented by a normal direction and perpendicular distance */ @@ -25,7 +26,6 @@ using namespace std; namespace gtsam { /* ************************************************************************* */ -/// The print fuction void OrientedPlane3::print(const string& s) const { Vector4 coeffs = planeCoefficients(); cout << s << " : " << coeffs << endl; @@ -39,22 +39,19 @@ OrientedPlane3 OrientedPlane3::Transform(const OrientedPlane3& plane, Matrix22 n_hp; Unit3 n_rotated = xr.rotation().unrotate(plane.n_, n_hr, n_hp); - Vector3 n_unit = plane.n_.unitVector(); Vector3 unit_vec = n_rotated.unitVector(); - double pred_d = n_unit.dot(xr.translation().vector()) + plane.d_; + double pred_d = plane.n_.unitVector().dot(xr.translation().vector()) + plane.d_; if (Hr) { *Hr = zeros(3, 6); - (*Hr).block<2, 3>(0, 0) = n_hr; - (*Hr).block<1, 3>(2, 3) = unit_vec; + Hr->block<2, 3>(0, 0) = n_hr; + Hr->block<1, 3>(2, 3) = unit_vec; } if (Hp) { - Vector3 xrp = xr.translation().vector(); - Matrix32 n_basis = plane.n_.basis(); - Vector2 hpp = n_basis.transpose() * xrp; + Vector2 hpp = plane.n_.basis().transpose() * xr.translation().vector(); *Hp = zeros(3, 3); - (*Hp).block<2, 2>(0, 0) = n_hp; - (*Hp).block<1, 2>(2, 0) = hpp; + Hp->block<2, 2>(0, 0) = n_hp; + Hp->block<1, 2>(2, 0) = hpp; (*Hp)(2, 2) = 1; } @@ -65,14 +62,11 @@ OrientedPlane3 OrientedPlane3::Transform(const OrientedPlane3& plane, Vector3 OrientedPlane3::error(const OrientedPlane3& plane) const { Vector2 n_error = -n_.localCoordinates(plane.n_); double d_error = d_ - plane.d_; - Vector3 e; - e << n_error(0), n_error(1), d_error; - return (e); + return Vector3(n_error(0), n_error(1), d_error); } /* ************************************************************************* */ OrientedPlane3 OrientedPlane3::retract(const Vector3& v) const { - // Retract the Unit3 Vector2 n_v(v(0), v(1)); Unit3 n_retracted = n_.retract(n_v); double d_retracted = d_ + v(2); @@ -84,8 +78,7 @@ Vector3 OrientedPlane3::localCoordinates(const OrientedPlane3& y) const { Vector2 n_local = n_.localCoordinates(y.n_); double d_local = d_ - y.d_; Vector3 e; - e << n_local(0), n_local(1), -d_local; - return e; + return Vector3(n_local(0), n_local(1), -d_local); } } diff --git a/gtsam/geometry/OrientedPlane3.h b/gtsam/geometry/OrientedPlane3.h index a6fee420b..55e7188af 100644 --- a/gtsam/geometry/OrientedPlane3.h +++ b/gtsam/geometry/OrientedPlane3.h @@ -14,6 +14,7 @@ * @date Dec 19, 2013 * @author Alex Trevor * @author Frank Dellaert + * @author Zhaoyang Lv * @brief An infinite plane, represented by a normal direction and perpendicular distance */ @@ -37,6 +38,7 @@ public: enum { dimension = 3 }; + /// @name Constructors /// @{ @@ -74,10 +76,12 @@ public: return (n_.equals(s.n_, tol) && (fabs(d_ - s.d_) < tol)); } + /// @} + /** Transforms a plane to the specified pose * @param The raw plane * @param A transformation in current coordiante - * @param Hr optional jacobian wrpt incremental Pose + * @param Hr optional jacobian wrpt the pose transformation * @param Hp optional Jacobian wrpt the destination plane */ static OrientedPlane3 Transform(const OrientedPlane3& plane, diff --git a/gtsam/geometry/tests/testOrientedPlane3.cpp b/gtsam/geometry/tests/testOrientedPlane3.cpp index 1fd9d9d6b..127bc3d0c 100644 --- a/gtsam/geometry/tests/testOrientedPlane3.cpp +++ b/gtsam/geometry/tests/testOrientedPlane3.cpp @@ -13,6 +13,7 @@ * @file testOrientedPlane3.cpp * @date Dec 19, 2012 * @author Alex Trevor + * @author Zhaoyang Lv * @brief Tests the OrientedPlane3 class */