31 using namespace gtsam;
76 Pose2 body_P_sensor_2D(0.25, -0.10, -M_PI_2);
77 Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
104 Pose2 body_P_sensor_2D(0.25, -0.10, -M_PI_2);
105 Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
106 Point3(0.25, -0.10, 1.0));
130 Vector actualError(factor.
unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}));
133 Vector expectedError = (
Vector(1) << 0.295630141).finished();
153 Vector actualError(factor.
unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}));
156 Vector expectedError = (
Vector(1) << 0.295630141).finished();
172 Vector actualError(factor.
unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}));
175 Vector expectedError = (
Vector(1) << 0.295630141).finished();
185 Point3(0.25, -0.10, 1.0));
190 Rot3 R = Rot3::RzRyRx(0.2, -0.3, 1.75);
196 Vector actualError(factor.
unwhitenedError({{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}));
199 Vector expectedError = (
Vector(1) << 0.295630141).finished();
215 Matrix H1Actual, H2Actual;
219 Matrix H1Expected, H2Expected;
220 H1Expected = numericalDerivative11<Vector, Pose2>(
221 std::bind(&factorError2D, std::placeholders::_1, point, factor),
pose);
222 H2Expected = numericalDerivative11<Vector, Point2>(
223 std::bind(&factorError2D, pose, std::placeholders::_1, factor),
point);
244 std::vector<Matrix> actualHs(2);
246 const Matrix& H1Actual = actualHs.at(0);
247 const Matrix& H2Actual = actualHs.at(1);
250 Matrix H1Expected, H2Expected;
251 H1Expected = numericalDerivative11<Vector, Pose2>(
252 std::bind(&factorErrorWithTransform2D, std::placeholders::_1, point, factor),
pose);
253 H2Expected = numericalDerivative11<Vector, Point2>(
254 std::bind(&factorErrorWithTransform2D, pose, std::placeholders::_1, factor),
point);
271 std::vector<Matrix> actualHs(2);
273 const Matrix& H1Actual = actualHs.at(0);
274 const Matrix& H2Actual = actualHs.at(1);
277 Matrix H1Expected, H2Expected;
278 H1Expected = numericalDerivative11<Vector, Pose3>(
279 std::bind(&factorError3D, std::placeholders::_1, point, factor),
pose);
280 H2Expected = numericalDerivative11<Vector, Point3>(
281 std::bind(&factorError3D, pose, std::placeholders::_1, factor),
point);
292 Point3(0.25, -0.10, 1.0));
297 Rot3 R = Rot3::RzRyRx(0.2, -0.3, 1.75);
303 std::vector<Matrix> actualHs(2);
305 const Matrix& H1Actual = actualHs.at(0);
306 const Matrix& H2Actual = actualHs.at(1);
309 Matrix H1Expected, H2Expected;
310 H1Expected = numericalDerivative11<Vector, Pose3>(
311 std::bind(&factorErrorWithTransform3D, std::placeholders::_1, point, factor),
pose);
312 H2Expected = numericalDerivative11<Vector, Point3>(
313 std::bind(&factorErrorWithTransform3D, pose, std::placeholders::_1, factor),
point);
330 Vector expectedError = (
Vector(1) << 0.295630141).finished();
344 Point3 p11(1.0, 2.0, 0.0),
p22(-4.0, 11.0, 0);
347 Vector expectedError = (
Vector(1) << 0.295630141).finished();
373 return (v2 - v1).norm();
387 Vector4
pose(1.0, 2.0, 00, 0);
388 Vector4
point(-4.0, 11.0, 0, 0);
391 Vector expectedError = (
Vector(1) << 0.295630141).finished();
Provides additional testing facilities for common data structures.
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
double operator()(const Vector4 &v1, const Vector4 &v2, OptionalJacobian< 1, 4 > H1, OptionalJacobian< 1, 4 > H2)
Rot2 R(Rot2::fromAngle(0.1))
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
RangeFactorWithTransform< Pose3, Point3 > RangeFactorWithTransform3D
Some functions to compute numerical derivatives.
RangeFactor< Pose3, Point3 > RangeFactor3D
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
const gtsam::Key pointKey
Base class for all pinhole cameras.
static Point2 measurement(323.0, 240.0)
TEST(RangeFactor, Constructor)
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RangeFactor< Pose2, Point2 > RangeFactor2D
GenericValue< T > genericValue(const T &v)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
RangeFactorWithTransform< Pose2, Point2 > RangeFactorWithTransform2D
Point2 rotate(const Point2 &p, OptionalJacobian< 2, 1 > H1={}, OptionalJacobian< 2, 2 > H2={}) const
Vector evaluateError(const A1 &a1, const A2 &a2, OptionalMatrixType H1=OptionalNone, OptionalMatrixType H2=OptionalNone) const
const KeyVector & keys() const
Access the factor's involved variable keys.
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
const Point2 & translation(OptionalJacobian< 2, 3 > Hself={}) const
translation