Go to the documentation of this file.
13 using namespace gtsam;
19 static const
Point3 pt(1.0, 2.0, 3.0);
24 TEST( testPoseRTV, constructors ) {
49 Vector vec_init = (
Vector(9) << 0.1, 0.2, 0.3, 1.0, 2.0, 3.0, 0.4, 0.5, 0.6).finished();
87 delta << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4,-0.1,-0.2,-0.3;
108 TEST( testPoseRTV, dynamics_identities ) {
112 const double dt = 0.1;
114 Vector imu01 = Z_6x1, imu12 = Z_6x1, imu23 = Z_6x1, imu34 = Z_6x1;
116 x1 =
x0.generalDynamics(accel, gyro,
dt);
117 x2 =
x1.generalDynamics(accel, gyro,
dt);
118 x3 =
x2.generalDynamics(accel, gyro,
dt);
119 x4 =
x3.generalDynamics(accel, gyro,
dt);
173 Point3 tA(1.0, 2.0, 3.0), tB(3.0, 2.0, 3.0);
180 rtvA.range(rtvB, actH1, actH2);
189 return a.transformed_from(
trans);
191 TEST( testPoseRTV, transformed_from_1 ) {
198 Matrix actDTrans, actDGlobal;
210 TEST( testPoseRTV, transformed_from_2 ) {
217 Matrix actDTrans, actDGlobal;
static int runAllTests(TestResult &result)
TangentVector localCoordinates(const ProductLieGroup &g, ChartJacobian H1={}, ChartJacobian H2={}) const
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
PoseRTV transformed_from(const Pose3 &trans, ChartJacobian Dglobal={}, OptionalJacobian< 9, 6 > Dtrans={}) const
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define GTSAM_CONCEPT_TESTABLE_INST(T)
#define EXPECT_LONGS_EQUAL(expected, actual)
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
static Matrix RRTMbn(const Vector3 &euler)
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
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 const Vector3 kZero3
static Rot3 Yaw(double t)
Positive yaw is to right (as in aircraft heading). See ypr.
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 Velocity3 vel(0.4, 0.5, 0.6)
static const Point3 pt(1.0, 2.0, 3.0)
Eigen::Triplet< double > T
const Vector3 & v() const
Return velocity as Vector3. Computation-free.
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hp={}, OptionalJacobian< 3, 1 > Hr={})
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
Provides additional testing facilities for common data structures.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
PoseRTV transformed_from_proxy(const PoseRTV &a, const Pose3 &trans)
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
Double_ range(const Point2_ &p, const Point2_ &q)
Some functions to compute numerical derivatives.
PoseRTV compose_proxy(const PoseRTV &A, const PoseRTV &B)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static Rot3 Rodrigues(const Vector3 &w)
#define GTSAM_CONCEPT_LIE_INST(T)
const Velocity3 & v() const
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Pose3 with translational velocity.
Vector3 t() const
Return position as Vector3.
Matrix3 R() const
Return rotation matrix. Induces computation in quaternion mode.
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
static const NavState state2(x2, v2)
ProductLieGroup expmap(const TangentVector &v) const
double range_proxy(const PoseRTV &A, const PoseRTV &B)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
ProductLieGroup retract(const TangentVector &v, ChartJacobian H1={}, ChartJacobian H2={}) const
TangentVector logmap(const ProductLieGroup &g) const
TEST(SmartFactorBase, Pinhole)
Matrix trans(const Matrix &A)
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)
PoseRTV inverse_proxy(const PoseRTV &A)
PoseRTV between_proxy(const PoseRTV &A, const PoseRTV &B)
static Matrix RRTMnb(const Vector3 &euler)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
const Pose3 & pose() const
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
static const NavState state1(x1, v1)
double range(const PoseRTV &other, OptionalJacobian< 1, 9 > H1={}, OptionalJacobian< 1, 9 > H2={}) const
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Rot2 R(Rot2::fromAngle(0.1))
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:11