15 #include <boost/bind.hpp> 16 #include <boost/assign/std/vector.hpp> 21 using namespace gtsam;
33 static const Unit3 p1(1, 0, 0),
p2(0, 1, 0),
p3(0, 0, 1);
59 Model
model = noiseModel::Isotropic::Sigma(3, 0.01);
64 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 74 expected = numericalDerivative11<Vector3,Rot3>(
75 boost::bind(&RotateFactor::evaluateError, &f, _1, boost::none),
iRc);
80 expected = numericalDerivative11<Vector3,Rot3>(
81 boost::bind(&RotateFactor::evaluateError, &f, _1, boost::none),
R);
91 Model
model = noiseModel::Isotropic::Sigma(3, 0.01);
104 initial.insert(1, initialE);
106 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 128 Model
model = noiseModel::Isotropic::Sigma(2, 0.01);
134 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 145 expected = numericalDerivative11<Vector,Rot3>(
146 boost::bind(&RotateDirectionsFactor::evaluateError, &f, _1,
152 expected = numericalDerivative11<Vector,Rot3>(
153 boost::bind(&RotateDirectionsFactor::evaluateError, &f, _1,
164 Model
model = noiseModel::Isotropic::Sigma(2, 0.01);
177 initial.insert(1, initialE);
179 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS) 202 const Unit3 n_p(-n_gravity);
205 std::vector<double> angles = {0, 45, 85, 135, 180, 225, 275, 315};
206 for (
double yaw : angles) {
208 for (
double pitch : angles) {
209 const Rot3 yRp = Rot3::Pitch(pitch * kDegree);
210 for (
double roll : angles) {
211 const Rot3 pRb = Rot3::Roll(roll * kDegree);
214 const Rot3 nRb = nRy * yRp * pRb;
219 const Unit3 b_z(b_acc);
222 const Rot3 actual_nRb = RotateDirectionsFactor::Initialize(n_p, b_z);
static const Unit3 p2(0, 1, 0)
static const double kDegree
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
TEST(RotateFactor, checkMath)
Factor Graph consisting of non-linear factors.
static const Unit3 p3(0, 0, 1)
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Vector evaluateError(const Rot3 &R, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 2D vector
static const Rot3 iRc(cameraX, cameraY, cameraZ)
Rot2 R(Rot2::fromAngle(0.1))
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
static const Point3 cameraZ(1, 0, 0)
noiseModel::Isotropic::shared_ptr Model
Some functions to compute numerical derivatives.
NonlinearFactorGraph graph
static const Point3 cameraY(0, 0, 1)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Rot3 inverse() const
inverse of a rotation
Represents a 3D point on a unit sphere.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
const ValueType at(Key j) const
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector evaluateError(const Rot3 &iRc, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 2D vector
static ConjugateGradientParameters parameters
static const Unit3 p1(1, 0, 0)
static const Point3 cameraX(0, 1, 0)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
boost::shared_ptr< Isotropic > shared_ptr
Vector3 rpy(OptionalJacobian< 3, 3 > H=boost::none) const
double error(const Values &values) const
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1