29 using namespace gtsam;
48 Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0),
Point3(0.0, 0.0, 0.0));
50 sigmas << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001;
51 graph.
addPrior(
X(0), init_pose, noiseModel::Diagonal::Sigmas(sigmas));
54 Vector3 sigmas3 {0.1, 0.1, 0.1};
55 Vector4 measurement0 {-1.0, 0.0, 0.0, 3.0};
57 measurement0, noiseModel::Diagonal::Sigmas(sigmas3),
X(0),
P(0));
135 Pose3 poseLin(rotationLin, pointLin);
144 return factor.evaluateError(p, o);
146 Matrix numericalH1 = numericalDerivative21<Vector, Pose3, OrientedPlane3>(
f, poseLin, pLin);
147 Matrix numericalH2 = numericalDerivative22<Vector, Pose3, OrientedPlane3>(
f, poseLin, pLin);
150 Matrix actualH1, actualH2;
151 factor.evaluateError(poseLin, pLin, actualH1, actualH2);
165 Vector4 planeOrientation = (
Vector(4) << 0.0, 0.0, -1.0, 10.0).finished();
173 Vector4 theta1 {0.0, 0.02, -1.2, 10.0};
174 Vector4 theta2 {0.0, 0.1, -0.8, 10.0};
175 Vector4 theta3 {0.0, 0.2, -0.9, 10.0};
182 Matrix expectedH1 = numericalDerivative11<Vector, OrientedPlane3>(
185 Matrix expectedH2 = numericalDerivative11<Vector, OrientedPlane3>(
188 Matrix expectedH3 = numericalDerivative11<Vector, OrientedPlane3>(
192 Matrix actualH1, actualH2, actualH3;
214 auto x0_noise = noiseModel::Isotropic::Sigma(6, 0.01);
218 const Plane
p1(0,0,1,1),
p2(0,0,1,2);
219 auto p1_noise = noiseModel::Diagonal::Sigmas(
Vector3{1, 1, 5});
220 auto p2_noise = noiseModel::Diagonal::Sigmas(
Vector3{1, 1, 5});
225 auto p1_measured_from_x0 = p1.transform(x0);
226 auto p2_measured_from_x0 = p2.transform(x0);
227 const auto x0_p1_noise = noiseModel::Isotropic::Sigma(3, 0.05);
228 const auto x0_p2_noise = noiseModel::Isotropic::Sigma(3, 0.05);
230 p1_measured_from_x0.planeCoefficients(), x0_p1_noise,
X(0),
P(1));
232 p2_measured_from_x0.planeCoefficients(), x0_p2_noise,
X(0),
P(2));
238 initialEstimate.insert(
P(1), p1);
239 initialEstimate.insert(
P(2), p2);
240 initialEstimate.insert(
X(0), x0_initial);
248 EXPECT(p1.equals(result.
at<Plane>(
P(1))));
249 EXPECT(p2.equals(result.
at<Plane>(
P(2))));
258 srand(
time(
nullptr));
const gtsam::Symbol key('X', 0)
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx={}, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hz={})
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
virtual const Values & optimize()
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Some functions to compute numerical derivatives.
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Represents an infinite plane in 3D, which is composed of a planar normal and its perpendicular distan...
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Vector evaluateError(const OrientedPlane3 &plane, OptionalMatrixType H) const override
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
#define EXPECT(condition)
static Point2 measurement1(323.0, 240.0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(OrientedPlane3Factor, lm_translation_error)
double error(const Values &values) const
Class compose(const Class &g) const
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
Vector4 planeCoefficients() const
Returns the plane coefficients.
void insert(Key j, const Value &val)
Jet< T, N > sqrt(const Jet< T, N > &f)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Key nearbyVariable() const
std::uint64_t Key
Integer nonlinear key type.
Values calculateEstimate() const
noiseModel::Gaussian::shared_ptr SharedGaussian
#define GTSAM_CONCEPT_TESTABLE_INST(T)