From bcdfea37d9d06ddfba2f66d820cf2e444cc43aac Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 22 Dec 2015 19:28:49 -0800 Subject: [PATCH 1/7] pick out correct blocks --- gtsam/navigation/ScenarioRunner.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h index fa07b290f..310d96d6f 100644 --- a/gtsam/navigation/ScenarioRunner.h +++ b/gtsam/navigation/ScenarioRunner.h @@ -74,10 +74,10 @@ class ScenarioRunner { /// Return pose covariance by re-arranging pim.preintMeasCov() appropriately Matrix6 poseCovariance( const ImuFactor::PreintegratedMeasurements& pim) const { - Matrix9 cov = pim.preintMeasCov(); // _ position rotation + Matrix9 cov = pim.preintMeasCov(); Matrix6 poseCov; - poseCov << cov.block<3, 3>(6, 6), cov.block<3, 3>(6, 3), // - cov.block<3, 3>(3, 6), cov.block<3, 3>(3, 3); + poseCov << cov.block<3, 3>(6, 6), cov.block<3, 3>(6, 0), // + cov.block<3, 3>(0, 6), cov.block<3, 3>(0, 0); return poseCov; } From 4129c9651a1526ee6568f16dd02740fe36fcc2af Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 22 Dec 2015 19:29:27 -0800 Subject: [PATCH 2/7] Set up tests that pass --- gtsam/navigation/tests/testScenarioRunner.cpp | 36 ++++++++++++------- 1 file changed, 24 insertions(+), 12 deletions(-) diff --git a/gtsam/navigation/tests/testScenarioRunner.cpp b/gtsam/navigation/tests/testScenarioRunner.cpp index 517e488dd..42bffa1a5 100644 --- a/gtsam/navigation/tests/testScenarioRunner.cpp +++ b/gtsam/navigation/tests/testScenarioRunner.cpp @@ -22,48 +22,60 @@ using namespace std; using namespace gtsam; -static const double degree = M_PI / 180.0; +static const double kDegree = M_PI / 180.0; +static const double kDeltaT = 1e-2; +static const double kGyroSigma = 0.02; +static const double kAccelerometerSigma = 0.1; /* ************************************************************************* */ TEST(ScenarioRunner, Forward) { const double v = 2; // m/s - Scenario forward(Vector3::Zero(), Vector3(v, 0, 0), 1e-2, 0.000001, 1); + Scenario forward(Vector3::Zero(), Vector3(v, 0, 0), kDeltaT, kGyroSigma, + kAccelerometerSigma); ScenarioRunner runner(forward); - const double T = 1; // seconds + const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); EXPECT(assert_equal(forward.pose(T), runner.predict(pim).pose, 1e-9)); Matrix6 estimatedCov = runner.estimatePoseCovariance(T); - EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-9)); + EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); } /* ************************************************************************* */ TEST(ScenarioRunner, Circle) { - // Forward velocity 2m/s, angular velocity 6 degree/sec - const double v = 2, w = 6 * degree; - Scenario circle(Vector3(0, 0, w), Vector3(v, 0, 0)); + // Forward velocity 2m/s, angular velocity 6 kDegree/sec + const double v = 2, w = 6 * kDegree; + Scenario circle(Vector3(0, 0, w), Vector3(v, 0, 0), kDeltaT, kGyroSigma, + kAccelerometerSigma); ScenarioRunner runner(circle); - const double T = 15; // seconds + const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); EXPECT(assert_equal(circle.pose(T), runner.predict(pim).pose, 0.1)); + + Matrix6 estimatedCov = runner.estimatePoseCovariance(T); + EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); } /* ************************************************************************* */ TEST(ScenarioRunner, Loop) { // Forward velocity 2m/s - // Pitch up with angular velocity 6 degree/sec (negative in FLU) - const double v = 2, w = 6 * degree; - Scenario loop(Vector3(0, -w, 0), Vector3(v, 0, 0)); + // Pitch up with angular velocity 6 kDegree/sec (negative in FLU) + const double v = 2, w = 6 * kDegree; + Scenario loop(Vector3(0, -w, 0), Vector3(v, 0, 0), kDeltaT, kGyroSigma, + kAccelerometerSigma); ScenarioRunner runner(loop); - const double T = 30; // seconds + const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); EXPECT(assert_equal(loop.pose(T), runner.predict(pim).pose, 0.1)); + + Matrix6 estimatedCov = runner.estimatePoseCovariance(T); + EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); } /* ************************************************************************* */ From dfe3f3a34804fdbd7dc56146ccba47609d320d75 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 23 Dec 2015 09:21:54 -0800 Subject: [PATCH 3/7] Split off Scenario abstract base class --- gtsam/navigation/Scenario.h | 67 +++++++++++-------- gtsam/navigation/ScenarioRunner.h | 20 +++--- gtsam/navigation/tests/testScenario.cpp | 6 +- gtsam/navigation/tests/testScenarioRunner.cpp | 24 +++---- 4 files changed, 65 insertions(+), 52 deletions(-) diff --git a/gtsam/navigation/Scenario.h b/gtsam/navigation/Scenario.h index 2fae5bf74..58d6057b3 100644 --- a/gtsam/navigation/Scenario.h +++ b/gtsam/navigation/Scenario.h @@ -22,7 +22,7 @@ namespace gtsam { /** - * Simple IMU simulator with constant twist 3D trajectory. + * Simple IMU simulator. * It is also assumed that gravity is magically counteracted and has no effect * on trajectory. Hence, a simulated IMU yields the actual body angular * velocity, and negative G acceleration plus the acceleration created by the @@ -31,11 +31,9 @@ namespace gtsam { class Scenario { public: /// Construct scenario with constant twist [w,v] - Scenario(const Vector3& w, const Vector3& v, - double imuSampleTime = 1.0 / 100.0, double gyroSigma = 0.17, + Scenario(double imuSampleTime = 1.0 / 100.0, double gyroSigma = 0.17, double accSigma = 0.01) - : twist_((Vector6() << w, v).finished()), - imuSampleTime_(imuSampleTime), + : imuSampleTime_(imuSampleTime), gyroNoiseModel_(noiseModel::Isotropic::Sigma(3, gyroSigma)), accNoiseModel_(noiseModel::Isotropic::Sigma(3, accSigma)) {} @@ -56,43 +54,58 @@ class Scenario { Matrix3 gyroCovariance() const { return gyroNoiseModel_->covariance(); } Matrix3 accCovariance() const { return accNoiseModel_->covariance(); } - Vector3 angularVelocityInBody() const { return twist_.head<3>(); } - Vector3 linearVelocityInBody() const { return twist_.tail<3>(); } + /// Pose of body in nav frame at time t + virtual Pose3 pose(double t) const = 0; /// Rotation of body in nav frame at time t - Rot3 rotAtTime(double t) const { - return Rot3::Expmap(angularVelocityInBody() * t); - } + virtual Rot3 rotation(double t) const { return pose(t).rotation(); } - /// Pose of body in nav frame at time t - Pose3 pose(double t) const { return Pose3::Expmap(twist_ * t); } + virtual Vector3 angularVelocityInBody(double t) const = 0; + virtual Vector3 linearVelocityInBody(double t) const = 0; + virtual Vector3 accelerationInBody(double t) const = 0; /// Velocity in nav frame at time t Vector3 velocity(double t) const { - const Rot3 nRb = rotAtTime(t); - return nRb * linearVelocityInBody(); + return rotation(t) * linearVelocityInBody(t); } // acceleration in nav frame + // TODO(frank): correct for rotating frames? Vector3 acceleration(double t) const { - const Vector3 centripetalAcceleration = - angularVelocityInBody().cross(linearVelocityInBody()); - const Rot3 nRb = rotAtTime(t); - return nRb * centripetalAcceleration - gravity(); - } - - // acceleration in body frame frame - Vector3 accelerationInBody(double t) const { - const Vector3 centripetalAcceleration = - angularVelocityInBody().cross(linearVelocityInBody()); - const Rot3 nRb = rotAtTime(t); - return centripetalAcceleration - nRb.transpose() * gravity(); + return rotation(t) * accelerationInBody(t); } private: - Vector6 twist_; double imuSampleTime_; noiseModel::Diagonal::shared_ptr gyroNoiseModel_, accNoiseModel_; }; +/** + * Simple IMU simulator with constant twist 3D trajectory. + */ +class ExpmapScenario : public Scenario { + public: + /// Construct scenario with constant twist [w,v] + ExpmapScenario(const Vector3& w, const Vector3& v, + double imuSampleTime = 1.0 / 100.0, double gyroSigma = 0.17, + double accSigma = 0.01) + : Scenario(imuSampleTime, gyroSigma, accSigma), + twist_((Vector6() << w, v).finished()), + centripetalAcceleration_(twist_.head<3>().cross(twist_.tail<3>())) {} + + Pose3 pose(double t) const { return Pose3::Expmap(twist_ * t); } + + Vector3 angularVelocityInBody(double t) const { return twist_.head<3>(); } + Vector3 linearVelocityInBody(double t) const { return twist_.tail<3>(); } + + Vector3 accelerationInBody(double t) const { + const Rot3 nRb = rotation(t); + return centripetalAcceleration_ - nRb.transpose() * gravity(); + } + + private: + const Vector6 twist_; + const Vector3 centripetalAcceleration_; +}; + } // namespace gtsam diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h index 310d96d6f..048692a37 100644 --- a/gtsam/navigation/ScenarioRunner.h +++ b/gtsam/navigation/ScenarioRunner.h @@ -30,7 +30,7 @@ static const Matrix3 kIntegrationErrorCovariance = intNoiseVar * I_3x3; /// Simple class to test navigation scenarios class ScenarioRunner { public: - ScenarioRunner(const Scenario& scenario) : scenario_(scenario) {} + ScenarioRunner(const Scenario* scenario) : scenario_(scenario) {} /// Integrate measurements for T seconds into a PIM ImuFactor::PreintegratedMeasurements integrate( @@ -40,17 +40,17 @@ class ScenarioRunner { const bool use2ndOrderIntegration = true; ImuFactor::PreintegratedMeasurements pim( - zeroBias, scenario_.accCovariance(), scenario_.gyroCovariance(), + zeroBias, scenario_->accCovariance(), scenario_->gyroCovariance(), kIntegrationErrorCovariance, use2ndOrderIntegration); - const double dt = scenario_.imuSampleTime(); + const double dt = scenario_->imuSampleTime(); const double sqrt_dt = std::sqrt(dt); const size_t nrSteps = T / dt; double t = 0; for (size_t k = 0; k < nrSteps; k++, t += dt) { - Vector3 measuredOmega = scenario_.angularVelocityInBody(); + Vector3 measuredOmega = scenario_->angularVelocityInBody(t); if (gyroSampler) measuredOmega += gyroSampler->sample() / sqrt_dt; - Vector3 measuredAcc = scenario_.accelerationInBody(t); + Vector3 measuredAcc = scenario_->accelerationInBody(t); if (accSampler) measuredAcc += accSampler->sample() / sqrt_dt; pim.integrateMeasurement(measuredAcc, measuredOmega, dt); } @@ -64,10 +64,10 @@ class ScenarioRunner { // TODO(frank): allow non-zero bias, omegaCoriolis const imuBias::ConstantBias zeroBias; const Pose3 pose_i = Pose3::identity(); - const Vector3 vel_i = scenario_.velocity(0); + const Vector3 vel_i = scenario_->velocity(0); const Vector3 omegaCoriolis = Vector3::Zero(); const bool use2ndOrderCoriolis = true; - return pim.predict(pose_i, vel_i, zeroBias, scenario_.gravity(), + return pim.predict(pose_i, vel_i, zeroBias, scenario_->gravity(), omegaCoriolis, use2ndOrderCoriolis); } @@ -87,8 +87,8 @@ class ScenarioRunner { Pose3 prediction = predict(integrate(T)).pose; // Create two samplers for acceleration and omega noise - Sampler gyroSampler(scenario_.gyroNoiseModel(), 10); - Sampler accSampler(scenario_.accNoiseModel(), 29284); + Sampler gyroSampler(scenario_->gyroNoiseModel(), 10); + Sampler accSampler(scenario_->accNoiseModel(), 29284); // Sample ! Matrix samples(9, N); @@ -114,7 +114,7 @@ class ScenarioRunner { } private: - Scenario scenario_; + const Scenario* scenario_; }; } // namespace gtsam diff --git a/gtsam/navigation/tests/testScenario.cpp b/gtsam/navigation/tests/testScenario.cpp index ae406f953..ffac96902 100644 --- a/gtsam/navigation/tests/testScenario.cpp +++ b/gtsam/navigation/tests/testScenario.cpp @@ -27,7 +27,7 @@ static const double degree = M_PI / 180.0; /* ************************************************************************* */ TEST(Scenario, Forward) { const double v = 2; // m/s - Scenario forward(Vector3::Zero(), Vector3(v, 0, 0)); + ExpmapScenario forward(Vector3::Zero(), Vector3(v, 0, 0)); const Pose3 T15 = forward.pose(15); EXPECT(assert_equal(Vector3(0, 0, 0), T15.rotation().xyz(), 1e-9)); @@ -38,7 +38,7 @@ TEST(Scenario, Forward) { TEST(Scenario, Circle) { // Forward velocity 2m/s, angular velocity 6 degree/sec around Z const double v = 2, w = 6 * degree; - Scenario circle(Vector3(0, 0, w), Vector3(v, 0, 0)); + ExpmapScenario circle(Vector3(0, 0, w), Vector3(v, 0, 0)); // R = v/w, so test if circle is of right size const double R = v / w; @@ -52,7 +52,7 @@ TEST(Scenario, Loop) { // Forward velocity 2m/s // Pitch up with angular velocity 6 degree/sec (negative in FLU) const double v = 2, w = 6 * degree; - Scenario loop(Vector3(0, -w, 0), Vector3(v, 0, 0)); + ExpmapScenario loop(Vector3(0, -w, 0), Vector3(v, 0, 0)); // R = v/w, so test if loop crests at 2*R const double R = v / w; diff --git a/gtsam/navigation/tests/testScenarioRunner.cpp b/gtsam/navigation/tests/testScenarioRunner.cpp index 42bffa1a5..3a6b63b92 100644 --- a/gtsam/navigation/tests/testScenarioRunner.cpp +++ b/gtsam/navigation/tests/testScenarioRunner.cpp @@ -30,14 +30,14 @@ static const double kAccelerometerSigma = 0.1; /* ************************************************************************* */ TEST(ScenarioRunner, Forward) { const double v = 2; // m/s - Scenario forward(Vector3::Zero(), Vector3(v, 0, 0), kDeltaT, kGyroSigma, - kAccelerometerSigma); + ExpmapScenario scenario(Vector3::Zero(), Vector3(v, 0, 0), kDeltaT, + kGyroSigma, kAccelerometerSigma); - ScenarioRunner runner(forward); + ScenarioRunner runner(&scenario); const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); - EXPECT(assert_equal(forward.pose(T), runner.predict(pim).pose, 1e-9)); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9)); Matrix6 estimatedCov = runner.estimatePoseCovariance(T); EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); @@ -47,14 +47,14 @@ TEST(ScenarioRunner, Forward) { TEST(ScenarioRunner, Circle) { // Forward velocity 2m/s, angular velocity 6 kDegree/sec const double v = 2, w = 6 * kDegree; - Scenario circle(Vector3(0, 0, w), Vector3(v, 0, 0), kDeltaT, kGyroSigma, - kAccelerometerSigma); + ExpmapScenario scenario(Vector3(0, 0, w), Vector3(v, 0, 0), kDeltaT, + kGyroSigma, kAccelerometerSigma); - ScenarioRunner runner(circle); + ScenarioRunner runner(&scenario); const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); - EXPECT(assert_equal(circle.pose(T), runner.predict(pim).pose, 0.1)); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 0.1)); Matrix6 estimatedCov = runner.estimatePoseCovariance(T); EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); @@ -65,14 +65,14 @@ TEST(ScenarioRunner, Loop) { // Forward velocity 2m/s // Pitch up with angular velocity 6 kDegree/sec (negative in FLU) const double v = 2, w = 6 * kDegree; - Scenario loop(Vector3(0, -w, 0), Vector3(v, 0, 0), kDeltaT, kGyroSigma, - kAccelerometerSigma); + ExpmapScenario scenario(Vector3(0, -w, 0), Vector3(v, 0, 0), kDeltaT, + kGyroSigma, kAccelerometerSigma); - ScenarioRunner runner(loop); + ScenarioRunner runner(&scenario); const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); - EXPECT(assert_equal(loop.pose(T), runner.predict(pim).pose, 0.1)); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 0.1)); Matrix6 estimatedCov = runner.estimatePoseCovariance(T); EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); From 00b83ced7aabd41cfe895fdc046792d356f20a8a Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 23 Dec 2015 11:15:42 -0800 Subject: [PATCH 4/7] AcceleratingScenario + some refactoring (v and a specified in nav frame) --- gtsam/navigation/Scenario.h | 71 ++++++++++++------- gtsam/navigation/ScenarioRunner.h | 6 +- gtsam/navigation/tests/testScenario.cpp | 53 ++++++++++++-- gtsam/navigation/tests/testScenarioRunner.cpp | 24 +++++++ 4 files changed, 118 insertions(+), 36 deletions(-) diff --git a/gtsam/navigation/Scenario.h b/gtsam/navigation/Scenario.h index 58d6057b3..69b5dfa00 100644 --- a/gtsam/navigation/Scenario.h +++ b/gtsam/navigation/Scenario.h @@ -54,25 +54,25 @@ class Scenario { Matrix3 gyroCovariance() const { return gyroNoiseModel_->covariance(); } Matrix3 accCovariance() const { return accNoiseModel_->covariance(); } - /// Pose of body in nav frame at time t - virtual Pose3 pose(double t) const = 0; + // Quantities a Scenario needs to specify: + + virtual Pose3 pose(double t) const = 0; + virtual Vector3 omega_b(double t) const = 0; + virtual Vector3 velocity_n(double t) const = 0; + virtual Vector3 acceleration_n(double t) const = 0; + + // Derived quantities: - /// Rotation of body in nav frame at time t virtual Rot3 rotation(double t) const { return pose(t).rotation(); } - virtual Vector3 angularVelocityInBody(double t) const = 0; - virtual Vector3 linearVelocityInBody(double t) const = 0; - virtual Vector3 accelerationInBody(double t) const = 0; - - /// Velocity in nav frame at time t - Vector3 velocity(double t) const { - return rotation(t) * linearVelocityInBody(t); + Vector3 velocity_b(double t) const { + const Rot3 nRb = rotation(t); + return nRb.transpose() * velocity_n(t); } - // acceleration in nav frame - // TODO(frank): correct for rotating frames? - Vector3 acceleration(double t) const { - return rotation(t) * accelerationInBody(t); + Vector3 acceleration_b(double t) const { + const Rot3 nRb = rotation(t); + return nRb.transpose() * acceleration_n(t); } private: @@ -80,9 +80,7 @@ class Scenario { noiseModel::Diagonal::shared_ptr gyroNoiseModel_, accNoiseModel_; }; -/** - * Simple IMU simulator with constant twist 3D trajectory. - */ +/// Scenario with constant twist 3D trajectory. class ExpmapScenario : public Scenario { public: /// Construct scenario with constant twist [w,v] @@ -91,21 +89,40 @@ class ExpmapScenario : public Scenario { double accSigma = 0.01) : Scenario(imuSampleTime, gyroSigma, accSigma), twist_((Vector6() << w, v).finished()), - centripetalAcceleration_(twist_.head<3>().cross(twist_.tail<3>())) {} + a_b_(twist_.head<3>().cross(twist_.tail<3>())) {} Pose3 pose(double t) const { return Pose3::Expmap(twist_ * t); } - - Vector3 angularVelocityInBody(double t) const { return twist_.head<3>(); } - Vector3 linearVelocityInBody(double t) const { return twist_.tail<3>(); } - - Vector3 accelerationInBody(double t) const { - const Rot3 nRb = rotation(t); - return centripetalAcceleration_ - nRb.transpose() * gravity(); - } + Vector3 omega_b(double t) const { return twist_.head<3>(); } + Vector3 velocity_n(double t) const { return rotation(t) * twist_.tail<3>(); } + Vector3 acceleration_n(double t) const { return rotation(t) * a_b_; } private: const Vector6 twist_; - const Vector3 centripetalAcceleration_; + const Vector3 a_b_; // constant centripetal acceleration in body = w_b * v_b +}; + +/// Accelerating from an arbitrary initial state +class AcceleratingScenario : public Scenario { + public: + /// Construct scenario with constant twist [w,v] + AcceleratingScenario(const Rot3& nRb, const Point3& p0, const Vector3& v0, + const Vector3& accelerationInBody, + double imuSampleTime = 1.0 / 100.0, + double gyroSigma = 0.17, double accSigma = 0.01) + : Scenario(imuSampleTime, gyroSigma, accSigma), + nRb_(nRb), + p0_(p0.vector()), + v0_(v0), + a_n_(nRb_ * accelerationInBody) {} + + Pose3 pose(double t) const { return Pose3(nRb_, p0_ + a_n_ * t * t / 2.0); } + Vector3 omega_b(double t) const { return Vector3::Zero(); } + Vector3 velocity_n(double t) const { return v0_ + a_n_ * t; } + Vector3 acceleration_n(double t) const { return a_n_; } + + private: + const Rot3 nRb_; + const Vector3 p0_, v0_, a_n_; }; } // namespace gtsam diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h index 048692a37..40f5f8585 100644 --- a/gtsam/navigation/ScenarioRunner.h +++ b/gtsam/navigation/ScenarioRunner.h @@ -48,9 +48,9 @@ class ScenarioRunner { const size_t nrSteps = T / dt; double t = 0; for (size_t k = 0; k < nrSteps; k++, t += dt) { - Vector3 measuredOmega = scenario_->angularVelocityInBody(t); + Vector3 measuredOmega = scenario_->omega_b(t); if (gyroSampler) measuredOmega += gyroSampler->sample() / sqrt_dt; - Vector3 measuredAcc = scenario_->accelerationInBody(t); + Vector3 measuredAcc = scenario_->acceleration_b(t); if (accSampler) measuredAcc += accSampler->sample() / sqrt_dt; pim.integrateMeasurement(measuredAcc, measuredOmega, dt); } @@ -64,7 +64,7 @@ class ScenarioRunner { // TODO(frank): allow non-zero bias, omegaCoriolis const imuBias::ConstantBias zeroBias; const Pose3 pose_i = Pose3::identity(); - const Vector3 vel_i = scenario_->velocity(0); + const Vector3 vel_i = scenario_->velocity_n(0); const Vector3 omegaCoriolis = Vector3::Zero(); const bool use2ndOrderCoriolis = true; return pim.predict(pose_i, vel_i, zeroBias, scenario_->gravity(), diff --git a/gtsam/navigation/tests/testScenario.cpp b/gtsam/navigation/tests/testScenario.cpp index ffac96902..b975440c7 100644 --- a/gtsam/navigation/tests/testScenario.cpp +++ b/gtsam/navigation/tests/testScenario.cpp @@ -27,9 +27,15 @@ static const double degree = M_PI / 180.0; /* ************************************************************************* */ TEST(Scenario, Forward) { const double v = 2; // m/s - ExpmapScenario forward(Vector3::Zero(), Vector3(v, 0, 0)); + const Vector3 W(0, 0, 0), V(v, 0, 0); + const ExpmapScenario scenario(W, V); - const Pose3 T15 = forward.pose(15); + const double T = 15; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(V, scenario.velocity_b(T), 1e-9)); + EXPECT(assert_equal(W.cross(V), scenario.acceleration_b(T), 1e-9)); + + const Pose3 T15 = scenario.pose(T); EXPECT(assert_equal(Vector3(0, 0, 0), T15.rotation().xyz(), 1e-9)); EXPECT(assert_equal(Point3(30, 0, 0), T15.translation(), 1e-9)); } @@ -38,11 +44,17 @@ TEST(Scenario, Forward) { TEST(Scenario, Circle) { // Forward velocity 2m/s, angular velocity 6 degree/sec around Z const double v = 2, w = 6 * degree; - ExpmapScenario circle(Vector3(0, 0, w), Vector3(v, 0, 0)); + const Vector3 W(0, 0, w), V(v, 0, 0); + const ExpmapScenario scenario(W, V); + + const double T = 15; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(V, scenario.velocity_b(T), 1e-9)); + EXPECT(assert_equal(W.cross(V), scenario.acceleration_b(T), 1e-9)); // R = v/w, so test if circle is of right size const double R = v / w; - const Pose3 T15 = circle.pose(15); + const Pose3 T15 = scenario.pose(T); EXPECT(assert_equal(Vector3(0, 0, 90 * degree), T15.rotation().xyz(), 1e-9)); EXPECT(assert_equal(Point3(R, R, 0), T15.translation(), 1e-9)); } @@ -52,15 +64,44 @@ TEST(Scenario, Loop) { // Forward velocity 2m/s // Pitch up with angular velocity 6 degree/sec (negative in FLU) const double v = 2, w = 6 * degree; - ExpmapScenario loop(Vector3(0, -w, 0), Vector3(v, 0, 0)); + const Vector3 W(0, -w, 0), V(v, 0, 0); + const ExpmapScenario scenario(W, V); + + const double T = 30; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(V, scenario.velocity_b(T), 1e-9)); + EXPECT(assert_equal(W.cross(V), scenario.acceleration_b(T), 1e-9)); // R = v/w, so test if loop crests at 2*R const double R = v / w; - const Pose3 T30 = loop.pose(30); + const Pose3 T30 = scenario.pose(30); EXPECT(assert_equal(Vector3(-M_PI, 0, -M_PI), T30.rotation().xyz(), 1e-9)); EXPECT(assert_equal(Point3(0, 0, 2 * R), T30.translation(), 1e-9)); } +/* ************************************************************************* */ +TEST(Scenario, Accelerating) { + // Set up body pointing towards y axis, and start at 10,20,0 with velocity + // going in X. The body itself has Z axis pointing down + const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); + const Point3 P0(10, 20, 0); + const Vector3 V0(50, 0, 0); + + const double a_b = 0.2; // m/s^2 + const AcceleratingScenario scenario(nRb, P0, V0, Vector3(a_b, 0, 0)); + + const double T = 3; + const Vector3 A = nRb * Vector3(a_b, 0, 0); + EXPECT(assert_equal(Vector3(0, 0, 0), scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(Vector3(V0 + T * A), scenario.velocity_n(T), 1e-9)); + EXPECT(assert_equal(A, scenario.acceleration_n(T), 1e-9)); + + const Pose3 T3 = scenario.pose(3); + EXPECT(assert_equal(nRb, T3.rotation(), 1e-9)); + EXPECT(assert_equal(Point3(P0.vector() + T * T * A / 2.0), T3.translation(), + 1e-9)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/navigation/tests/testScenarioRunner.cpp b/gtsam/navigation/tests/testScenarioRunner.cpp index 3a6b63b92..15c2456b6 100644 --- a/gtsam/navigation/tests/testScenarioRunner.cpp +++ b/gtsam/navigation/tests/testScenarioRunner.cpp @@ -78,6 +78,30 @@ TEST(ScenarioRunner, Loop) { EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); } +/* ************************************************************************* */ +TEST(ScenarioRunner, Accelerating) { + // Set up body pointing towards y axis, and start at 10,20,0 with velocity + // going in X + // The body itself has Z axis pointing down + const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); + const Point3 initial_position(10, 20, 0); + const Vector3 initial_velocity(50, 0, 0); + + const double a = 0.2, dt = 3.0; + AcceleratingScenario scenario(nRb, initial_velocity, initial_velocity, + Vector3(a, 0, 0), dt / 10, kGyroSigma, + kAccelerometerSigma); + + ScenarioRunner runner(&scenario); + const double T = 3; // seconds + + ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9)); + + Matrix6 estimatedCov = runner.estimatePoseCovariance(T); + EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); +} + /* ************************************************************************* */ int main() { TestResult tr; From dc2bac5a9e8330b42590e66afc9d9feb5bcbe829 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 23 Dec 2015 11:33:52 -0800 Subject: [PATCH 5/7] Moved all noise/sampling of IMU to ScenarioRunner --- gtsam/navigation/Scenario.h | 54 +++---------------- gtsam/navigation/ScenarioRunner.h | 43 +++++++++++---- gtsam/navigation/tests/testScenarioRunner.cpp | 30 +++++------ 3 files changed, 51 insertions(+), 76 deletions(-) diff --git a/gtsam/navigation/Scenario.h b/gtsam/navigation/Scenario.h index 69b5dfa00..421507d92 100644 --- a/gtsam/navigation/Scenario.h +++ b/gtsam/navigation/Scenario.h @@ -21,39 +21,9 @@ namespace gtsam { -/** - * Simple IMU simulator. - * It is also assumed that gravity is magically counteracted and has no effect - * on trajectory. Hence, a simulated IMU yields the actual body angular - * velocity, and negative G acceleration plus the acceleration created by the - * rotating body frame. - */ +/// Simple trajectory simulator. class Scenario { public: - /// Construct scenario with constant twist [w,v] - Scenario(double imuSampleTime = 1.0 / 100.0, double gyroSigma = 0.17, - double accSigma = 0.01) - : imuSampleTime_(imuSampleTime), - gyroNoiseModel_(noiseModel::Isotropic::Sigma(3, gyroSigma)), - accNoiseModel_(noiseModel::Isotropic::Sigma(3, accSigma)) {} - - const double& imuSampleTime() const { return imuSampleTime_; } - - // NOTE(frank): hardcoded for now with Z up (gravity points in negative Z) - // also, uses g=10 for easy debugging - Vector3 gravity() const { return Vector3(0, 0, -10.0); } - - const noiseModel::Diagonal::shared_ptr& gyroNoiseModel() const { - return gyroNoiseModel_; - } - - const noiseModel::Diagonal::shared_ptr& accNoiseModel() const { - return accNoiseModel_; - } - - Matrix3 gyroCovariance() const { return gyroNoiseModel_->covariance(); } - Matrix3 accCovariance() const { return accNoiseModel_->covariance(); } - // Quantities a Scenario needs to specify: virtual Pose3 pose(double t) const = 0; @@ -74,24 +44,18 @@ class Scenario { const Rot3 nRb = rotation(t); return nRb.transpose() * acceleration_n(t); } - - private: - double imuSampleTime_; - noiseModel::Diagonal::shared_ptr gyroNoiseModel_, accNoiseModel_; }; /// Scenario with constant twist 3D trajectory. class ExpmapScenario : public Scenario { public: /// Construct scenario with constant twist [w,v] - ExpmapScenario(const Vector3& w, const Vector3& v, - double imuSampleTime = 1.0 / 100.0, double gyroSigma = 0.17, - double accSigma = 0.01) - : Scenario(imuSampleTime, gyroSigma, accSigma), - twist_((Vector6() << w, v).finished()), + ExpmapScenario(const Vector3& w, const Vector3& v) + : twist_((Vector6() << w, v).finished()), a_b_(twist_.head<3>().cross(twist_.tail<3>())) {} Pose3 pose(double t) const { return Pose3::Expmap(twist_ * t); } + Rot3 rotation(double t) const { return Rot3::Expmap(twist_.head<3>() * t); } Vector3 omega_b(double t) const { return twist_.head<3>(); } Vector3 velocity_n(double t) const { return rotation(t) * twist_.tail<3>(); } Vector3 acceleration_n(double t) const { return rotation(t) * a_b_; } @@ -106,14 +70,8 @@ class AcceleratingScenario : public Scenario { public: /// Construct scenario with constant twist [w,v] AcceleratingScenario(const Rot3& nRb, const Point3& p0, const Vector3& v0, - const Vector3& accelerationInBody, - double imuSampleTime = 1.0 / 100.0, - double gyroSigma = 0.17, double accSigma = 0.01) - : Scenario(imuSampleTime, gyroSigma, accSigma), - nRb_(nRb), - p0_(p0.vector()), - v0_(v0), - a_n_(nRb_ * accelerationInBody) {} + const Vector3& accelerationInBody) + : nRb_(nRb), p0_(p0.vector()), v0_(v0), a_n_(nRb_ * accelerationInBody) {} Pose3 pose(double t) const { return Pose3(nRb_, p0_ + a_n_ * t * t / 2.0); } Vector3 omega_b(double t) const { return Vector3::Zero(); } diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h index 40f5f8585..60cc9a751 100644 --- a/gtsam/navigation/ScenarioRunner.h +++ b/gtsam/navigation/ScenarioRunner.h @@ -30,7 +30,29 @@ static const Matrix3 kIntegrationErrorCovariance = intNoiseVar * I_3x3; /// Simple class to test navigation scenarios class ScenarioRunner { public: - ScenarioRunner(const Scenario* scenario) : scenario_(scenario) {} + ScenarioRunner(const Scenario* scenario, double imuSampleTime = 1.0 / 100.0, + double gyroSigma = 0.17, double accSigma = 0.01) + : scenario_(scenario), + imuSampleTime_(imuSampleTime), + gyroNoiseModel_(noiseModel::Isotropic::Sigma(3, gyroSigma)), + accNoiseModel_(noiseModel::Isotropic::Sigma(3, accSigma)) {} + + const double& imuSampleTime() const { return imuSampleTime_; } + + // NOTE(frank): hardcoded for now with Z up (gravity points in negative Z) + // also, uses g=10 for easy debugging + Vector3 gravity_n() const { return Vector3(0, 0, -10.0); } + + const noiseModel::Diagonal::shared_ptr& gyroNoiseModel() const { + return gyroNoiseModel_; + } + + const noiseModel::Diagonal::shared_ptr& accNoiseModel() const { + return accNoiseModel_; + } + + Matrix3 gyroCovariance() const { return gyroNoiseModel_->covariance(); } + Matrix3 accCovariance() const { return accNoiseModel_->covariance(); } /// Integrate measurements for T seconds into a PIM ImuFactor::PreintegratedMeasurements integrate( @@ -40,17 +62,18 @@ class ScenarioRunner { const bool use2ndOrderIntegration = true; ImuFactor::PreintegratedMeasurements pim( - zeroBias, scenario_->accCovariance(), scenario_->gyroCovariance(), + zeroBias, accCovariance(), gyroCovariance(), kIntegrationErrorCovariance, use2ndOrderIntegration); - const double dt = scenario_->imuSampleTime(); + const double dt = imuSampleTime(); const double sqrt_dt = std::sqrt(dt); const size_t nrSteps = T / dt; double t = 0; for (size_t k = 0; k < nrSteps; k++, t += dt) { + Rot3 bRn = scenario_->rotation(t).transpose(); Vector3 measuredOmega = scenario_->omega_b(t); if (gyroSampler) measuredOmega += gyroSampler->sample() / sqrt_dt; - Vector3 measuredAcc = scenario_->acceleration_b(t); + Vector3 measuredAcc = scenario_->acceleration_b(t) - bRn * gravity_n(); if (accSampler) measuredAcc += accSampler->sample() / sqrt_dt; pim.integrateMeasurement(measuredAcc, measuredOmega, dt); } @@ -63,12 +86,10 @@ class ScenarioRunner { const ImuFactor::PreintegratedMeasurements& pim) const { // TODO(frank): allow non-zero bias, omegaCoriolis const imuBias::ConstantBias zeroBias; - const Pose3 pose_i = Pose3::identity(); - const Vector3 vel_i = scenario_->velocity_n(0); const Vector3 omegaCoriolis = Vector3::Zero(); const bool use2ndOrderCoriolis = true; - return pim.predict(pose_i, vel_i, zeroBias, scenario_->gravity(), - omegaCoriolis, use2ndOrderCoriolis); + return pim.predict(scenario_->pose(0), scenario_->velocity_n(0), zeroBias, + gravity_n(), omegaCoriolis, use2ndOrderCoriolis); } /// Return pose covariance by re-arranging pim.preintMeasCov() appropriately @@ -87,8 +108,8 @@ class ScenarioRunner { Pose3 prediction = predict(integrate(T)).pose; // Create two samplers for acceleration and omega noise - Sampler gyroSampler(scenario_->gyroNoiseModel(), 10); - Sampler accSampler(scenario_->accNoiseModel(), 29284); + Sampler gyroSampler(gyroNoiseModel(), 10); + Sampler accSampler(accNoiseModel(), 29284); // Sample ! Matrix samples(9, N); @@ -115,6 +136,8 @@ class ScenarioRunner { private: const Scenario* scenario_; + double imuSampleTime_; + noiseModel::Diagonal::shared_ptr gyroNoiseModel_, accNoiseModel_; }; } // namespace gtsam diff --git a/gtsam/navigation/tests/testScenarioRunner.cpp b/gtsam/navigation/tests/testScenarioRunner.cpp index 15c2456b6..c7a3216a9 100644 --- a/gtsam/navigation/tests/testScenarioRunner.cpp +++ b/gtsam/navigation/tests/testScenarioRunner.cpp @@ -30,10 +30,9 @@ static const double kAccelerometerSigma = 0.1; /* ************************************************************************* */ TEST(ScenarioRunner, Forward) { const double v = 2; // m/s - ExpmapScenario scenario(Vector3::Zero(), Vector3(v, 0, 0), kDeltaT, - kGyroSigma, kAccelerometerSigma); + ExpmapScenario scenario(Vector3::Zero(), Vector3(v, 0, 0)); - ScenarioRunner runner(&scenario); + ScenarioRunner runner(&scenario, kDeltaT, kGyroSigma, kAccelerometerSigma); const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); @@ -47,10 +46,9 @@ TEST(ScenarioRunner, Forward) { TEST(ScenarioRunner, Circle) { // Forward velocity 2m/s, angular velocity 6 kDegree/sec const double v = 2, w = 6 * kDegree; - ExpmapScenario scenario(Vector3(0, 0, w), Vector3(v, 0, 0), kDeltaT, - kGyroSigma, kAccelerometerSigma); + ExpmapScenario scenario(Vector3(0, 0, w), Vector3(v, 0, 0)); - ScenarioRunner runner(&scenario); + ScenarioRunner runner(&scenario, kDeltaT, kGyroSigma, kAccelerometerSigma); const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); @@ -65,10 +63,9 @@ TEST(ScenarioRunner, Loop) { // Forward velocity 2m/s // Pitch up with angular velocity 6 kDegree/sec (negative in FLU) const double v = 2, w = 6 * kDegree; - ExpmapScenario scenario(Vector3(0, -w, 0), Vector3(v, 0, 0), kDeltaT, - kGyroSigma, kAccelerometerSigma); + ExpmapScenario scenario(Vector3(0, -w, 0), Vector3(v, 0, 0)); - ScenarioRunner runner(&scenario); + ScenarioRunner runner(&scenario, kDeltaT, kGyroSigma, kAccelerometerSigma); const double T = 0.1; // seconds ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); @@ -81,19 +78,16 @@ TEST(ScenarioRunner, Loop) { /* ************************************************************************* */ TEST(ScenarioRunner, Accelerating) { // Set up body pointing towards y axis, and start at 10,20,0 with velocity - // going in X - // The body itself has Z axis pointing down + // going in X. The body itself has Z axis pointing down const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); - const Point3 initial_position(10, 20, 0); - const Vector3 initial_velocity(50, 0, 0); + const Point3 P0(10, 20, 0); + const Vector3 V0(50, 0, 0); - const double a = 0.2, dt = 3.0; - AcceleratingScenario scenario(nRb, initial_velocity, initial_velocity, - Vector3(a, 0, 0), dt / 10, kGyroSigma, - kAccelerometerSigma); + const double a_b = 0.2; // m/s^2 + const AcceleratingScenario scenario(nRb, P0, V0, Vector3(a_b, 0, 0)); - ScenarioRunner runner(&scenario); const double T = 3; // seconds + ScenarioRunner runner(&scenario, T / 10, kGyroSigma, kAccelerometerSigma); ImuFactor::PreintegratedMeasurements pim = runner.integrate(T); EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9)); From ccef2faa95a345c79f3f988c9b585c6c4a9274be Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 23 Dec 2015 11:58:41 -0800 Subject: [PATCH 6/7] Fixed pose of accelerating trajectory --- gtsam/navigation/Scenario.h | 4 +++- gtsam/navigation/tests/testScenario.cpp | 4 ++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/Scenario.h b/gtsam/navigation/Scenario.h index 421507d92..7badd6d4e 100644 --- a/gtsam/navigation/Scenario.h +++ b/gtsam/navigation/Scenario.h @@ -73,7 +73,9 @@ class AcceleratingScenario : public Scenario { const Vector3& accelerationInBody) : nRb_(nRb), p0_(p0.vector()), v0_(v0), a_n_(nRb_ * accelerationInBody) {} - Pose3 pose(double t) const { return Pose3(nRb_, p0_ + a_n_ * t * t / 2.0); } + Pose3 pose(double t) const { + return Pose3(nRb_, p0_ + v0_ * t + a_n_ * t * t / 2.0); + } Vector3 omega_b(double t) const { return Vector3::Zero(); } Vector3 velocity_n(double t) const { return v0_ + a_n_ * t; } Vector3 acceleration_n(double t) const { return a_n_; } diff --git a/gtsam/navigation/tests/testScenario.cpp b/gtsam/navigation/tests/testScenario.cpp index b975440c7..c029ecc03 100644 --- a/gtsam/navigation/tests/testScenario.cpp +++ b/gtsam/navigation/tests/testScenario.cpp @@ -98,8 +98,8 @@ TEST(Scenario, Accelerating) { const Pose3 T3 = scenario.pose(3); EXPECT(assert_equal(nRb, T3.rotation(), 1e-9)); - EXPECT(assert_equal(Point3(P0.vector() + T * T * A / 2.0), T3.translation(), - 1e-9)); + EXPECT(assert_equal(Point3(10 + T * 50, 20 + a_b * T * T / 2, 0), + T3.translation(), 1e-9)); } /* ************************************************************************* */ From 30946af98162e7e8c34e4fb57c3fe24ec87cd1ac Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 23 Dec 2015 11:59:56 -0800 Subject: [PATCH 7/7] Acceleration scenario tested --- gtsam/navigation/tests/testScenarioRunner.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/navigation/tests/testScenarioRunner.cpp b/gtsam/navigation/tests/testScenarioRunner.cpp index c7a3216a9..b7a864016 100644 --- a/gtsam/navigation/tests/testScenarioRunner.cpp +++ b/gtsam/navigation/tests/testScenarioRunner.cpp @@ -93,7 +93,7 @@ TEST(ScenarioRunner, Accelerating) { EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9)); Matrix6 estimatedCov = runner.estimatePoseCovariance(T); - EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 1e-5)); + EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 0.1)); } /* ************************************************************************* */