53 const Vector3& biasHat) :
58 const Params& p()
const {
return *boost::static_pointer_cast<const Params>(p_);}
59 const Vector3& biasHat()
const {
return biasHat_; }
60 const Matrix3& preintMeasCov()
const {
return preintMeasCov_; }
63 void print(
const std::string& s =
"Preintegrated Measurements: ")
const;
66 bool equals(
const PreintegratedAhrsMeasurements&,
double tol = 1e-9)
const;
69 void resetIntegration();
76 void integrateMeasurement(
const Vector3& measuredOmega,
double deltaT);
80 Vector3 predict(
const Vector3& bias, OptionalJacobian<3,3> H = boost::none)
const;
84 static Vector DeltaAngles(
const Vector& msr_gyro_t,
const double msr_dt,
85 const Vector3& delta_angles);
89 const Matrix3& measuredOmegaCovariance)
92 p_->gyroscopeCovariance = measuredOmegaCovariance;
99 friend class boost::serialization::access;
100 template<
class ARCHIVE>
101 void serialize(ARCHIVE & ar,
const unsigned int ) {
103 ar & BOOST_SERIALIZATION_NVP(p_);
104 ar & BOOST_SERIALIZATION_NVP(biasHat_);
121 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5 122 typedef typename boost::shared_ptr<AHRSFactor> shared_ptr;
141 virtual gtsam::NonlinearFactor::shared_ptr clone()
const;
145 DefaultKeyFormatter)
const;
157 Vector evaluateError(
const Rot3& rot_i,
const Rot3& rot_j,
159 const Vector3& bias, boost::optional<Matrix&> H1 = boost::none,
160 boost::optional<Matrix&> H2 = boost::none, boost::optional<Matrix&> H3 =
166 const Rot3& rot_i,
const Vector3& bias,
175 const Vector3& omegaCoriolis,
176 const boost::optional<Pose3>& body_P_sensor = boost::none);
179 static Rot3 predict(
const Rot3& rot_i,
const Vector3& bias,
181 const Vector3& omegaCoriolis,
182 const boost::optional<Pose3>& body_P_sensor = boost::none);
187 friend class boost::serialization::access;
188 template<
class ARCHIVE>
189 void serialize(ARCHIVE & ar,
const unsigned int ) {
191 & boost::serialization::make_nvp(
"NoiseModelFactor3",
192 boost::serialization::base_object<Base>(*
this));
193 ar & BOOST_SERIALIZATION_NVP(_PIM_);
PreintegratedRotation is the base class for all PreintegratedMeasurements classes (in AHRSFactor,...
Definition: PreintegratedRotation.h:74
This is the base class for all factor types.
Definition: Factor.h:54
PreintegratedAHRSMeasurements accumulates (integrates) the Gyroscope measurements (rotation rates) an...
Definition: AHRSFactor.h:34
PreintegratedAhrsMeasurements()
Default constructor, only for serialization and Cython wrapper.
Definition: AHRSFactor.h:46
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
boost::shared_ptr< AHRSFactor > shared_ptr
Shorthand for a smart pointer to a factor.
Definition: AHRSFactor.h:124
PreintegratedAhrsMeasurements(const boost::shared_ptr< Params > &p, const Vector3 &biasHat)
Default constructor, initialize with no measurements.
Definition: AHRSFactor.h:52
const PreintegratedAhrsMeasurements & preintegratedMeasurements() const
Access the preintegrated measurements.
Definition: AHRSFactor.h:151
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegratedRotation.h:31
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
Template to create a binary predicate.
Definition: Testable.h:110
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:420
Non-linear factor base classes.
PreintegratedAhrsMeasurements(const Vector3 &biasHat, const Matrix3 &measuredOmegaCovariance)
Definition: AHRSFactor.h:88
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Vector3 biasHat_
Angular rate bias values used during preintegration.
Definition: AHRSFactor.h:38
PreintegratedAhrsMeasurements PreintegratedMeasurements
Definition: AHRSFactor.h:170
Definition: AHRSFactor.h:108
Matrix3 preintMeasCov_
Covariance matrix of the preintegrated measurements (first-order propagation from measurementCovarian...
Definition: AHRSFactor.h:39