28 #include <boost/assign/std/vector.hpp> 29 #include <boost/assign/std.hpp> 30 #include <boost/bind.hpp> 33 using namespace gtsam;
39 using symbol_shorthand::
P;
40 using symbol_shorthand::
X;
52 Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0),
Point3(0.0, 0.0, 0.0));
54 sigmas << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001;
55 graph.
addPrior(
X(0), init_pose, noiseModel::Diagonal::Sigmas(sigmas));
58 Vector3 sigmas3 {0.1, 0.1, 0.1};
59 Vector4 measurement0 {-1.0, 0.0, 0.0, 3.0};
60 OrientedPlane3Factor factor0(
61 measurement0, noiseModel::Diagonal::Sigmas(sigmas3),
X(0),
P(0));
139 Pose3 poseLin(rotationLin, pointLin);
147 boost::function<Vector(const Pose3&, const OrientedPlane3&)>
f = boost::bind(
148 &OrientedPlane3Factor::evaluateError, factor, _1, _2, boost::none, boost::none);
149 Matrix numericalH1 = numericalDerivative21<Vector, Pose3, OrientedPlane3>(
f, poseLin, pLin);
150 Matrix numericalH2 = numericalDerivative22<Vector, Pose3, OrientedPlane3>(
f, poseLin, pLin);
153 Matrix actualH1, actualH2;
154 factor.evaluateError(poseLin, pLin, actualH1, actualH2);
168 Vector4 planeOrientation = (
Vector(4) << 0.0, 0.0, -1.0, 10.0).finished();
176 Vector4 theta1 {0.0, 0.02, -1.2, 10.0};
177 Vector4 theta2 {0.0, 0.1, -0.8, 10.0};
178 Vector4 theta3 {0.0, 0.2, -0.9, 10.0};
185 Matrix expectedH1 = numericalDerivative11<Vector, OrientedPlane3>(
186 boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1,
189 Matrix expectedH2 = numericalDerivative11<Vector, OrientedPlane3>(
190 boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1,
193 Matrix expectedH3 = numericalDerivative11<Vector, OrientedPlane3>(
194 boost::bind(&OrientedPlane3DirectionPrior::evaluateError, &factor, _1,
198 Matrix actualH1, actualH2, actualH3;
220 auto x0_noise = noiseModel::Isotropic::Sigma(6, 0.01);
224 const Plane
p1(0,0,1,1),
p2(0,0,1,2);
225 auto p1_noise = noiseModel::Diagonal::Sigmas(
Vector3{1, 1, 5});
226 auto p2_noise = noiseModel::Diagonal::Sigmas(
Vector3{1, 1, 5});
231 auto p1_measured_from_x0 = p1.transform(x0);
232 auto p2_measured_from_x0 = p2.transform(x0);
233 const auto x0_p1_noise = noiseModel::Isotropic::Sigma(3, 0.05);
234 const auto x0_p2_noise = noiseModel::Isotropic::Sigma(3, 0.05);
236 p1_measured_from_x0.planeCoefficients(), x0_p1_noise,
X(0),
P(1));
238 p2_measured_from_x0.planeCoefficients(), x0_p2_noise,
X(0),
P(2));
244 initialEstimate.insert(
P(1), p1);
245 initialEstimate.insert(
P(2), p2);
246 initialEstimate.insert(
X(0), x0_initial);
254 EXPECT(p1.equals(result.
at<Plane>(
P(1))));
255 EXPECT(p2.equals(result.
at<Plane>(
P(2))));
264 srand(
time(
nullptr));
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
virtual const Values & optimize()
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
static StereoPoint2 measurement1(323.0, 300.0, 240.0)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Some functions to compute numerical derivatives.
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx=boost::none, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hz=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
IsDerived< DERIVEDFACTOR > add(boost::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Represents an infinite plane in 3D, which is composed of a planar normal and its perpendicular distan...
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Values calculateEstimate() const
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Class compose(const Class &g) const
const ValueType at(Key j) const
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(OrientedPlane3Factor, lm_translation_error)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
Vector4 planeCoefficients() const
Returns the plane coefficients.
double error(const Values &values) const
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Key nearbyVariable() const
std::uint64_t Key
Integer nonlinear key type.
Vector evaluateError(const OrientedPlane3 &plane, boost::optional< Matrix & > H=boost::none) const override
noiseModel::Gaussian::shared_ptr SharedGaussian
#define GTSAM_CONCEPT_TESTABLE_INST(T)
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))