Go to the documentation of this file.
25 using namespace std::placeholders;
27 using namespace gtsam;
37 static const Vector9
kZeroXi = Vector9::Zero();
42 std::bind(&NavState::Create, std::placeholders::_1, std::placeholders::_2,
43 std::placeholders::_3,
nullptr,
nullptr,
nullptr);
62 std::bind(&NavState::FromPoseVelocity, std::placeholders::_1,
63 std::placeholders::_2,
nullptr,
nullptr);
77 eH = numericalDerivative11<Rot3, NavState>(
87 eH = numericalDerivative11<Point3, NavState>(
98 eH = numericalDerivative11<Velocity3, NavState>(
109 eH = numericalDerivative11<Velocity3, NavState>(
125 xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3;
144 std::placeholders::_2,
nullptr,
nullptr);
149 const Vector9 xi2 = -3.0*
xi;
156 std::bind(&NavState::localCoordinates, std::placeholders::_1,
157 std::placeholders::_2,
nullptr,
nullptr);
173 static const double dt = 2.0;
176 std::placeholders::_2,
nullptr);
211 double dt = 2.0, dt2 =
dt *
dt;
212 Vector3 n_omega(0.0, 0.0, 1.0), n_t(1.0, 0.0, 0.0), n_v(0.0, 1.0, 0.0);
213 Vector3 n_aCorr1 = -2.0 * n_omega.cross(n_v),
214 n_aCorr2 = -n_omega.cross(n_omega.cross(n_t));
215 Rot3 nRb =
Rot3(-1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 1.0, 0.0),
219 Vector3 n_dP1e = 0.5 * dt2 * n_aCorr1,
220 n_dP2e = 0.5 * dt2 * (n_aCorr1 + n_aCorr2),
221 n_dV1e =
dt * n_aCorr1,
222 n_dV2e =
dt * (n_aCorr1 + n_aCorr2);
226 b_dP1e = bRn * n_dP1e, b_dP2e = bRn * n_dP2e,
227 b_dV1e = bRn * n_dV1e, b_dV2e = bRn * n_dV2e;
231 Vector9 dXi1a = kState2.coriolis(
dt, n_omega,
false),
232 dXi2a = kState2.coriolis(
dt, n_omega,
true);
233 Vector3 dRa = NavState::dR(dXi1a),
234 b_dP1a = NavState::dP(dXi1a), b_dV1a = NavState::dV(dXi1a),
235 b_dP2a = NavState::dP(dXi2a), b_dV2a = NavState::dV(dXi2a);
248 xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3;
251 std::function<Vector9(
const NavState&,
const Vector9&)> correctPIM =
252 std::bind(&NavState::correctPIM, std::placeholders::_1,
265 std::ostringstream
os;
269 expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: 0 0 0\nv: 0 0 0";
static int runAllTests(TestResult &result)
ADT create(const Signature &signature)
static const Pose3 kPose(kAttitude, kPosition)
#define EXPECT(condition)
static const Velocity3 kVelocity(0.4, 0.5, 0.6)
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
static const Vector3 kOmegaCoriolis(0.02, 0.03, 0.04)
static const Rot3 kAttitude
static const Point3 kPosition(1.0, 2.0, 3.0)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
def retract(a, np.ndarray xi)
Velocity3 bodyVelocity(OptionalJacobian< 3, 9 > H={}) const
ofstream os("timeSchurFactors.csv")
int BLASFUNC() drot(int *, double *, int *, double *, int *, double *, double *)
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
Provides additional testing facilities for common data structures.
static const NavState kState1(kAttitude, kPosition, kVelocity)
Vector9 correctPIM(const Vector9 &pim, double dt, const Vector3 &n_gravity, const std::optional< Vector3 > &omegaCoriolis, bool use2ndOrderCoriolis=false, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
Rot3 attitude(const NavState &X, OptionalJacobian< 3, 9 > H)
Pose2_ Expmap(const Vector3_ &xi)
Some functions to compute numerical derivatives.
const Rot3 & attitude(OptionalJacobian< 3, 9 > H={}) const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Navigation state composing of attitude, position, and velocity.
static const Vector3 kGravity(0, 0, 9.81)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Velocity3 velocity(const NavState &X, OptionalJacobian< 3, 9 > H)
TEST(NavState, Constructor)
Vector3 bodyVelocity(const Pose3 &w_t_b, const Vector3 &vec_w, OptionalJacobian< 3, 6 > Hpose={}, OptionalJacobian< 3, 3 > Hvel={})
static const Vector9 kZeroXi
static const NavState state2(x2, v2)
static const NavState kIdentity
Rot3 inverse() const
inverse of a rotation
const Point3 & position(OptionalJacobian< 3, 9 > H={}) const
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)
std::function< Vector9(const NavState &, const bool &)> coriolis
Point3 position(const NavState &X, OptionalJacobian< 3, 9 > H)
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H={}) const
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
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
Vector9 coriolis(double dt, const Vector3 &omega, bool secondOrder=false, OptionalJacobian< 9, 9 > H={}) const
Compute tangent space contribution due to Coriolis forces.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:58