Go to the documentation of this file.
   23 using namespace gtsam;
 
  158   Matrix expectedH, actualH;
 
  182   Vector4 actual_vec = 
R.
vec(actualH);
 
  186   std::function<Vector4(
const Rot2&)> 
f = [](
const Rot2& 
p) { 
return p.vec(); };
 
  187   Matrix41 numericalH = numericalDerivative11<Vector4, Rot2>(
f, 
R);
 
  200   EXPECT(check_group_invariants(
id, 
id));
 
  201   EXPECT(check_group_invariants(
id, 
T1));
 
  202   EXPECT(check_group_invariants(
T2, 
id));
 
  205   EXPECT(check_manifold_invariants(
id, 
id));
 
  206   EXPECT(check_manifold_invariants(
id, 
T1));
 
  207   EXPECT(check_manifold_invariants(
T2, 
id));
 
  
static int runAllTests(TestResult &result)
Class between(const Class &g) const
gtsam::Expression< typename gtsam::traits< T >::TangentVector > logmap(const gtsam::Expression< T > &x1, const gtsam::Expression< T > &x2)
logmap
Eigen::Matrix< double, 1, 1 > Vector1
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Point2 unrotate(const Point2 &p, OptionalJacobian< 2, 1 > H1={}, OptionalJacobian< 2, 2 > H2={}) const
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Concept check for values that can be used in unit tests.
Jet< T, N > sin(const Jet< T, N > &f)
#define EXPECT(condition)
static Rot2 fromCosSin(double c, double s)
Named constructor from cos(theta),sin(theta) pair.
Class compose(const Class &g) const
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
static Rot2 relativeBearing(const Point2 &d, OptionalJacobian< 1, 2 > H={})
static Rot2 atan2(double y, double x)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Point3 pt(1.0, 2.0, 3.0)
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
Jet< T, N > cos(const Jet< T, N > &f)
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
static Rot2 fromAngle(double theta)
Named constructor from angle in radians.
Vector4 vec(OptionalJacobian< 4, 1 > H={}) const
Return vectorized SO(2) matrix in column order.
static const Similarity3 id
Point3_ unrotate(const Rot3_ &x, const Point3_ &p)
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
bool equals(const Rot2 &R, double tol=1e-9) const
#define DOUBLES_EQUAL(expected, actual, threshold)
#define GTSAM_CONCEPT_LIE_INST(T)
EIGEN_DONT_INLINE Scalar zero()
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
Point2 unrotate_(const Rot2 &R, const Point2 &p)
Matrix2 transpose() const
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
A matrix or vector expression mapping an existing array of data.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Point2 rotate(const Point2 &p, OptionalJacobian< 2, 1 > H1={}, OptionalJacobian< 2, 2 > H2={}) const
TEST(SmartFactorBase, Pinhole)
static Vector1 Vee(const Matrix2 &X)
Vee maps from Lie algebra to tangent vector.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
static Matrix2 Hat(const Vector1 &xi)
Hat maps from tangent vector to Lie algebra.
Rot2 relativeBearing_(const Point2 &pt)
Array< int, Dynamic, 1 > v
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
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
#define CHECK_CHART_DERIVATIVES(t1, t2)
Rot2 R(Rot2::fromAngle(0.1))
Point2 rotate_(const Rot2 &R, const Point2 &p)
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:07:23