30 using namespace gtsam;
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself=boost::none, OptionalJacobian< 2, 3 > Hpoint=boost::none) const
BearingFactor< Pose3, Point3 > BearingFactor3D
static int runAllTests(TestResult &result)
void insert(Key j, const Value &val)
BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic)
bool equalsObj(const T &input=T())
static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5))
double measurement2D(10.0)
Evaluate derivatives of a nonlinear factor numerically.
static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(1, 0.5))
bool equalsXML(const T &input=T())
bool equalsBinary(const T &input=T())
BearingFactor3D factor3D(poseKey, pointKey, measurement3D, model3D)
#define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by an expression against finite differences.
void deserializeXML(const std::string &serialized, T &output, const std::string &name="data")
deserializes from a string in XML
TEST(BearingFactor, Serialization2D)
Represents a 3D point on a unit sphere.
BearingFactor< Pose2, Point2 > BearingFactor2D
Test harness methods for expressions.
Expression< T > expression(const typename Base::ArrayNKeys &keys) const override
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
BearingFactor2D factor2D(poseKey, pointKey, measurement2D, model2D)
std::string serializeXML(const T &input, const std::string &name="data")
serializes to a string in XML
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel