34 Eigen::Matrix3<T> e_F_11;
36 e_F_11 << 0 , omega_ie, 0,
47template<
typename Derived>
48[[nodiscard]] Eigen::Matrix<typename Derived::Scalar, 3, 3>
e_F_dpsi_dw(
const Eigen::MatrixBase<Derived>& e_Dcm_b)
57template<
typename Derived>
58[[nodiscard]] Eigen::Matrix<typename Derived::Scalar, 3, 3>
e_F_dv_dpsi(
const Eigen::MatrixBase<Derived>& e_force_ib)
61 Eigen::Matrix<typename Derived::Scalar, 3, 3> e_F_21;
63 e_F_21 << 0 , e_force_ib.z(), -e_force_ib.y(),
64 -e_force_ib.z(), 0 , e_force_ib.x(),
65 e_force_ib.y(), -e_force_ib.x(), 0 ;
75[[nodiscard]] Eigen::Matrix3<T>
e_F_dv_dv(
double omega_ie)
78 Eigen::Matrix3d e_F_22;
80 e_F_22 << 0.0 , 2.0 * omega_ie, 0.0,
81 -2.0 * omega_ie, 0.0 , 0.0,
84 return e_F_22.cast<T>();
94template<
typename Derived1,
typename Derived2,
typename T>
95[[nodiscard]] Eigen::Matrix<typename Derived1::Scalar, 3, 3>
e_F_dv_dr(
const Eigen::MatrixBase<Derived1>& e_position,
96 const Eigen::MatrixBase<Derived2>& e_gravitation,
98 const Eigen::Vector3d& e_omega_ie)
103 Eigen::Matrix<typename Derived1::Scalar, 3, 3> e_F_23 = -((2.0 * e_gravitation * e_position.transpose()) / (r_eS_e * e_position.norm()) + e_Omega_ie * e_Omega_ie);
115template<
typename Derived1,
typename Derived2,
typename Derived3,
typename Derived4,
typename Derived5,
typename Derived6>
116Eigen::Matrix<typename Derived6::Scalar, 3, 4>
e_F_dv_dq(
const Eigen::MatrixBase<Derived1>& p_accelBias,
117 const Eigen::MatrixBase<Derived2>& p_accelScale,
118 const Eigen::QuaternionBase<Derived3>& p_quatAccel_ps,
119 const Eigen::MatrixBase<Derived4>& ps_f_ip,
120 const Eigen::QuaternionBase<Derived5>& b_quat_p,
121 const Eigen::QuaternionBase<Derived6>& e_quat_b)
123 Eigen::Vector3<typename Derived6::Scalar> b_f_ip = b_quat_p.template cast<typename Derived6::Scalar>()
124 * (p_accelScale.asDiagonal() * p_quatAccel_ps * ps_f_ip.template cast<typename Derived6::Scalar>() + p_accelBias);
126 Eigen::Matrix<typename Derived6::Scalar, 3, 4> F_dv_dq;
128 F_dv_dq(0, 0) = 2.0 * (b_f_ip.x() * e_quat_b.x() + b_f_ip.y() * e_quat_b.y() + b_f_ip.z() * e_quat_b.z());
129 F_dv_dq(0, 1) = -2.0 * (b_f_ip.x() * e_quat_b.y() - b_f_ip.y() * e_quat_b.x() - b_f_ip.z() * e_quat_b.w());
130 F_dv_dq(0, 2) = -2.0 * (b_f_ip.x() * e_quat_b.z() + b_f_ip.y() * e_quat_b.w() - b_f_ip.z() * e_quat_b.x());
131 F_dv_dq(0, 3) = 2.0 * (b_f_ip.x() * e_quat_b.w() - b_f_ip.y() * e_quat_b.z() + b_f_ip.z() * e_quat_b.y());
133 F_dv_dq(1, 0) = -F_dv_dq(0, 1);
134 F_dv_dq(1, 1) = F_dv_dq(0, 0);
135 F_dv_dq(1, 2) = F_dv_dq(0, 3);
136 F_dv_dq(1, 3) = -F_dv_dq(0, 2);
138 F_dv_dq(2, 0) = -F_dv_dq(0, 2);
139 F_dv_dq(2, 1) = -F_dv_dq(0, 3);
140 F_dv_dq(2, 2) = F_dv_dq(0, 0);
141 F_dv_dq(2, 3) = F_dv_dq(0, 1);
150template<
typename Derived>
151[[nodiscard]] Eigen::Matrix<typename Derived::Scalar, 3, 3>
e_F_dv_df_b(
const Eigen::MatrixBase<Derived>& e_Dcm_b)
160template<
typename Derived1,
typename Derived2>
161[[nodiscard]] Eigen::Matrix<typename Derived2::Scalar, 3, 3>
e_F_dv_dAccelBias(
const Eigen::QuaternionBase<Derived1>& b_quat_p,
const Eigen::QuaternionBase<Derived2>& e_quat_b)
163 return (e_quat_b * b_quat_p.template cast<typename Derived2::Scalar>()).toRotationMatrix();
171template<
typename Derived1,
typename Derived2,
typename Derived3,
typename Derived4>
172[[nodiscard]] Eigen::Matrix<typename Derived4::Scalar, 3, 3>
e_F_dv_dAccelScale(
const Eigen::QuaternionBase<Derived1>& p_quatAccel_ps,
173 const Eigen::MatrixBase<Derived2>& ps_f_ip,
174 const Eigen::QuaternionBase<Derived3>& b_quat_p,
175 const Eigen::QuaternionBase<Derived4>& e_quat_b)
178 * b_quat_p.template cast<typename Derived4::Scalar>()
180 * ps_f_ip.template cast<typename Derived4::Scalar>().asDiagonal();
189template<
typename Derived1,
typename Derived2,
typename Derived3,
typename Derived4,
typename Derived5>
191 const Eigen::QuaternionBase<Derived2>& p_quatAccel_ps,
192 const Eigen::MatrixBase<Derived3>& ps_f_ip,
193 const Eigen::QuaternionBase<Derived4>& b_quat_p,
194 const Eigen::QuaternionBase<Derived5>& e_quat_b)
196 Eigen::Matrix3<typename Derived5::Scalar> e_dcmAccelScaled_p = e_quat_b * b_quat_p.template cast<typename Derived5::Scalar>() * p_accelScale.asDiagonal();
198 auto a = p_quatAccel_ps.w() * e_dcmAccelScaled_p(0, 2) + p_quatAccel_ps.y() * e_dcmAccelScaled_p(0, 0) - p_quatAccel_ps.x() * e_dcmAccelScaled_p(0, 1);
199 auto b = p_quatAccel_ps.w() * e_dcmAccelScaled_p(1, 2) + p_quatAccel_ps.y() * e_dcmAccelScaled_p(1, 0) - p_quatAccel_ps.x() * e_dcmAccelScaled_p(1, 1);
200 auto c = p_quatAccel_ps.w() * e_dcmAccelScaled_p(2, 2) + p_quatAccel_ps.y() * e_dcmAccelScaled_p(2, 0) - p_quatAccel_ps.x() * e_dcmAccelScaled_p(2, 1);
201 auto d = p_quatAccel_ps.w() * e_dcmAccelScaled_p(0, 1) + p_quatAccel_ps.x() * e_dcmAccelScaled_p(0, 2) - p_quatAccel_ps.z() * e_dcmAccelScaled_p(0, 0);
202 auto e = p_quatAccel_ps.w() * e_dcmAccelScaled_p(1, 1) + p_quatAccel_ps.x() * e_dcmAccelScaled_p(1, 2) - p_quatAccel_ps.z() * e_dcmAccelScaled_p(1, 0);
203 auto f = p_quatAccel_ps.w() * e_dcmAccelScaled_p(2, 1) + p_quatAccel_ps.x() * e_dcmAccelScaled_p(2, 2) - p_quatAccel_ps.z() * e_dcmAccelScaled_p(2, 0);
204 auto g = p_quatAccel_ps.w() * e_dcmAccelScaled_p(0, 0) + p_quatAccel_ps.z() * e_dcmAccelScaled_p(0, 1) - p_quatAccel_ps.y() * e_dcmAccelScaled_p(0, 2);
205 auto h = p_quatAccel_ps.w() * e_dcmAccelScaled_p(1, 0) + p_quatAccel_ps.z() * e_dcmAccelScaled_p(1, 1) - p_quatAccel_ps.y() * e_dcmAccelScaled_p(1, 2);
206 auto i = p_quatAccel_ps.w() * e_dcmAccelScaled_p(2, 0) + p_quatAccel_ps.z() * e_dcmAccelScaled_p(2, 1) - p_quatAccel_ps.y() * e_dcmAccelScaled_p(2, 2);
207 auto j = p_quatAccel_ps.x() * e_dcmAccelScaled_p(0, 0) + p_quatAccel_ps.y() * e_dcmAccelScaled_p(0, 1) + p_quatAccel_ps.z() * e_dcmAccelScaled_p(0, 2);
208 auto k = p_quatAccel_ps.x() * e_dcmAccelScaled_p(1, 0) + p_quatAccel_ps.y() * e_dcmAccelScaled_p(1, 1) + p_quatAccel_ps.z() * e_dcmAccelScaled_p(1, 2);
209 auto l = p_quatAccel_ps.x() * e_dcmAccelScaled_p(2, 0) + p_quatAccel_ps.y() * e_dcmAccelScaled_p(2, 1) + p_quatAccel_ps.z() * e_dcmAccelScaled_p(2, 2);
239template<
typename Derived1,
typename Derived2,
typename Derived3,
typename Derived4,
typename Derived5,
typename Derived6>
240[[nodiscard]] Eigen::Matrix4<typename Derived6::Scalar>
e_F_dq_dq(
const Eigen::MatrixBase<Derived1>& p_gyroBias,
241 const Eigen::MatrixBase<Derived2>& p_gyroScale,
242 const Eigen::QuaternionBase<Derived3>& p_quatGyro_ps,
243 const Eigen::MatrixBase<Derived4>& ps_omega_ip,
244 const Eigen::QuaternionBase<Derived5>& b_quat_p,
245 const Eigen::QuaternionBase<Derived6>& e_quat_b,
248 Eigen::Vector3<typename Derived6::Scalar> b_omega_ib = b_quat_p.template cast<typename Derived6::Scalar>()
249 * (p_gyroScale.asDiagonal() * p_quatGyro_ps * ps_omega_ip.template cast<typename Derived6::Scalar>()
252 Eigen::Matrix4<typename Derived6::Scalar> F_dq_dq;
254 F_dq_dq(0, 0) = omega_ie * e_quat_b.x() * e_quat_b.y();
255 F_dq_dq(0, 1) = 0.5 * b_omega_ib.z() + 0.5 * omega_ie * std::pow(e_quat_b.w(), 2) + 0.5 * omega_ie * std::pow(e_quat_b.x(), 2) + 0.5 * omega_ie * std::pow(e_quat_b.z(), 2) + 1.5 * omega_ie * std::pow(e_quat_b.y(), 2);
256 F_dq_dq(0, 2) = -0.5 * b_omega_ib.y() + omega_ie * e_quat_b.y() * e_quat_b.z();
257 F_dq_dq(0, 3) = 0.5 * b_omega_ib.x() + omega_ie * e_quat_b.w() * e_quat_b.y();
259 F_dq_dq(1, 0) = -0.5 * b_omega_ib.z() - 0.5 * omega_ie * std::pow(e_quat_b.w(), 2) - 0.5 * omega_ie * std::pow(e_quat_b.y(), 2) - 0.5 * omega_ie * std::pow(e_quat_b.z(), 2) - 1.5 * omega_ie * std::pow(e_quat_b.x(), 2);
260 F_dq_dq(1, 1) = -F_dq_dq(0, 0);
261 F_dq_dq(1, 2) = 0.5 * b_omega_ib.x() - omega_ie * e_quat_b.x() * e_quat_b.z();
262 F_dq_dq(1, 3) = 0.5 * b_omega_ib.y() - omega_ie * e_quat_b.w() * e_quat_b.x();
264 F_dq_dq(2, 0) = F_dq_dq(1, 3);
265 F_dq_dq(2, 1) = -0.5 * b_omega_ib.x() - omega_ie * e_quat_b.w() * e_quat_b.y();
266 F_dq_dq(2, 2) = -omega_ie * e_quat_b.w() * e_quat_b.z();
267 F_dq_dq(2, 3) = 0.5 * b_omega_ib.z() - 0.5 * omega_ie * std::pow(e_quat_b.x(), 2) - 0.5 * omega_ie * std::pow(e_quat_b.y(), 2) - 0.5 * omega_ie * std::pow(e_quat_b.z(), 2) - 1.5 * omega_ie * std::pow(e_quat_b.w(), 2);
269 F_dq_dq(3, 0) = -0.5 * b_omega_ib.x() + omega_ie * e_quat_b.x() * e_quat_b.z();
270 F_dq_dq(3, 1) = F_dq_dq(0, 2);
271 F_dq_dq(3, 2) = -0.5 * b_omega_ib.z() + 0.5 * omega_ie * std::pow(e_quat_b.w(), 2) + 0.5 * omega_ie * std::pow(e_quat_b.x(), 2) + 0.5 * omega_ie * std::pow(e_quat_b.y(), 2) + 1.5 * omega_ie * std::pow(e_quat_b.z(), 2);
272 F_dq_dq(3, 3) = -F_dq_dq(2, 2);
280template<
typename Derived1,
typename Derived2>
281[[nodiscard]] Eigen::Matrix<typename Derived2::Scalar, 4, 3>
e_F_dq_dGyroBias(
const Eigen::QuaternionBase<Derived1>& b_quat_p,
282 const Eigen::QuaternionBase<Derived2>& e_quat_b)
284 Eigen::Matrix<typename Derived2::Scalar, 4, 3> F_dq_dGyroBias;
286 auto a = std::pow(b_quat_p.w(), 2) + std::pow(b_quat_p.x(), 2) - std::pow(b_quat_p.y(), 2) - std::pow(b_quat_p.z(), 2);
287 auto b = std::pow(b_quat_p.w(), 2) + std::pow(b_quat_p.y(), 2) - std::pow(b_quat_p.x(), 2) - std::pow(b_quat_p.z(), 2);
288 auto c = std::pow(b_quat_p.w(), 2) + std::pow(b_quat_p.z(), 2) - std::pow(b_quat_p.x(), 2) - std::pow(b_quat_p.y(), 2);
289 auto d = b_quat_p.w() * b_quat_p.x() + b_quat_p.y() * b_quat_p.z();
290 auto e = b_quat_p.w() * b_quat_p.x() - b_quat_p.y() * b_quat_p.z();
291 auto f = b_quat_p.w() * b_quat_p.y() + b_quat_p.x() * b_quat_p.z();
292 auto g = b_quat_p.w() * b_quat_p.y() - b_quat_p.x() * b_quat_p.z();
293 auto h = b_quat_p.w() * b_quat_p.z() + b_quat_p.x() * b_quat_p.y();
294 auto i = b_quat_p.w() * b_quat_p.z() - b_quat_p.x() * b_quat_p.y();
296 F_dq_dGyroBias(0, 0) = 0.5 * a * e_quat_b.w() - g * e_quat_b.y() - h * e_quat_b.z();
297 F_dq_dGyroBias(0, 1) = d * e_quat_b.y() - 0.5 * b * e_quat_b.z() - i * e_quat_b.w();
298 F_dq_dGyroBias(0, 2) = 0.5 * c * e_quat_b.y() + e * e_quat_b.z() + f * e_quat_b.w();
300 F_dq_dGyroBias(1, 0) = 0.5 * a * e_quat_b.z() + g * e_quat_b.x() + h * e_quat_b.w();
301 F_dq_dGyroBias(1, 1) = 0.5 * b * e_quat_b.w() - d * e_quat_b.x() - i * e_quat_b.z();
302 F_dq_dGyroBias(1, 2) = f * e_quat_b.z() - 0.5 * c * e_quat_b.x() - e * e_quat_b.w();
304 F_dq_dGyroBias(2, 0) = h * e_quat_b.x() - 0.5 * a * e_quat_b.y() - g * e_quat_b.w();
305 F_dq_dGyroBias(2, 1) = 0.5 * b * e_quat_b.x() + d * e_quat_b.w() + i * e_quat_b.y();
306 F_dq_dGyroBias(2, 2) = 0.5 * c * e_quat_b.w() - e * e_quat_b.x() - f * e_quat_b.y();
308 F_dq_dGyroBias(3, 0) = g * e_quat_b.z() - 0.5 * a * e_quat_b.x() - h * e_quat_b.y();
309 F_dq_dGyroBias(3, 1) = i * e_quat_b.x() - 0.5 * b * e_quat_b.y() - d * e_quat_b.z();
310 F_dq_dGyroBias(3, 2) = e * e_quat_b.y() - 0.5 * c * e_quat_b.z() - f * e_quat_b.x();
312 return F_dq_dGyroBias;
320template<
typename Derived1,
typename Derived2,
typename Derived3,
typename Derived4>
321[[nodiscard]] Eigen::Matrix<typename Derived4::Scalar, 4, 3>
e_F_dq_dGyroScale(
const Eigen::QuaternionBase<Derived1>& p_quatGyro_ps,
322 const Eigen::MatrixBase<Derived2>& ps_omega_ip,
323 const Eigen::QuaternionBase<Derived3>& b_quat_p,
324 const Eigen::QuaternionBase<Derived4>& e_quat_b)
326 Eigen::Vector3<typename Derived4::Scalar> p_omega_ip = p_quatGyro_ps * ps_omega_ip.template cast<typename Derived4::Scalar>();
337template<
typename Derived1,
typename Derived2,
typename Derived3,
typename Derived4,
typename Derived5>
339 const Eigen::QuaternionBase<Derived2>& p_quatGyro_ps,
340 const Eigen::MatrixBase<Derived3>& ps_omega_ip,
341 const Eigen::QuaternionBase<Derived4>& b_quat_p,
342 const Eigen::QuaternionBase<Derived5>& e_quat_b)
344 Eigen::Matrix3<typename Derived1::Scalar> b_dcmGyroScaled_p = b_quat_p.template cast<typename Derived1::Scalar>() * p_gyroScale.asDiagonal();
346 auto a = p_quatGyro_ps.x() * b_dcmGyroScaled_p(0, 0) + p_quatGyro_ps.y() * b_dcmGyroScaled_p(0, 1) + p_quatGyro_ps.z() * b_dcmGyroScaled_p(0, 2);
347 auto b = p_quatGyro_ps.w() * b_dcmGyroScaled_p(0, 2) + p_quatGyro_ps.y() * b_dcmGyroScaled_p(0, 0) - p_quatGyro_ps.x() * b_dcmGyroScaled_p(0, 1);
348 auto c = p_quatGyro_ps.w() * b_dcmGyroScaled_p(0, 1) + p_quatGyro_ps.x() * b_dcmGyroScaled_p(0, 2) - p_quatGyro_ps.z() * b_dcmGyroScaled_p(0, 0);
349 auto d = p_quatGyro_ps.x() * b_dcmGyroScaled_p(2, 0) + p_quatGyro_ps.y() * b_dcmGyroScaled_p(2, 1) + p_quatGyro_ps.z() * b_dcmGyroScaled_p(2, 2);
350 auto e = p_quatGyro_ps.w() * b_dcmGyroScaled_p(2, 2) + p_quatGyro_ps.y() * b_dcmGyroScaled_p(2, 0) - p_quatGyro_ps.x() * b_dcmGyroScaled_p(2, 1);
351 auto f = p_quatGyro_ps.w() * b_dcmGyroScaled_p(2, 1) + p_quatGyro_ps.x() * b_dcmGyroScaled_p(2, 2) - p_quatGyro_ps.z() * b_dcmGyroScaled_p(2, 0);
352 auto g = p_quatGyro_ps.x() * b_dcmGyroScaled_p(1, 0) + p_quatGyro_ps.y() * b_dcmGyroScaled_p(1, 1) + p_quatGyro_ps.z() * b_dcmGyroScaled_p(1, 2);
353 auto h = p_quatGyro_ps.w() * b_dcmGyroScaled_p(1, 2) + p_quatGyro_ps.y() * b_dcmGyroScaled_p(1, 0) - p_quatGyro_ps.x() * b_dcmGyroScaled_p(1, 1);
354 auto i = p_quatGyro_ps.w() * b_dcmGyroScaled_p(1, 1) + p_quatGyro_ps.x() * b_dcmGyroScaled_p(1, 2) - p_quatGyro_ps.z() * b_dcmGyroScaled_p(1, 0);
355 auto j = p_quatGyro_ps.w() * b_dcmGyroScaled_p(0, 0) + p_quatGyro_ps.z() * b_dcmGyroScaled_p(0, 1) - p_quatGyro_ps.y() * b_dcmGyroScaled_p(0, 2);
356 auto k = p_quatGyro_ps.w() * b_dcmGyroScaled_p(2, 0) + p_quatGyro_ps.z() * b_dcmGyroScaled_p(2, 1) - p_quatGyro_ps.y() * b_dcmGyroScaled_p(2, 2);
357 auto l = p_quatGyro_ps.w() * b_dcmGyroScaled_p(1, 0) + p_quatGyro_ps.z() * b_dcmGyroScaled_p(1, 1) - p_quatGyro_ps.y() * b_dcmGyroScaled_p(1, 2);
358 auto m = a * ps_omega_ip.x() + b * ps_omega_ip.y() - c * ps_omega_ip.z();
359 auto n = d * ps_omega_ip.x() + e * ps_omega_ip.y() - f * ps_omega_ip.z();
360 auto o = g * ps_omega_ip.x() + h * ps_omega_ip.y() - i * ps_omega_ip.z();
361 auto p = a * ps_omega_ip.y() + j * ps_omega_ip.z() - b * ps_omega_ip.x();
362 auto q = d * ps_omega_ip.y() + k * ps_omega_ip.z() - e * ps_omega_ip.x();
363 auto r = g * ps_omega_ip.y() + l * ps_omega_ip.z() - h * ps_omega_ip.x();
364 auto s = a * ps_omega_ip.z() + c * ps_omega_ip.x() - j * ps_omega_ip.y();
365 auto t = d * ps_omega_ip.z() + f * ps_omega_ip.x() - k * ps_omega_ip.y();
366 auto u = g * ps_omega_ip.z() + i * ps_omega_ip.x() - l * ps_omega_ip.y();
367 auto v = b * ps_omega_ip.z() + c * ps_omega_ip.y() + j * ps_omega_ip.x();
368 auto w = e * ps_omega_ip.z() + f * ps_omega_ip.y() + k * ps_omega_ip.x();
369 auto x = h * ps_omega_ip.z() + i * ps_omega_ip.y() + l * ps_omega_ip.x();
371 Eigen::Matrix4<typename Derived5::Scalar> F_dq_dGyroMisalignment;
373 F_dq_dGyroMisalignment(0, 0) = m * e_quat_b.w() + n * e_quat_b.y() - o * e_quat_b.z();
374 F_dq_dGyroMisalignment(0, 1) = p * e_quat_b.w() + q * e_quat_b.y() - r * e_quat_b.z();
375 F_dq_dGyroMisalignment(0, 2) = s * e_quat_b.w() + t * e_quat_b.y() - u * e_quat_b.z();
376 F_dq_dGyroMisalignment(0, 3) = v * e_quat_b.w() + w * e_quat_b.y() - x * e_quat_b.z();
378 F_dq_dGyroMisalignment(1, 0) = m * e_quat_b.z() + o * e_quat_b.w() - n * e_quat_b.x();
379 F_dq_dGyroMisalignment(1, 1) = p * e_quat_b.z() + r * e_quat_b.w() - q * e_quat_b.x();
380 F_dq_dGyroMisalignment(1, 2) = s * e_quat_b.z() + u * e_quat_b.w() - t * e_quat_b.x();
381 F_dq_dGyroMisalignment(1, 3) = v * e_quat_b.z() + x * e_quat_b.w() - w * e_quat_b.x();
383 F_dq_dGyroMisalignment(2, 0) = n * e_quat_b.w() + o * e_quat_b.x() - m * e_quat_b.y();
384 F_dq_dGyroMisalignment(2, 1) = q * e_quat_b.w() + r * e_quat_b.x() - p * e_quat_b.y();
385 F_dq_dGyroMisalignment(2, 2) = t * e_quat_b.w() + u * e_quat_b.x() - s * e_quat_b.y();
386 F_dq_dGyroMisalignment(2, 3) = w * e_quat_b.w() + x * e_quat_b.x() - v * e_quat_b.y();
388 F_dq_dGyroMisalignment(3, 0) = -m * e_quat_b.x() - n * e_quat_b.z() - o * e_quat_b.y();
389 F_dq_dGyroMisalignment(3, 1) = -p * e_quat_b.x() - q * e_quat_b.z() - r * e_quat_b.y();
390 F_dq_dGyroMisalignment(3, 2) = -s * e_quat_b.x() - t * e_quat_b.z() - u * e_quat_b.y();
391 F_dq_dGyroMisalignment(3, 3) = -v * e_quat_b.x() - w * e_quat_b.z() - x * e_quat_b.y();
393 return F_dq_dGyroMisalignment;
402 return Eigen::Matrix3<T>::Identity();
409template<
typename Derived>
410[[nodiscard]] Eigen::Matrix<typename Derived::Scalar, 3, 3>
e_F_df_df(
const Eigen::MatrixBase<Derived>& beta_a)
413 return -1.0 * beta_a.asDiagonal();
420template<
typename Derived>
421[[nodiscard]] Eigen::Matrix<typename Derived::Scalar, 3, 3>
e_F_dw_dw(
const Eigen::MatrixBase<Derived>& beta_omega)
424 return -1.0 * beta_omega.asDiagonal();
450template<
typename KeyType,
typename T>
452 const Eigen::Vector3d& ps_omega_ip,
453 const Eigen::Quaterniond& b_quat_p,
454 const Eigen::Vector3<T>& e_gravitation,
456 std::optional<double> tau_bad,
457 std::optional<double> tau_bgd,
458 const Eigen::Vector3<T>& e_position,
459 const Eigen::Quaternion<T>& e_quat_b,
460 const Eigen::Vector3<T>& p_accelBias,
461 const Eigen::Vector3<T>& p_gyroBias,
462 const Eigen::Vector3<T>& p_accelScale,
463 const Eigen::Vector3<T>& p_gyroScale,
464 const Eigen::Quaternion<T>& p_quatAccel_ps,
465 const Eigen::Quaternion<T>& p_quatGyro_ps,
467 bool accelBiases,
bool gyroBiases,
468 bool accelScaleFactor,
bool gyroScaleFactor,
469 bool accelMisalignment,
bool gyroMisalignment)
471 std::vector<KeyType> keys;
472 keys.reserve(3 + 3 + 4
473 + 3 * (
static_cast<size_t>(accelBiases) +
static_cast<size_t>(gyroBiases))
474 + 3 * (
static_cast<size_t>(accelScaleFactor) +
static_cast<size_t>(gyroScaleFactor))
475 + 4 * (
static_cast<size_t>(accelMisalignment) +
static_cast<size_t>(gyroMisalignment)));
477 keys.insert(keys.end(), { Keys::PosX, Keys::PosY, Keys::PosZ,
478 Keys::VelX, Keys::VelY, Keys::VelZ,
479 Keys::AttQ1, Keys::AttQ2, Keys::AttQ3, Keys::AttQ0 });
509 if (accelScaleFactor)
517 if (accelMisalignment)
521 if (gyroMisalignment)
KeyedMatrixX< T, KeyType, KeyType > e_systemMatrix_F(const Eigen::Vector3d &ps_f_ip, const Eigen::Vector3d &ps_omega_ip, const Eigen::Quaterniond &b_quat_p, const Eigen::Vector3< T > &e_gravitation, const T &r_eS_e, std::optional< double > tau_bad, std::optional< double > tau_bgd, const Eigen::Vector3< T > &e_position, const Eigen::Quaternion< T > &e_quat_b, const Eigen::Vector3< T > &p_accelBias, const Eigen::Vector3< T > &p_gyroBias, const Eigen::Vector3< T > &p_accelScale, const Eigen::Vector3< T > &p_gyroScale, const Eigen::Quaternion< T > &p_quatAccel_ps, const Eigen::Quaternion< T > &p_quatGyro_ps, const PosVelAttDerivativeConstants &config, bool accelBiases, bool gyroBiases, bool accelScaleFactor, bool gyroScaleFactor, bool accelMisalignment, bool gyroMisalignment)
Calculate the linearized system matrix in Earth frame coordinates.
Definition ErrorEquations.hpp:451
Eigen::Matrix< typename Derived4::Scalar, 4, 3 > e_F_dq_dGyroScale(const Eigen::QuaternionBase< Derived1 > &p_quatGyro_ps, const Eigen::MatrixBase< Derived2 > &ps_omega_ip, const Eigen::QuaternionBase< Derived3 > &b_quat_p, const Eigen::QuaternionBase< Derived4 > &e_quat_b)
Calculate the linearized attitude quaternion differential equation partially derived for the angular ...
Definition ErrorEquations.hpp:321
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dv_df_b(const Eigen::MatrixBase< Derived > &e_Dcm_b)
Calculates the matrix 𝐅_𝜓'_𝛿f_b.
Definition ErrorEquations.hpp:151
Eigen::Matrix3< T > e_F_dr_dv()
Calculates the matrix 𝐅_𝛿r'_𝛿v.
Definition ErrorEquations.hpp:400
Eigen::Matrix< typename Derived5::Scalar, 3, 4 > e_F_dv_dAccelMisalignment(const Eigen::MatrixBase< Derived1 > &p_accelScale, const Eigen::QuaternionBase< Derived2 > &p_quatAccel_ps, const Eigen::MatrixBase< Derived3 > &ps_f_ip, const Eigen::QuaternionBase< Derived4 > &b_quat_p, const Eigen::QuaternionBase< Derived5 > &e_quat_b)
Calculate the linearized velocity differential equation partially derived for the accelerometer misal...
Definition ErrorEquations.hpp:190
Eigen::Matrix< typename Derived1::Scalar, 3, 3 > e_F_dv_dr(const Eigen::MatrixBase< Derived1 > &e_position, const Eigen::MatrixBase< Derived2 > &e_gravitation, const T &r_eS_e, const Eigen::Vector3d &e_omega_ie)
Calculates the matrix 𝐅_𝛿v'_𝛿r.
Definition ErrorEquations.hpp:95
Eigen::Matrix3< T > e_F_dv_dv(double omega_ie)
Calculates the matrix 𝐅_𝛿v'_𝛿v.
Definition ErrorEquations.hpp:75
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dw_dw(const Eigen::MatrixBase< Derived > &beta_omega)
Calculates the matrix 𝐅_𝛿ω'_𝛿ω
Definition ErrorEquations.hpp:421
Eigen::Matrix< typename Derived6::Scalar, 3, 4 > e_F_dv_dq(const Eigen::MatrixBase< Derived1 > &p_accelBias, const Eigen::MatrixBase< Derived2 > &p_accelScale, const Eigen::QuaternionBase< Derived3 > &p_quatAccel_ps, const Eigen::MatrixBase< Derived4 > &ps_f_ip, const Eigen::QuaternionBase< Derived5 > &b_quat_p, const Eigen::QuaternionBase< Derived6 > &e_quat_b)
Calculate the linearized velocity differential equation partially derived for the attitude.
Definition ErrorEquations.hpp:116
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dv_dpsi(const Eigen::MatrixBase< Derived > &e_force_ib)
Calculates the matrix 𝐅_𝛿v'_𝜓
Definition ErrorEquations.hpp:58
Eigen::Matrix< typename Derived2::Scalar, 3, 3 > e_F_dv_dAccelBias(const Eigen::QuaternionBase< Derived1 > &b_quat_p, const Eigen::QuaternionBase< Derived2 > &e_quat_b)
Calculates the matrix 𝐅_𝜓'_𝛿f_p.
Definition ErrorEquations.hpp:161
Eigen::Matrix< typename Derived2::Scalar, 4, 3 > e_F_dq_dGyroBias(const Eigen::QuaternionBase< Derived1 > &b_quat_p, const Eigen::QuaternionBase< Derived2 > &e_quat_b)
Calculate the linearized attitude quaternion differential equation partially derived for the angular ...
Definition ErrorEquations.hpp:281
Eigen::Matrix3< T > e_F_dpsi_dpsi(const T &omega_ie)
Calculates the matrix 𝐅_𝜓'_𝜓
Definition ErrorEquations.hpp:31
Eigen::Matrix4< typename Derived5::Scalar > e_F_dq_dGyroMisalignment(const Eigen::MatrixBase< Derived1 > &p_gyroScale, const Eigen::QuaternionBase< Derived2 > &p_quatGyro_ps, const Eigen::MatrixBase< Derived3 > &ps_omega_ip, const Eigen::QuaternionBase< Derived4 > &b_quat_p, const Eigen::QuaternionBase< Derived5 > &e_quat_b)
Calculate the linearized attitude quaternion differential equation partially derived for the gyroscop...
Definition ErrorEquations.hpp:338
Eigen::Matrix4< typename Derived6::Scalar > e_F_dq_dq(const Eigen::MatrixBase< Derived1 > &p_gyroBias, const Eigen::MatrixBase< Derived2 > &p_gyroScale, const Eigen::QuaternionBase< Derived3 > &p_quatGyro_ps, const Eigen::MatrixBase< Derived4 > &ps_omega_ip, const Eigen::QuaternionBase< Derived5 > &b_quat_p, const Eigen::QuaternionBase< Derived6 > &e_quat_b, double omega_ie)
Calculate the linearized attitude quaternion differential equation partially derived for the attitude...
Definition ErrorEquations.hpp:240
Eigen::Matrix< typename Derived4::Scalar, 3, 3 > e_F_dv_dAccelScale(const Eigen::QuaternionBase< Derived1 > &p_quatAccel_ps, const Eigen::MatrixBase< Derived2 > &ps_f_ip, const Eigen::QuaternionBase< Derived3 > &b_quat_p, const Eigen::QuaternionBase< Derived4 > &e_quat_b)
Calculate the linearized velocity differential equation partially derived for the acceleration bias.
Definition ErrorEquations.hpp:172
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dpsi_dw(const Eigen::MatrixBase< Derived > &e_Dcm_b)
Calculates the matrix 𝐅_𝜓'_𝛿ω
Definition ErrorEquations.hpp:48
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_df_df(const Eigen::MatrixBase< Derived > &beta_a)
Calculates the matrix 𝐅_𝛿f'_𝛿f.
Definition ErrorEquations.hpp:410
@ None
Gravity Model turned off.
Definition Gravity.hpp:31
Inertial Navigation System Keys.
constexpr std::array< StateKeyType, 3 > GyroBias
All gyroscope bias keys.
Definition Keys.hpp:58
constexpr std::array< StateKeyType, 3 > AccelScaleFactor
All accelerometer scale factor keys.
Definition Keys.hpp:62
constexpr std::array< StateKeyType, 4 > AccelMisalignment
All accelerometer misalignment quaternion keys.
Definition Keys.hpp:69
constexpr std::array< StateKeyType, 4 > GyroMisalignment
All gyroscope misalignment quaternion keys.
Definition Keys.hpp:72
constexpr std::array< StateKeyType, 3 > GyroScaleFactor
All gyroscope scale factor keys.
Definition Keys.hpp:65
constexpr std::array< StateKeyType, 3 > AccelBias
All accelerometer bias keys.
Definition Keys.hpp:55
Eigen::Matrix< typename Derived::Scalar, 3, 3 > skewSymmetricMatrix(const Eigen::MatrixBase< Derived > &a)
Calculates the skew symmetric matrix of the given vector. This is needed to perform the cross product...
Definition Math.hpp:90
constexpr std::array< StateKeyType, 4 > Att
All attitude keys.
Definition MotionModel.hpp:62
constexpr std::array< StateKeyType, 3 > Pos
All position keys.
Definition MotionModel.hpp:56
constexpr std::array< StateKeyType, 3 > Vel
All velocity keys.
Definition MotionModel.hpp:59
static constexpr double omega_ie
Nominal mean angular velocity of the Earth in [rad/s].
Definition Constants.hpp:217
static const Eigen::Vector3< double > e_omega_ie
ω_ie_e = ω_ie_i Nominal mean angular velocity of the Earth in [rad/s], in earth coordinates
Definition Constants.hpp:222
Values needed to calculate the PosVelAttDerivative for the local-navigation frame.
Definition Mechanization.hpp:26
bool centrifgalAccelerationCompensationEnabled
Apply the centrifugal acceleration compensation to the measured accelerations.
Definition Mechanization.hpp:29
bool angularRateEarthRotationCompensationEnabled
Apply the Earth rotation rate compensation to the measured angular rates.
Definition Mechanization.hpp:30
GravitationModel gravitationModel
Gravity Model to use.
Definition Mechanization.hpp:27
bool coriolisAccelerationCompensationEnabled
Apply the Coriolis acceleration compensation to the measured accelerations.
Definition Mechanization.hpp:28
Matrix which can be accessed by keys.
KeyedMatrix< Scalar, RowKeyType, ColKeyType, Eigen::Dynamic, Eigen::Dynamic > KeyedMatrixX
Dynamic size KeyedMatrix.
Definition KeyedMatrix.hpp:2308