change: formatting

release/4.3a0
zhaoyang 2015-06-25 09:44:18 -04:00
parent d8f0a35a9a
commit e45f5faea1
2 changed files with 23 additions and 23 deletions

View File

@ -44,17 +44,17 @@ public:
/// Default constructor
OrientedPlane3() :
n_(), d_(0.0) {
n_(), d_(0.0) {
}
/// Construct from a Unit3 and a distance
OrientedPlane3(const Unit3& s, double d) :
n_(s), d_(d) {
n_(s), d_(d) {
}
/// Construct from a vector of plane coefficients
OrientedPlane3(const Vector4& vec) :
n_(vec(0), vec(1), vec(2)), d_(vec(3)) {
n_(vec(0), vec(1), vec(2)), d_(vec(3)) {
}
/// Construct from four numbers of plane coeffcients (a, b, c, d)
@ -85,8 +85,8 @@ public:
* @return the transformed plane
*/
OrientedPlane3 transform(const Pose3& xr,
OptionalJacobian<3, 3> Hp = boost::none,
OptionalJacobian<3, 6> Hr = boost::none) const;
OptionalJacobian<3, 3> Hp = boost::none,
OptionalJacobian<3, 6> Hr = boost::none) const;
/**
* @ deprecated the static method has wrong Jacobian order,
@ -143,11 +143,11 @@ public:
};
template<> struct traits<OrientedPlane3> : public internal::Manifold<
OrientedPlane3> {
OrientedPlane3> {
};
template<> struct traits<const OrientedPlane3> : public internal::Manifold<
OrientedPlane3> {
OrientedPlane3> {
};
} // namespace gtsam

View File

@ -51,11 +51,11 @@ TEST (OrientedPlane3, getMethods) {
//*******************************************************************************
OrientedPlane3 Transform_(const OrientedPlane3& plane, const Pose3& xr) {
return OrientedPlane3::Transform(plane, xr);
return OrientedPlane3::Transform(plane, xr);
}
OrientedPlane3 transform_(const OrientedPlane3& plane, const Pose3& xr) {
return plane.transform(xr);
return plane.transform(xr);
}
TEST (OrientedPlane3, transform) {
@ -72,26 +72,26 @@ TEST (OrientedPlane3, transform) {
// Test the jacobians of transform
Matrix actualH1, expectedH1, actualH2, expectedH2;
{
OrientedPlane3::Transform(plane, pose, actualH1, none);
// because the Transform class uses a wrong order of Jacobians in interface
expectedH1 = numericalDerivative22(Transform_, plane, pose);
EXPECT(assert_equal(expectedH1, actualH1, 1e-9));
OrientedPlane3::Transform(plane, pose, none, actualH2);
expectedH2 = numericalDerivative21(Transform_, plane, pose);
EXPECT(assert_equal(expectedH2, actualH2, 1e-9));
// because the Transform class uses a wrong order of Jacobians in interface
OrientedPlane3::Transform(plane, pose, actualH1, none);
expectedH1 = numericalDerivative22(Transform_, plane, pose);
EXPECT(assert_equal(expectedH1, actualH1, 1e-9));
OrientedPlane3::Transform(plane, pose, none, actualH2);
expectedH2 = numericalDerivative21(Transform_, plane, pose);
EXPECT(assert_equal(expectedH2, actualH2, 1e-9));
}
{
plane.transform(pose, actualH1, none);
expectedH1 = numericalDerivative21(transform_, plane, pose);
EXPECT(assert_equal(expectedH1, actualH1, 1e-9));
plane.transform(pose, none, actualH2);
expectedH2 = numericalDerivative22(Transform_, plane, pose);
EXPECT(assert_equal(expectedH2, actualH2, 1e-9));
plane.transform(pose, actualH1, none);
expectedH1 = numericalDerivative21(transform_, plane, pose);
EXPECT(assert_equal(expectedH1, actualH1, 1e-9));
plane.transform(pose, none, actualH2);
expectedH2 = numericalDerivative22(Transform_, plane, pose);
EXPECT(assert_equal(expectedH2, actualH2, 1e-9));
}
}
//*******************************************************************************
// Returns a random vector -- copied from testUnit3.cpp
// Returns a any size random vector
inline static Vector randomVector(const Vector& minLimits,
const Vector& maxLimits) {