27 #include <boost/bind.hpp> 29 using namespace gtsam;
35 using symbol_shorthand::
P;
36 using symbol_shorthand::
X;
54 Vector4 measurement0(-1.0, 0.0, 0.0, 3.0);
56 LocalOrientedPlane3Factor factor0(
58 LocalOrientedPlane3Factor
factor1(
66 values.
insert(
X(1), anchor_pose);
71 isam2.
update(graph, values);
140 Key planeKey(1),
poseKey(2), anchorPoseKey(3);
146 _1, _2, _3, boost::none, boost::none, boost::none);
155 Matrix actualH1, actualH2, actualH3;
156 factor.
evaluateError(poseLin, anchorPoseLin, pLin, actualH1, actualH2,
191 const Plane
p1(0, 0, 1, 1),
p2(0, 0, 1, 2);
193 auto p1_in_x1 =
p1.transform(x1);
194 auto p2_in_x1 = p2.transform(x1);
197 graph.
addPrior<Plane>(
P(1), p1_in_x1, p1_noise);
198 graph.
addPrior<Plane>(
P(2), p2_in_x1, p2_noise);
202 auto p1_measured_from_x0 =
p1.transform(x0);
204 auto p2_measured_from_x0 = p2.transform(x0);
208 p1_measured_from_x0.planeCoefficients(), x0_p1_noise,
X(0),
X(1),
P(1));
210 p2_measured_from_x0.planeCoefficients(), x0_p2_noise,
X(0),
X(1),
P(2));
216 initialEstimate.insert(
P(1), p1_in_x1);
217 initialEstimate.insert(
P(2), p2_in_x1);
218 initialEstimate.insert(
X(0), x0_initial);
219 initialEstimate.insert(
X(1), x1);
224 isam2.
update(graph, initialEstimate);
228 EXPECT(p1_in_x1.equals(result.
at<Plane>(
P(1))));
229 EXPECT(p2_in_x1.equals(result.
at<Plane>(
P(2))));
231 cerr <<
"CAPTURED THE EXCEPTION: " 239 srand(
time(
nullptr));
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
static int runAllTests(TestResult &result)
void insert(Key j, const Value &val)
static StereoPoint2 measurement1(323.0, 300.0, 240.0)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
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
Vector evaluateError(const Pose3 &wTwi, const Pose3 &wTwa, const OrientedPlane3 &a_plane, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
#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)
static Rot3 identity()
identity rotation for group operation
static Pose3 identity()
identity for group operation
Values calculateEstimate() const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
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.)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
TEST(LPInitSolver, InfiniteLoopSingleVar)
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)
double error(const Values &values) const
Key nearbyVariable() const
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Gaussian::shared_ptr SharedGaussian
#define GTSAM_CONCEPT_TESTABLE_INST(T)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))