19 #include <gtsam/navigation/ImuFactor.h> 26 static noiseModel::Diagonal::shared_ptr Diagonal(
const Matrix& covariance) {
29 auto diagonal = boost::dynamic_pointer_cast<noiseModel::Diagonal>(model);
31 throw std::invalid_argument(
"ScenarioRunner::Diagonal: not a diagonal");
42 typedef boost::shared_ptr<PreintegrationParams> SharedParams;
46 const SharedParams p_;
47 const double imuSampleTime_, sqrt_dt_;
48 const Bias estimatedBias_;
51 mutable Sampler gyroSampler_, accSampler_;
55 double imuSampleTime = 1.0 / 100.0,
const Bias& bias =
Bias())
56 : scenario_(scenario),
58 imuSampleTime_(imuSampleTime),
59 sqrt_dt_(std::sqrt(imuSampleTime)),
62 gyroSampler_(Diagonal(p->gyroscopeCovariance), 10),
63 accSampler_(Diagonal(p->accelerometerCovariance), 29284) {}
67 const Vector3& gravity_n()
const {
return p_->n_gravity; }
70 Vector3 actualAngularVelocity(
double t)
const {
75 Vector3 actualSpecificForce(
double t)
const {
77 return scenario_.acceleration_b(t) - bRn * gravity_n();
81 Vector3 measuredAngularVelocity(
double t)
const {
82 return actualAngularVelocity(t) + estimatedBias_.
gyroscope() +
83 gyroSampler_.
sample() / sqrt_dt_;
85 Vector3 measuredSpecificForce(
double t)
const {
86 return actualSpecificForce(t) + estimatedBias_.
accelerometer() +
87 accSampler_.
sample() / sqrt_dt_;
90 const double& imuSampleTime()
const {
return imuSampleTime_; }
95 bool corrupted =
false)
const;
99 const Bias& estimatedBias =
Bias())
const;
103 const Bias& estimatedBias =
Bias())
const;
108 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 112 double imuSampleTime = 1.0 / 100.0,
const Bias& bias =
Bias())
Vector sample()
sample from distribution NOTE: not const due to need to update the underlying generator
Definition: Sampler.cpp:59
Navigation state: Pose (rotation, translation) + velocity NOTE(frank): it does not make sense to make...
Definition: NavState.h:34
NavState predict(const PreintegratedImuMeasurements &pim, const Bias &estimatedBias=Bias()) const
Predict predict given a PIM.
Definition: ScenarioRunner.cpp:50
PreintegratedImuMeasurements integrate(double T, const Bias &estimatedBias=Bias(), bool corrupted=false) const
Integrate measurements for T seconds into a PIM.
Definition: ScenarioRunner.cpp:32
const Vector3 & accelerometer() const
get accelerometer bias
Definition: ImuBias.h:59
sampling that can be parameterized using a NoiseModel to generate samples fromthe given distribution
Matrix3 transpose() const
Return 3*3 transpose (inverse) rotation matrix.
Definition: Rot3M.cpp:115
Definition: ScenarioRunner.h:39
Simple trajectory simulator.
Definition: Scenario.h:25
Sampling structure that keeps internal random number generators for diagonal distributions specified ...
Definition: Sampler.h:34
Matrix9 estimateCovariance(double T, size_t N=1000, const Bias &estimatedBias=Bias()) const
Compute a Monte Carlo estimate of the predict covariance using N samples.
Definition: ScenarioRunner.cpp:56
Definition: ImuFactor.h:71
const Vector3 & gyroscope() const
get gyroscope bias
Definition: ImuBias.h:64
Matrix6 estimateNoiseCovariance(size_t N=1000) const
Estimate covariance of sampled noise for sanity-check.
Definition: ScenarioRunner.cpp:86
Simple class to test navigation scenarios.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
static shared_ptr Covariance(const Matrix &covariance, bool smart=true)
A Gaussian noise model created by specifying a covariance matrix.
Definition: NoiseModel.cpp:112
virtual Vector3 omega_b(double t) const =0
angular velocity in body frame