26 using namespace gtsam;
48 const double angle = 2.5;
50 SO3 R = SO3::AxisAngle(axis, angle);
57 M << 0.79067393, 0.6051136, -0.0930814,
58 0.4155925, -0.64214347, -0.64324489,
59 -0.44948549, 0.47046326, -0.75917576;
62 expected << 0.790687, 0.605096, -0.0931312,
63 0.415746, -0.642355, -0.643844,
64 -0.449411, 0.47036, -0.759468;
66 auto actual = SO3::ClosestTo(3 * M);
129 EXPECT(check_group_invariants(
id,
id));
130 EXPECT(check_group_invariants(
id,
R1));
131 EXPECT(check_group_invariants(
R2,
id));
134 EXPECT(check_manifold_invariants(
id,
id));
135 EXPECT(check_manifold_invariants(
id,
R1));
136 EXPECT(check_manifold_invariants(
R2,
id));
159 double angle = 3.14 / 4.0;
161 expected << 0.707388, 0, 0.706825, 0, 1, 0, -0.706825, 0, 0.707388;
164 so3::ExpmapFunctor
f1(axis, angle);
169 so3::ExpmapFunctor
f2(axis, angle - 2*
M_PI);
174 so3::ExpmapFunctor
f3(axis * angle);
179 so3::ExpmapFunctor
f4(axis * (angle - 2*
M_PI));
186 static const Vector3 w(0.1, 0.27, -0.2);
199 const Matrix actualDexpL = SO3::ExpmapDerivative(
w);
200 const Matrix expectedDexpL =
201 numericalDerivative11<Vector3, Vector3>(
testDexpL, Vector3::Zero(), 1
e-2);
204 const Matrix actualDexpInvL = SO3::LogmapDerivative(
w);
211 const Matrix Jexpected = numericalDerivative11<SO3, Vector3>(
216 SO3::ExpmapDerivative(-theta)));
222 const Matrix Jexpected = numericalDerivative11<SO3, Vector3>(
227 SO3::ExpmapDerivative(-theta)));
246 auto w_dot = [](
double t) {
return Vector3(2,
cos(
t), 8 *
t); };
251 for (
double t = -2.0;
t < 2.0;
t += 0.3) {
253 const Matrix actual = SO3::ExpmapDerivative(
w(
t)) * w_dot(
t);
261 auto w_dot = [](
double t) {
return Vector3(2,
cos(
t), 8 *
t); };
267 for (
double t = -2.0;
t < 2.0;
t += 0.3) {
269 const Matrix actual = SO3::ExpmapDerivative(
w(
t)) * w_dot(
t);
276 const Vector3 thetahat(0.1, 0, 0.1);
277 const Matrix Jexpected = numericalDerivative11<SO3, Vector3>(
278 boost::bind(&
SO3::Expmap, _1, boost::none), thetahat);
286 const Vector3 thetahat(0.1, 0, 0.1);
288 const Matrix Jexpected = numericalDerivative11<Vector, SO3>(
289 boost::bind(&SO3::Logmap, _1, boost::none),
R);
290 const Matrix3 Jactual = SO3::LogmapDerivative(thetahat);
296 const Vector3 thetahat(0.1, 0, 0.1);
298 const Matrix Jexpected = numericalDerivative11<Vector, SO3>(
299 boost::bind(&SO3::Logmap, _1, boost::none),
R);
301 SO3::Logmap(R, Jactual);
308 for (
bool nearZeroApprox : {
true,
false}) {
309 boost::function<Vector3(const Vector3&, const Vector3&)>
f =
311 return so3::DexpFunctor(omega, nearZeroApprox).applyDexp(
v);
315 so3::DexpFunctor local(omega, nearZeroApprox);
319 local.applyDexp(
v, aH1, aH2)));
331 for (
bool nearZeroApprox : {
true,
false}) {
332 boost::function<Vector3(const Vector3&, const Vector3&)>
f =
334 return so3::DexpFunctor(omega, nearZeroApprox).applyInvDexp(
v);
338 so3::DexpFunctor local(omega, nearZeroApprox);
339 Matrix invDexp = local.dexp().inverse();
343 local.applyInvDexp(v, aH1, aH2)));
356 const Vector9 actual =
R2.
vec(actualH);
358 boost::function<Vector9(const SO3&)>
f = [](
const SO3&
Q) {
return Q.
vec(); };
366 M << 1, 2, 3, 4, 5, 6, 7, 8, 9;
372 boost::function<Matrix3(const Matrix3&)>
f = [
R](
const Matrix3&
M) {
Matrix< RealScalar, Dynamic, Dynamic > M
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H=boost::none) const
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
SO3 R2(Eigen::AngleAxisd(0.2, z_axis))
A matrix or vector expression mapping an existing array of data.
Vector3 testDexpL(const Vector3 &dw)
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
const MatrixNN & matrix() const
Return matrix.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
double f2(const Vector2 &x)
SO inverse() const
inverse of a rotation = transpose
3*3 matrix representation of SO(3)
T compose(const T &t1, const T &t2)
SO3 R1(Eigen::AngleAxisd(0.1, z_axis))
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
EIGEN_DEVICE_FUNC const VectorBlock< const Coefficients, 3 > vec() const
EIGEN_DEVICE_FUNC const CosReturnType cos() const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Class expmap(const TangentVector &v) const
#define EXPECT(condition)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Vector3 w(0.1, 0.27,-0.2)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define EXPECT_LONGS_EQUAL(expected, actual)
The quaternion class used to represent 3D orientations and rotations.
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
double f4(double x, double y, double z)
#define CHECK_CHART_DERIVATIVES(t1, t2)
Class between(const Class &g) const
double f3(double x1, double x2)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(boost::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.