fixed formatting issues
parent
e4a6a2a951
commit
ce85eecaff
|
|
@ -33,11 +33,10 @@ void OrientedPlane3::print(const std::string& s) const {
|
||||||
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
OrientedPlane3 OrientedPlane3::Transform (const gtsam::OrientedPlane3& plane,
|
OrientedPlane3 OrientedPlane3::Transform (const gtsam::OrientedPlane3& plane,
|
||||||
const gtsam::Pose3& xr,
|
const gtsam::Pose3& xr,
|
||||||
OptionalJacobian<3, 6> Hr,
|
OptionalJacobian<3, 6> Hr,
|
||||||
OptionalJacobian<3, 3> Hp)
|
OptionalJacobian<3, 3> Hp) {
|
||||||
{
|
|
||||||
Matrix n_hr;
|
Matrix n_hr;
|
||||||
Matrix n_hp;
|
Matrix n_hp;
|
||||||
Unit3 n_rotated = xr.rotation ().unrotate (plane.n_, n_hr, n_hp);
|
Unit3 n_rotated = xr.rotation ().unrotate (plane.n_, n_hr, n_hp);
|
||||||
|
|
@ -65,17 +64,17 @@ void OrientedPlane3::print(const std::string& s) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
return (transformed_plane);
|
return (transformed_plane);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Vector3 OrientedPlane3::error (const gtsam::OrientedPlane3& plane) const
|
Vector3 OrientedPlane3::error (const gtsam::OrientedPlane3& plane) const
|
||||||
{
|
{
|
||||||
Vector2 n_error = -n_.localCoordinates (plane.n_);
|
Vector2 n_error = -n_.localCoordinates (plane.n_);
|
||||||
double d_error = d_ - plane.d_;
|
double d_error = d_ - plane.d_;
|
||||||
Vector3 e;
|
Vector3 e;
|
||||||
e << n_error (0), n_error (1), d_error;
|
e << n_error (0), n_error (1), d_error;
|
||||||
return (e);
|
return (e);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
OrientedPlane3 OrientedPlane3::retract(const Vector& v) const {
|
OrientedPlane3 OrientedPlane3::retract(const Vector& v) const {
|
||||||
|
|
@ -96,13 +95,13 @@ Vector3 OrientedPlane3::localCoordinates(const OrientedPlane3& y) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Vector3 OrientedPlane3::planeCoefficients () const
|
Vector3 OrientedPlane3::planeCoefficients () const
|
||||||
{
|
{
|
||||||
Vector unit_vec = n_.unitVector ();
|
Vector unit_vec = n_.unitVector ();
|
||||||
Vector3 a;
|
Vector3 a;
|
||||||
a << unit_vec[0], unit_vec[1], unit_vec[2], d_;
|
a << unit_vec[0], unit_vec[1], unit_vec[2], d_;
|
||||||
return a;
|
return a;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -42,7 +42,7 @@ GTSAM_CONCEPT_MANIFOLD_INST(OrientedPlane3)
|
||||||
|
|
||||||
//*******************************************************************************
|
//*******************************************************************************
|
||||||
TEST (OrientedPlane3, transform)
|
TEST (OrientedPlane3, transform)
|
||||||
{
|
{
|
||||||
// Test transforming a plane to a pose
|
// Test transforming a plane to a pose
|
||||||
gtsam::Pose3 pose(gtsam::Rot3::ypr (-M_PI/4.0, 0.0, 0.0), gtsam::Point3(2.0, 3.0, 4.0));
|
gtsam::Pose3 pose(gtsam::Rot3::ypr (-M_PI/4.0, 0.0, 0.0), gtsam::Point3(2.0, 3.0, 4.0));
|
||||||
OrientedPlane3 plane (-1 , 0, 0, 5);
|
OrientedPlane3 plane (-1 , 0, 0, 5);
|
||||||
|
|
@ -65,7 +65,7 @@ TEST (OrientedPlane3, transform)
|
||||||
EXPECT (assert_equal (expectedH2, actualH2, 1e-9));
|
EXPECT (assert_equal (expectedH2, actualH2, 1e-9));
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//*******************************************************************************
|
//*******************************************************************************
|
||||||
// Returns a random vector -- copied from testUnit3.cpp
|
// Returns a random vector -- copied from testUnit3.cpp
|
||||||
|
|
|
||||||
|
|
@ -33,7 +33,7 @@ bool OrientedPlane3DirectionPrior::equals(const NonlinearFactor& expected,
|
||||||
Vector OrientedPlane3DirectionPrior::evaluateError(const OrientedPlane3& plane,
|
Vector OrientedPlane3DirectionPrior::evaluateError(const OrientedPlane3& plane,
|
||||||
boost::optional<Matrix&> H) const {
|
boost::optional<Matrix&> H) const {
|
||||||
|
|
||||||
if(H) {
|
if(H) {
|
||||||
Matrix H_p;
|
Matrix H_p;
|
||||||
Unit3 n_hat_p = measured_p_.normal();
|
Unit3 n_hat_p = measured_p_.normal();
|
||||||
Unit3 n_hat_q = plane.normal();
|
Unit3 n_hat_q = plane.normal();
|
||||||
|
|
@ -42,12 +42,12 @@ Vector OrientedPlane3DirectionPrior::evaluateError(const OrientedPlane3& plane,
|
||||||
H->block <2,2>(0,0) << H_p;
|
H->block <2,2>(0,0) << H_p;
|
||||||
H->block <2,1>(0,2) << Matrix::Zero(2, 1);
|
H->block <2,1>(0,2) << Matrix::Zero(2, 1);
|
||||||
return e;
|
return e;
|
||||||
} else {
|
} else {
|
||||||
Unit3 n_hat_p = measured_p_.normal();
|
Unit3 n_hat_p = measured_p_.normal();
|
||||||
Unit3 n_hat_q = plane.normal();
|
Unit3 n_hat_q = plane.normal();
|
||||||
Vector e = n_hat_p.error(n_hat_q);
|
Vector e = n_hat_p.error(n_hat_q);
|
||||||
return e;
|
return e;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -16,12 +16,12 @@
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Factor to measure a planar landmark from a given pose
|
* Factor to measure a planar landmark from a given pose
|
||||||
*/
|
*/
|
||||||
class OrientedPlane3Factor: public NoiseModelFactor2<Pose3, OrientedPlane3> {
|
class OrientedPlane3Factor: public NoiseModelFactor2<Pose3, OrientedPlane3> {
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
Symbol poseSymbol_;
|
Symbol poseSymbol_;
|
||||||
Symbol landmarkSymbol_;
|
Symbol landmarkSymbol_;
|
||||||
Vector3 measured_coeffs_;
|
Vector3 measured_coeffs_;
|
||||||
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
||||||
|
|
||||||
typedef NoiseModelFactor2<Pose3, OrientedPlane3 > Base;
|
typedef NoiseModelFactor2<Pose3, OrientedPlane3 > Base;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/// Constructor
|
/// Constructor
|
||||||
OrientedPlane3Factor ()
|
OrientedPlane3Factor ()
|
||||||
|
|
@ -49,7 +49,6 @@ namespace gtsam {
|
||||||
|
|
||||||
/// print
|
/// print
|
||||||
void print(const std::string& s="PlaneFactor") const;
|
void print(const std::string& s="PlaneFactor") const;
|
||||||
|
|
||||||
virtual Vector evaluateError(const Pose3& pose, const OrientedPlane3& plane,
|
virtual Vector evaluateError(const Pose3& pose, const OrientedPlane3& plane,
|
||||||
boost::optional<Matrix&> H1 = boost::none,
|
boost::optional<Matrix&> H1 = boost::none,
|
||||||
boost::optional<Matrix&> H2 = boost::none) const
|
boost::optional<Matrix&> H2 = boost::none) const
|
||||||
|
|
@ -59,18 +58,15 @@ namespace gtsam {
|
||||||
err << predicted_plane.error (measured_p_);
|
err << predicted_plane.error (measured_p_);
|
||||||
return (err);
|
return (err);
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
// TODO: Convert this factor to dimension two, three dimensions is redundant for direction prior
|
// TODO: Convert this factor to dimension two, three dimensions is redundant for direction prior
|
||||||
class OrientedPlane3DirectionPrior: public NoiseModelFactor1<OrientedPlane3> {
|
class OrientedPlane3DirectionPrior: public NoiseModelFactor1<OrientedPlane3> {
|
||||||
|
protected:
|
||||||
protected:
|
|
||||||
OrientedPlane3 measured_p_; /// measured plane parameters
|
OrientedPlane3 measured_p_; /// measured plane parameters
|
||||||
Key landmarkKey_;
|
Key landmarkKey_;
|
||||||
|
|
||||||
typedef NoiseModelFactor1<OrientedPlane3 > Base;
|
typedef NoiseModelFactor1<OrientedPlane3 > Base;
|
||||||
|
public:
|
||||||
public:
|
|
||||||
|
|
||||||
typedef OrientedPlane3DirectionPrior This;
|
typedef OrientedPlane3DirectionPrior This;
|
||||||
/// Constructor
|
/// Constructor
|
||||||
|
|
@ -85,7 +81,6 @@ namespace gtsam {
|
||||||
{
|
{
|
||||||
measured_p_ = OrientedPlane3 (Unit3 (z (0), z (1), z (2)), z (3));
|
measured_p_ = OrientedPlane3 (Unit3 (z (0), z (1), z (2)), z (3));
|
||||||
}
|
}
|
||||||
|
|
||||||
/// print
|
/// print
|
||||||
void print(const std::string& s) const;
|
void print(const std::string& s) const;
|
||||||
|
|
||||||
|
|
@ -94,7 +89,7 @@ namespace gtsam {
|
||||||
|
|
||||||
virtual Vector evaluateError(const OrientedPlane3& plane,
|
virtual Vector evaluateError(const OrientedPlane3& plane,
|
||||||
boost::optional<Matrix&> H = boost::none) const;
|
boost::optional<Matrix&> H = boost::none) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // gtsam
|
} // gtsam
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -141,7 +141,7 @@ TEST( OrientedPlane3DirectionPriorFactor, Constructor ) {
|
||||||
SharedGaussian model = gtsam::noiseModel::Diagonal::Sigmas (Vector3(0.1, 0.1, 10.0));
|
SharedGaussian model = gtsam::noiseModel::Diagonal::Sigmas (Vector3(0.1, 0.1, 10.0));
|
||||||
OrientedPlane3DirectionPrior factor(key, planeOrientation, model);
|
OrientedPlane3DirectionPrior factor(key, planeOrientation, model);
|
||||||
|
|
||||||
// Create a linearization point at the zero-error point
|
// Create a linearization point at the zero-error point
|
||||||
Vector theta1 = Vector4(0.0, 0.02, -1.2, 10.0);
|
Vector theta1 = Vector4(0.0, 0.02, -1.2, 10.0);
|
||||||
Vector theta2 = Vector4(0.0, 0.1, - 0.8, 10.0);
|
Vector theta2 = Vector4(0.0, 0.1, - 0.8, 10.0);
|
||||||
Vector theta3 = Vector4(0.0, 0.2, -0.9, 10.0);
|
Vector theta3 = Vector4(0.0, 0.2, -0.9, 10.0);
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue