strapdown/
earth.rs

1//! Earth-related constants and functions
2//!
3//! This module contains constants and functions related to the Earth's shape and other
4//! geophysical features (gravity and magnetic field). The Earth is modeled as an ellipsoid
5//! (WGS84) with a semi-major axis and a semi-minor axis. The Earth's gravity is modeled as
6//! a function of the latitude and altitude using the Somigliana method. The Earth's
7//! rotation rate is also included in this module. This module relies on the `nav-types`
8//! crate for the coordinate types and conversions, but provides additional functionality
9//! for calculating rotations for the strapdown navigation filters. This permits the
10//! transformation of additional quantities (velocity, acceleration, etc.) between the
11//! Earth-centered Earth-fixed (ECEF) frame and the local-level frame.
12//!
13//! # Coordinate Systems
14//! The WGS84 ellipsoidal model is the primary model used for the Earth's shape. This crate
15//! is primarily concerned with the ECEF and local-level frames, in addition to the basic
16//! body frame of the vehicle. The ECEF frame is a right-handed Cartesian coordinate system
17//! with the origin at the Earth's center. The local-level frame is a right-handed Cartesian
18//! coordinate system with the origin at the sensor's position. The local-level frame is
19//! defined by the tangent to the ellipsoidal surface at the sensor's position. The body
20//! frame is a right-handed Cartesian coordinate system with the origin at the sensor's
21//! center of mass. The body frame is defined by the sensor's orientation.
22//!
23//! For basic positional conversions, the [`nav-types`](https://crates.io/crates/nav-types)
24//! crate is used. This crate provides the `WGS84` and `ECEF` types for representing the
25//! Earth's position in geodetic and Cartesian coordinates, respectively. The `nav-types`
26//! crate also provides the necessary conversions between the two coordinate systems.
27//!
28//! # Rotation Functions
29//! The rotations needed for the strapdown navigation filters are not directly supported
30//! by the `nav-types` crate. These functions provide the necessary rotations that are
31//! primarily used for projecting the velocity and acceleration vectors. The rotations
32//! are primarily used to convert between the ECEF and local-level frames. The rotations
33//! from the local level frame to the body frame can be taken care of by the `nalgebra`
34//! crate, which provides the necessary rotation matrices using the Rotation3 type.
35use crate::{wrap_latitude, wrap_to_180};
36use nalgebra::{Matrix3, Vector3};
37use nav_types::{ECEF, WGS84};
38use world_magnetic_model::GeomagneticField;
39
40/// Earth's rotation rate rad/s ($\omega_{ie}$)
41pub const RATE: f64 = 7.2921159e-5;
42/// Earth's rotation rate rad/s ($\omega_{ie}$) in a vector form
43pub const RATE_VECTOR: Vector3<f64> = Vector3::new(0.0, 0.0, RATE);
44/// Earth's equatorial radius in meters
45pub const EQUATORIAL_RADIUS: f64 = 6378137.0; // meters
46/// Earth's polar radius in meters
47pub const POLAR_RADIUS: f64 = 6356752.31425; // meters
48/// Earth's mean radius in meters
49pub const MEAN_RADIUS: f64 = 6371000.0; // meters
50/// Earth's eccentricity ($e$)
51pub const ECCENTRICITY: f64 = 0.0818191908425; // unit-less
52/// Earth's eccentricity squared ($e^2$)
53pub const ECCENTRICITY_SQUARED: f64 = ECCENTRICITY * ECCENTRICITY;
54/// Earth's gravitational acceleration at the equator ($g_e$) in $m/s^2$
55pub const GE: f64 = 9.7803253359; // m/s^2, equatorial radius
56/// Earth's gravitational acceleration at the poles ($g_p$) in $m/s^2$
57pub const GP: f64 = 9.8321849378; // $m/s^2$, polar radius
58/// Earth's average gravitational acceleration ($g$) in $m/s^2$
59pub const G0: f64 = 9.80665; // m/s^2, average gravitational acceleration
60/// Earth's flattening factor ($f$)
61pub const F: f64 = 1.0 / 298.257223563; // Flattening factor
62/// Somigliana's constant ($K$)
63pub const K: f64 = (POLAR_RADIUS * GP - EQUATORIAL_RADIUS * GE) / (EQUATORIAL_RADIUS * GE); // Somigliana's constant
64// Earth magnetic field constants (dipole model)
65/// Earth's magnetic north pole latitude, degrees (2025, International Geomagnetic Reference Field)
66pub const MAGNETIC_NORTH_LATITUDE: f64 = 80.8; // degrees, geomagnetic north pole latitude  
67/// Earth's magnetic north pole longitude, degrees (2025, International Geomagnetic Reference Field)
68pub const MAGNETIC_NORTH_LONGITUDE: f64 = -72.8; // degrees, geomagnetic north pole longitude
69/// Earth's magnetic reference radius, meters (2025, International Geomagnetic Reference Field)
70pub const MAGNETIC_REFERENCE_RADIUS: f64 = 6371200.0; // meters, reference radius for magnetic field calculations
71/// Earth's magnetic field strength ($B_0$), teslas (2025, International Geomagnetic Reference Field)
72pub const MAGNETIC_FIELD_STRENGTH: f64 = 3.12e-5; // T, reference mean magnetic field strength
73/// Rough conversion factor from meters to degrees for latitude/longitude via nautical miles (1 degree ~ 60 nautical miles; 1 nautical mile ~ 1852 meters)
74pub const METERS_TO_DEGREES: f64 = 1.0 / (60.0 * 1852.0);
75/// Rough conversion factor from degrees to meters for latitude/longitude via nautical miles (1 degree ~ 60 nautical miles; 1 nautical mile ~ 1852 meters)
76pub const DEGREES_TO_METERS: f64 = 60.0 * 1852.0;
77/// Atmospheric pressure at sea level in Pascals ($P_0$)
78pub const SEA_LEVEL_PRESSURE: f64 = 101325.0;
79/// Standard temperature at sea level in Kelvin ($T_0$)
80pub const SEA_LEVEL_TEMPERATURE: f64 = 288.15;
81/// Molar mass of dry air in kg/mol ($M$)
82pub const MOLAR_MASS_DRY_AIR: f64 = 0.0289644;
83/// Universal gas constant in J/(mol·K) ($R_0$)
84pub const UNIVERSAL_GAS_CONSTANT: f64 = 8.314462618;
85/// Standard lapse rate in K/m ($L$)
86pub const STANDARD_LAPSE_RATE: f64 = 0.0065;
87/// Calculate a barometric altitude from a measured pressure
88///
89/// This function calculates the altitude above sea level based on the measured pressure
90/// using the barometric formula. The formula assumes a standard atmosphere and uses the
91/// universal gas constant, standard lapse rate, and molar mass of dry air.
92///
93/// # Parameters
94/// - `pressure` - The measured pressure in Pascals
95/// # Returns
96/// The calculated altitude in meters above sea level
97pub fn barometric_altitude(pressure: &f64) -> f64 {
98    let exponent: f64 = -(UNIVERSAL_GAS_CONSTANT * STANDARD_LAPSE_RATE) / (G0 * MOLAR_MASS_DRY_AIR);
99    (SEA_LEVEL_PRESSURE / STANDARD_LAPSE_RATE)
100        * (pressure / SEA_LEVEL_PRESSURE - 1.0)
101        * exponent.exp()
102}
103/// Calculate the relative barometric altitude from a measured pressure
104///
105/// This function calculates the relative altitude from a reference pressure using the
106/// barometric formula. The formula assumes a standard atmosphere and uses the universal
107/// gas constant, standard lapse rate, and molar mass of dry air.
108///
109/// # Parameters
110/// - `pressure` - The measured pressure in Pascals
111/// - `initial_pressure` - The reference pressure in Pascals
112/// - `average_temperature` - Optional average temperature in Kelvin (defaults to standard sea level temperature)
113///
114/// # Returns
115/// The calculated relative altitude in meters above the reference pressure
116pub fn relative_barometric_altitude(
117    pressure: f64,
118    initial_pressure: f64,
119    average_temperature: Option<f64>,
120) -> f64 {
121    let average_temperature = average_temperature.unwrap_or(SEA_LEVEL_TEMPERATURE);
122    ((UNIVERSAL_GAS_CONSTANT * average_temperature) / (G0 * MOLAR_MASS_DRY_AIR))
123        * (initial_pressure / pressure).ln()
124}
125/// Calculates the expected barometric pressure at a given altitude
126///
127/// This function calculates the expected atmospheric pressure at a given altitude using the barometric formula,
128/// given a reference sea level pressure. This is the inverse of the relative_barometric_altitude function.
129///
130/// # Arguments
131/// - `altitude` - The altitude above sea level in meters
132/// - `sea_level_pressure` - The atmospheric pressure at sea level in pascals
133///
134/// # Returns
135/// The expected atmospheric pressure at the given altitude in pascals
136///
137/// # Example
138/// ```rust
139/// use strapdown::earth;
140/// let altitude = 1000.0;
141/// let sea_level_pressure = 101325.0;
142/// let pressure = earth::expected_barometric_pressure(altitude, sea_level_pressure);
143/// ```
144pub fn expected_barometric_pressure(altitude: f64, sea_level_pressure: f64) -> f64 {
145    // Barometric formula (assuming isothermal atmosphere):
146    // P = P0 * exp(- (g0 * M * h) / (R * T0))
147    // Here we use the same constants as in barometric_altitude
148    let exponent =
149        -(G0 * MOLAR_MASS_DRY_AIR * altitude) / (UNIVERSAL_GAS_CONSTANT * SEA_LEVEL_TEMPERATURE);
150    sea_level_pressure * exponent.exp()
151}
152/// Convert a three-element vector to a skew-symmetric matrix
153///
154/// Groves' notation uses a lot of skew-symmetric matrices to represent cross products
155/// and to perform more concise matrix operations (particularly involving rotations).
156/// This function converts a three-element vector to a skew-symmetric matrix.
157///
158/// $$
159/// x = \begin{bmatrix} a \\\\ b \\\\ c \end{bmatrix} \rightarrow X = \begin{bmatrix} 0 & -c & b \\\\ c & 0 & -a \\\\ -b & a & 0 \end{bmatrix}
160/// $$
161///
162/// # Example
163/// ```rust
164/// use nalgebra::{Vector3, Matrix3};
165/// use strapdown::earth;
166/// let v: Vector3<f64> = Vector3::new(1.0, 2.0, 3.0);
167/// let skew: Matrix3<f64> = earth::vector_to_skew_symmetric(&v);
168/// ```
169pub fn vector_to_skew_symmetric(v: &Vector3<f64>) -> Matrix3<f64> {
170    let mut skew: Matrix3<f64> = Matrix3::zeros();
171    skew[(0, 1)] = -v[2];
172    skew[(0, 2)] = v[1];
173    skew[(1, 0)] = v[2];
174    skew[(1, 2)] = -v[0];
175    skew[(2, 0)] = -v[1];
176    skew[(2, 1)] = v[0];
177    skew
178}
179/// Convert a skew-symmetric matrix to a three-element vector
180///
181/// This function converts a skew-symmetric matrix to a three-element vector. This is the
182/// inverse operation of the `vector_to_skew_symmetric` function.
183///
184/// $$
185/// X = \begin{bmatrix} 0 & -c & b \\\\ c & 0 & -a \\\\ -b & a & 0 \end{bmatrix} \rightarrow x = \begin{bmatrix} a \\\\ b \\\\ c \end{bmatrix}
186/// $$
187///
188/// # Example
189/// ```rust
190/// use strapdown::earth;
191/// use nalgebra::{Vector3, Matrix3};
192/// let skew: Matrix3<f64> = Matrix3::new(0.0, -3.0, 2.0, 3.0, 0.0, -1.0, -2.0, 1.0, 0.0);
193/// let v: Vector3<f64> = earth::skew_symmetric_to_vector(&skew);
194/// ```
195pub fn skew_symmetric_to_vector(skew: &Matrix3<f64>) -> Vector3<f64> {
196    let mut v: Vector3<f64> = Vector3::zeros();
197    v[0] = skew[(2, 1)];
198    v[1] = skew[(0, 2)];
199    v[2] = skew[(1, 0)];
200    v
201}
202/// Coordinate conversion from the Earth-centered Inertial (ECI) frame to the Earth-centered
203/// Earth-fixed (ECEF) frame.
204///
205/// The ECI frame is a right-handed Cartesian coordinate system with
206/// the origin at the Earth's center. The ECEF frame is a right-handed Cartesian coordinate
207/// system with the origin at the Earth's center. The ECI frame is fixed with respect to the
208/// stars, whereas the ECEF frame rotates with the Earth.
209///
210/// # Arguments
211/// - `time` - The time in seconds that define the rotation period
212///
213/// # Returns
214/// A 3x3 rotation matrix that converts from the ECI frame to the ECEF frame
215///
216/// # Example
217/// ```rust
218/// use nalgebra::Matrix3;
219/// use strapdown::earth;
220/// let time: f64 = 30.0;
221/// let rot: Matrix3<f64> = earth::eci_to_ecef(time);
222/// ```
223pub fn eci_to_ecef(time: f64) -> Matrix3<f64> {
224    let mut rot: Matrix3<f64> = Matrix3::zeros();
225    rot[(0, 0)] = (RATE * time).cos();
226    rot[(0, 1)] = (RATE * time).sin();
227    rot[(1, 0)] = -(RATE * time).sin();
228    rot[(1, 1)] = (RATE * time).cos();
229    rot[(2, 2)] = 1.0;
230    rot
231}
232/// Coordinate conversion from the Earth-centered Earth-fixed (ECEF) frame to the Earth-centered
233/// Inertial (ECI) frame.
234///
235/// The ECI frame is a right-handed Cartesian coordinate system with
236/// the origin at the Earth's center. The ECEF frame is a right-handed Cartesian coordinate
237/// system with the origin at the Earth's center. The ECI frame is fixed with respect to the
238/// stars, whereas the ECEF frame rotates with the Earth.
239///     
240/// # Arguments
241/// - `time` - The time in seconds that define the rotation period
242///
243/// # Returns
244/// A 3x3 rotation matrix that converts from the ECEF frame to the ECI frame
245///
246/// # Example
247/// ```rust
248/// use nalgebra::Matrix3;
249/// use strapdown::earth;
250/// let time: f64 = 30.0;
251/// let rot: Matrix3<f64> = earth::ecef_to_eci(time);
252/// ```
253pub fn ecef_to_eci(time: f64) -> Matrix3<f64> {
254    eci_to_ecef(time).transpose()
255}
256/// Coordinate conversion from the Earth-centered Earth-fixed (ECEF) frame to the local-level frame.
257///
258/// The ECEF frame is a right-handed Cartesian coordinate system with the origin at the Earth's center.
259/// The local-level frame is a right-handed Cartesian coordinate system with the origin at the sensor's
260/// position. The local-level frame is defined by the tangent to the ellipsoidal surface at the sensor's
261/// position. The local level frame is defined by the WGS84 latitude and longitude.
262///
263/// # Arguments
264/// - `latitude` - The WGS84 latitude in degrees
265/// - `longitude` - The WGS84 longitude in degrees
266///
267/// # Returns
268/// A 3x3 rotation matrix that converts from the ECEF frame to the local-level frame
269///
270/// # Example
271/// ```rust
272/// use nalgebra::Matrix3;
273/// use strapdown::earth;
274/// let latitude: f64 = 45.0;
275/// let longitude: f64 = 90.0;
276/// let rot: Matrix3<f64> = earth::ecef_to_lla(&latitude, &longitude);
277/// ```
278pub fn ecef_to_lla(latitude: &f64, longitude: &f64) -> Matrix3<f64> {
279    let lat: f64 = (*latitude).to_radians();
280    let lon: f64 = (*longitude).to_radians();
281
282    let mut rot: Matrix3<f64> = Matrix3::zeros();
283    rot[(0, 0)] = -lon.sin() * lat.cos();
284    rot[(0, 1)] = -lon.sin() * lat.sin();
285    rot[(0, 2)] = lat.cos();
286    rot[(1, 0)] = -lon.sin();
287    rot[(1, 1)] = lon.cos();
288    rot[(2, 0)] = -lat.cos() * lon.cos();
289    rot[(2, 1)] = -lat.cos() * lon.sin();
290    rot[(2, 2)] = -lat.sin();
291    rot
292}
293/// Coordinate conversion from the local-level frame to the Earth-centered Earth-fixed (ECEF) frame.
294///
295/// The ECEF frame is a right-handed Cartesian coordinate system with the origin at the Earth's center.
296/// The local-level frame is a right-handed Cartesian coordinate system with the origin at the sensor's
297/// position. The local-level frame is defined by the tangent to the ellipsoidal surface at the sensor's
298/// position. The local level frame is defined by the WGS84 latitude and longitude.
299///
300/// # Arguments
301/// - `latitude` - The WGS84 latitude in degrees
302/// - `longitude` - The WGS84 longitude in degrees
303///
304/// # Returns
305/// A 3x3 rotation matrix that converts from the local-level frame to the ECEF frame
306///
307/// # Example
308/// ```rust
309/// use nalgebra::Matrix3;
310/// use strapdown::earth;
311/// let latitude: f64 = 45.0;
312/// let longitude: f64 = 90.0;
313/// let rot: Matrix3<f64> = earth::lla_to_ecef(&latitude, &longitude);
314/// ```
315pub fn lla_to_ecef(latitude: &f64, longitude: &f64) -> Matrix3<f64> {
316    ecef_to_lla(latitude, longitude).transpose()
317}
318/// Convert NED displacements (north/east, meters) into changes in latitude/longitude (radians).
319///
320/// Uses a simplified WGS84 ellipsoidal Earth model to compute radii of curvature
321/// in the meridian and prime vertical, then converts linear displacements to
322/// angular offsets.
323///
324/// ## Arguments
325/// - `lat_rad`: Current geodetic latitude in **radians**.
326/// - `alt_m`: Current altitude above the ellipsoid in meters.
327/// - `d_n`: Northward displacement in meters.
328/// - `d_e`: Eastward displacement in meters.
329///
330/// ## Returns
331/// A tuple `(dlat, dlon)`:
332/// - `dlat`: Change in latitude (radians).
333/// - `dlon`: Change in longitude (radians).
334///
335/// ## Notes
336/// - A small clamp is applied to `cos(lat)` to avoid division by zero at the poles.
337/// - This is an approximation sufficient for small offsets (meters to kilometers).
338///
339/// ## Example
340///
341/// ```
342/// let lat0 = 40.0_f64.to_radians();
343/// let alt = 0.0;
344/// // Move 100 m north and 50 m east
345/// let (dlat, dlon) = strapdown::earth::meters_ned_to_dlat_dlon(lat0, alt, 100.0, 50.0);
346/// println!("Δlat = {} rad, Δlon = {} rad", dlat, dlon);
347/// ```
348pub fn meters_ned_to_dlat_dlon(lat_rad: f64, alt_m: f64, d_n: f64, d_e: f64) -> (f64, f64) {
349    // WGS84 principal radii (approx)
350    let a = 6378137.0;
351    let e2 = 6.69437999014e-3;
352    let sin_lat = lat_rad.sin();
353    let rn = a / (1.0 - e2 * sin_lat * sin_lat).sqrt();
354    let re = rn * (1.0 - e2) / (1.0 - e2 * sin_lat * sin_lat);
355    let dlat = d_n / (rn + alt_m);
356    let dlon = d_e / ((re + alt_m) * lat_rad.cos().max(1e-6));
357    (dlat, dlon)
358}
359/// Compute the great-circle distance between two geodetic coordinates
360/// using the haversine formula.
361///
362/// This assumes a spherical Earth with mean radius `R = 6,371,000 m`.
363/// For higher precision you can adapt this to use ellipsoidal formulas,
364/// but haversine is usually accurate to within ~0.5% for most navigation
365/// and simulation purposes.
366///
367/// ## Arguments
368/// - `lat1_rad`: Latitude of first point (radians).
369/// - `lon1_rad`: Longitude of first point (radians).
370/// - `lat2_rad`: Latitude of second point (radians).
371/// - `lon2_rad`: Longitude of second point (radians).
372///
373/// ## Returns
374/// Great-circle distance between the two points, in meters.
375///
376/// ## Example
377/// ```
378/// let d = strapdown::earth::haversine_distance(
379///     40.0_f64.to_radians(), -75.0_f64.to_radians(),
380///     41.0_f64.to_radians(), -74.0_f64.to_radians(),
381/// );
382/// println!("Distance: {:.1} km", d / 1000.0);
383/// ```
384pub fn haversine_distance(
385    lat1_rad: f64,
386    lon1_rad: f64,
387    lat2_rad: f64,
388    lon2_rad: f64,
389) -> f64 {
390    let dlat = lat2_rad - lat1_rad;
391    let dlon = lon2_rad - lon1_rad;
392
393    let a = (dlat / 2.0).sin().powi(2)
394        + lat1_rad.cos() * lat2_rad.cos() * (dlon / 2.0).sin().powi(2);
395
396    let c = 2.0 * a.sqrt().atan2((1.0 - a).sqrt());
397
398    const R: f64 = 6_371_000.0; // mean Earth radius in meters
399    R * c
400}
401
402/// Calculate principal radii of curvature
403///
404/// The [principal radii of curvature](https://en.wikipedia.org/wiki/Earth_radius) are used to
405/// calculate and convert Cartesian body frame quantities to the local-level frame WGS84 coordinates.
406///
407/// # Arguments
408/// - `latitude` - The WGS84 latitude in degrees
409/// - `altitude` - The WGS84 altitude in meters
410///
411/// # Returns
412/// A tuple of the principal radii of curvature (r_n, r_e, r_p) in meters where r_n is the radius
413/// of curvature in the prime vertical (alternatively as _N_ or R_N), r_e is the radius of curvature
414/// in the meridian (alternatively _M_ or R_M), and r_p is the radius of curvature in the local
415/// normal direction.
416///
417/// # Example
418/// ```rust
419/// use strapdown::earth;
420/// let latitude: f64 = 45.0;
421/// let altitude: f64 = 1000.0;
422/// let (r_n, r_e, r_p) = earth::principal_radii(&latitude, &altitude);
423/// ```
424pub fn principal_radii(latitude: &f64, altitude: &f64) -> (f64, f64, f64) {
425    let latitude_rad: f64 = (latitude).to_radians();
426    let sin_lat: f64 = latitude_rad.sin();
427    let sin_lat_sq: f64 = sin_lat * sin_lat;
428    let r_n: f64 = (EQUATORIAL_RADIUS * (1.0 - ECCENTRICITY_SQUARED))
429        / (1.0 - ECCENTRICITY_SQUARED * sin_lat_sq).powf(3.0 / 2.0);
430    let r_e: f64 = EQUATORIAL_RADIUS / (1.0 - ECCENTRICITY_SQUARED * sin_lat_sq).sqrt();
431    let r_p: f64 = r_e * latitude_rad.cos() + altitude;
432    (r_n, r_e, r_p)
433}
434/// Calculate the WGS84 gravity scalar
435///
436/// The [gravity model](https://en.wikipedia.org/wiki/Gravity_of_Earth) is based on the [Somigliana
437/// method](https://en.wikipedia.org/wiki/Theoretical_gravity#Somigliana_equation), which models
438/// the Earth's gravity as a function of the latitude and altitude. The gravity model is used to
439/// calculate the gravitational force scalar in the local-level frame. Free-air correction is applied.
440///
441/// # Arguments
442/// - `latitude` - The WGS84 latitude in degrees
443/// - `altitude` - The WGS84 altitude in meters
444///
445/// # Returns
446/// The gravitational force scalar in m/s^2
447///
448/// # Example
449/// ```rust
450/// use strapdown::earth;
451/// let latitude: f64 = 45.0;
452/// let altitude: f64 = 1000.0;
453/// let grav = earth::gravity(&latitude, &altitude);
454/// ```
455pub fn gravity(latitude: &f64, altitude: &f64) -> f64 {
456    let sin_lat: f64 = (latitude).to_radians().sin();
457    let g0: f64 = (GE * (1.0 + K * sin_lat * sin_lat))
458        / (1.0 - ECCENTRICITY_SQUARED * sin_lat * sin_lat).sqrt();
459    g0 - 3.08e-6 * altitude
460}
461/// Calculate the gravitational force vector in the local-level frame
462///
463/// The [gravity model](https://en.wikipedia.org/wiki/Gravity_of_Earth) is based on the [Somigliana
464/// method](https://en.wikipedia.org/wiki/Theoretical_gravity#Somigliana_equation), which models
465/// the Earth's gravity as a function of the latitude and altitude. The gravity model is used to
466/// calculate the gravitational force vector in the local-level frame. This is then combined
467/// with the rotational effects of the Earth to calculate the effective gravity vector. This
468/// differs from the gravity scalar in that it includes the centrifugal effects of the Earth's
469/// rotation.
470///
471/// *Note:* Local level frame coordinates are odd and mixed and can be defined as North, East,
472/// Down (NED) or East, North, Up (ENU). This function uses the ENU convention, thus gravity acts
473/// along the negative Z-axis (downward) in the local-level frame.
474///
475/// # Arguments
476/// - `latitude` - The WGS84 latitude in degrees
477/// - `longitude` - The WGS84 longitude in degrees
478/// - `altitude` - The WGS84 altitude in meters
479///
480/// # Returns
481/// The gravitational force vector in m/s^2 in the local-level frame
482///
483/// # Example
484/// ```rust
485/// use strapdown::earth;
486/// let latitude: f64 = 45.0;
487/// let longitude: f64 = 90.0;
488/// let altitude: f64 = 1000.0;
489/// let grav = earth::gravitation(&latitude, &longitude, &altitude);
490/// ```
491pub fn gravitation(latitude: &f64, longitude: &f64, altitude: &f64) -> Vector3<f64> {
492    let latitude = wrap_latitude(*latitude);
493    let longitude = wrap_to_180(*longitude);
494    let wgs84: WGS84<f64> = WGS84::from_degrees_and_meters(latitude, longitude, *altitude);
495    let ecef: ECEF<f64> = ECEF::from(wgs84);
496    // Get centrifugal terms in ECEF
497    let ecef_vec: Vector3<f64> = Vector3::new(ecef.x(), ecef.y(), ecef.z());
498    let omega_ie: Matrix3<f64> = vector_to_skew_symmetric(&RATE_VECTOR);
499    // Get rotation and gravity in LLA
500    let rot: Matrix3<f64> = ecef_to_lla(&latitude, &longitude);
501    let gravity: Vector3<f64> = Vector3::new(0.0, 0.0, gravity(&latitude, altitude));
502    // Calculate the effective gravity vector combining gravity and centrifugal terms
503    gravity + rot * omega_ie * omega_ie * ecef_vec
504}
505/// Calculate local gravity anomaly from IMU accelerometer measurements
506///
507/// This function calculates the local gravity anomaly by comparing the observed gravity from the
508/// IMU accelerometer measurements (eg: $\sqrt(a_x^2 + a_y^2 + a_z^2)$) with the normal gravity
509/// at the given latitude and altitude via the Somigliana method. Additionally, this function
510/// compensates for the motion of the platform (if any) using the Eötvös correction.
511///
512/// # Arguments
513/// - `latitude` - The WGS84 latitude in degrees
514/// - `altitude` - The WGS84 altitude in meters
515/// - `north_velocity` - The northward velocity component in m/s
516/// - `east_velocity` - The eastward velocity component in m/s
517/// - `gravity_observed` - The observed gravity from the IMU accelerometer measurements in m/s^2
518///
519/// # Returns
520/// The local gravity anomaly in m/s^2, which is the difference between the observed gravity and the normal gravity at the given latitude and altitude, adjusted for the Eötvös correction.
521pub fn gravity_anomaly(
522    latitude: &f64,
523    altitude: &f64,
524    north_velocity: &f64,
525    east_velocity: &f64,
526    gravity_observed: &f64,
527) -> f64 {
528    let normal_gravity: f64 = gravity(latitude, &0.0);
529    let eotvos_correction: f64 = eotvos(latitude, altitude, north_velocity, east_velocity);
530    *gravity_observed - normal_gravity - eotvos_correction
531}
532/// Calculate the Eötvös correction for the local-level frame
533///
534/// The Eötvös correction accounts for the centrifugal acceleration caused by the vehicle's motion
535/// relative to the Earth's rotation. It depends on the platform's velocity, latitude, and Earth's
536/// angular velocity. The correction is generally added to the observed gravity measurement to
537/// account for this effect. The formula can be complex, involving latitude, velocity components
538/// (East-West), and Earth's rotation rate.
539///
540/// # Arguments
541/// - `latitude` - The WGS84 latitude in radians
542/// - `altitude` - The WGS84 altitude in meters
543/// - `north_velocity` - The northward velocity component in m/s
544/// - `east_velocity` - The eastward velocity component in m/s
545///
546/// # Returns
547/// The Eötvös correction in m/s^2
548pub fn eotvos(latitude: &f64, altitude: &f64, north_velocity: &f64, east_velocity: &f64) -> f64 {
549    let (_, _, r_p) = principal_radii(latitude, altitude);
550    2.0 * RATE * *east_velocity * latitude.cos()
551        + (north_velocity.powi(2) + east_velocity.powi(2)) / r_p
552}
553
554/// Calculate the Earth rotation rate vector in the local-level frame
555///
556/// The Earth's rotation rate modeled as a vector in the local-level frame. This vector
557/// is used to calculate the Coriolis and centrifugal effects in the local-level frame.
558///
559/// # Arguments
560/// - `latitude` - The WGS84 latitude in degrees
561///
562/// # Returns
563/// The Earth's rotation rate vector in rad/s in the local-level frame
564///
565/// # Example
566/// ```rust
567/// use strapdown::earth;
568/// let latitude: f64 = 45.0;
569/// let omega_ie = earth::earth_rate_lla(&latitude);
570/// ```
571pub fn earth_rate_lla(latitude: &f64) -> Vector3<f64> {
572    let sin_lat: f64 = (latitude).to_radians().sin();
573    let cos_lat: f64 = (latitude).to_radians().cos();
574    let omega_ie: Vector3<f64> = Vector3::new(RATE * cos_lat, 0.0, -RATE * sin_lat);
575    omega_ie
576}
577/// Calculate the transport rate vector in the local-level frame
578///
579/// The transport rate is used to calculate the rate of change of the local-level frame
580/// with respect to the ECEF frame since the origin point of the local-level frame is
581/// always tangential to the WGS84 ellipsoid and thus constantly moving in the ECEF frame.
582///
583/// # Arguments
584/// - `latitude` - The WGS84 latitude in degrees
585/// - `altitude` - The WGS84 altitude in meters
586/// - `velocities` - The velocity vector in the local-level frame (northward, eastward, downward)
587///
588/// # Returns
589/// The transport rate vector in m/s^2 in the local-level frame
590///
591/// # Example
592/// ```rust
593/// use nalgebra::Vector3;
594/// use strapdown::earth;
595/// let latitude: f64 = 45.0;
596/// let altitude: f64 = 1000.0;
597/// let velocities: Vector3<f64> = Vector3::new(10.0, 0.0, 0.0);
598/// let omega_en_n = earth::transport_rate(&latitude, &altitude, &velocities);
599/// ```
600pub fn transport_rate(latitude: &f64, altitude: &f64, velocities: &Vector3<f64>) -> Vector3<f64> {
601    let (r_n, r_e, _) = principal_radii(latitude, altitude);
602    let lat_rad = latitude.to_radians();
603    let omega_en_n: Vector3<f64> = Vector3::new(
604        -velocities[1] / (r_n + *altitude),
605        velocities[0] / (r_e + *altitude),
606        velocities[0] * lat_rad.tan() / (r_n + *altitude),
607    );
608    omega_en_n
609}
610/// Calculate the magnetic field using the Earth's dipole model in the local-level frame
611///
612/// This function computes the Earth's magnetic field at a given position using a simple
613/// dipole model. The dipole model approximates the Earth's magnetic field as a magnetic
614/// dipole with the axis through the geographic poles.
615///
616/// # Arguments
617/// - `latitude` - The WGS84 latitude in degrees
618/// - `longitude` - The WGS84 longitude in degrees  
619/// - `altitude` - The WGS84 altitude in meters
620///
621/// # Returns
622/// The magnetic field vector in nano teslas (nT) in the local-level frame (North, East, Down)
623///
624/// # Example
625/// ```rust
626/// use nalgebra::Vector3;
627/// use strapdown::earth;
628/// let latitude: f64 = 45.0;
629/// let longitude: f64 = -75.0;
630/// let altitude: f64 = 0.0;
631/// let magnetic_field = earth::calculate_magnetic_field(&latitude, &longitude, &altitude);
632/// ```
633pub fn calculate_magnetic_field(latitude: &f64, longitude: &f64, altitude: &f64) -> Vector3<f64> {
634    // Calculate the magnetic colatitude and longitude
635    let (mag_colatitude, _) = wgs84_to_magnetic(latitude, longitude);
636
637    // Calculate the radial and latitudinal components of the magnetic field
638    let radial_field = calculate_radial_magnetic_field(mag_colatitude.to_radians(), *altitude);
639    let lat_field = calculate_latitudinal_magnetic_field(mag_colatitude.to_radians(), *altitude);
640
641    // Create the magnetic field vector in the local-level frame (NED)
642    let b_vector: Vector3<f64> = Vector3::new(radial_field, lat_field, 0.0);
643
644    b_vector
645}
646
647/// Calculate the radial component of Earth's magnetic field using the dipole model
648///
649/// # Arguments
650/// - `colatitude` - The magnetic *colatitude* in radians (angle from magnetic north pole)
651/// - `radius` - The distance from Earth's center in meters
652///
653/// # Returns
654/// The radial component of the magnetic field in nano teslas (nT)
655///
656/// # Example
657/// ```rust
658/// use strapdown::earth;
659/// let colatitude: f64 = 1.0;
660/// let radius: f64 = 6371000.0;
661/// let radial_field = earth::calculate_radial_magnetic_field(colatitude, radius);
662/// ```
663pub fn calculate_radial_magnetic_field(colatitude: f64, radius: f64) -> f64 {
664    // let radius_ratio = radius / MAGNETIC_REFERENCE_RADIUS;
665    // return -2.0 * MAGNETIC_FIELD_STRENGTH / radius_ratio.powi(3) * latitude.sin();
666    -2.0 * MAGNETIC_FIELD_STRENGTH * (MEAN_RADIUS / radius).powi(3) * colatitude.cos()
667}
668
669/// Calculate the latitudinal component of Earth's magnetic field using the dipole model
670///
671/// # Arguments
672/// - `colatitude` - The magnetic *colatitude* in radians (angle from magnetic north pole)
673/// - `radius` - The distance from Earth's center in meters
674///
675/// # Returns
676/// The latitudinal component of the magnetic field in nano teslas (nT)
677///
678/// # Example
679/// ```rust
680/// use strapdown::earth;
681/// let colatitude: f64 = 1.0;
682/// let radius: f64 = 6371000.0;
683/// let lat_field = earth::calculate_latitudinal_magnetic_field(colatitude, radius);
684/// ```
685pub fn calculate_latitudinal_magnetic_field(colatitude: f64, radius: f64) -> f64 {
686    -MAGNETIC_FIELD_STRENGTH * (MEAN_RADIUS / radius).powi(3) * colatitude.sin()
687}
688/// Calculate magnetic colatitude and longitude from WGS84 coordinates
689///
690/// This function transforms WGS84 geographic coordinates to geomagnetic coordinates
691/// using the dipole model of Earth's magnetic field. The transformation is based on
692/// the location of the geomagnetic north pole.
693///
694/// # Arguments
695/// - `latitude` - The WGS84 latitude in degrees
696/// - `longitude` - The WGS84 longitude in degrees
697///
698/// # Returns
699/// A tuple containing (magnetic_colatitude, magnetic_longitude) in degrees. Colatitude
700/// is the angle from the magnetic north pole [0, 180], and longitude is the angle from the
701/// magnetic meridian.
702///
703/// # Example
704/// ```rust
705/// use strapdown::earth;
706/// let latitude = 45.0;
707/// let longitude = -75.0;
708/// let (mag_lat, mag_lon) = earth::wgs84_to_magnetic(&latitude, &longitude);
709/// ```
710pub fn wgs84_to_magnetic(latitude: &f64, longitude: &f64) -> (f64, f64) {
711    // Convert all angles to radians for calculations
712    let lat_rad = latitude.to_radians();
713    let lon_rad = longitude.to_radians();
714    let mag_lat_rad = MAGNETIC_NORTH_LATITUDE.to_radians();
715    let mag_lon_rad = MAGNETIC_NORTH_LONGITUDE.to_radians();
716
717    // Calculate the magnetic latitude
718    // This is based on the spherical angle between the point and the geomagnetic pole
719    let cos_theta = lat_rad.sin() * mag_lat_rad.sin()
720        + lat_rad.cos() * mag_lat_rad.cos() * (lon_rad - mag_lon_rad).cos();
721    // Calculate magnetic longitude
722    // This requires finding the azimuth from the magnetic pole to the point
723    let y = (lon_rad - mag_lon_rad).sin() * lat_rad.cos();
724    let x = mag_lat_rad.cos() * lat_rad.sin()
725        - mag_lat_rad.sin() * lat_rad.cos() * (lon_rad - mag_lon_rad).cos();
726
727    // Magnetic latitude is defined as the angle from the magnetic pole
728    let mag_latitude = cos_theta.acos().to_degrees();
729    // Magnetic longitude is defined relative to the magnetic meridian (0°)
730    let mag_longitude = y.atan2(x).to_degrees();
731
732    (mag_latitude, mag_longitude)
733}
734/// Calculate the magnetic inclination (dip angle) at a given location
735///
736/// The magnetic inclination is the angle between the horizontal plane and the
737/// magnetic field vector, positive downward. At the magnetic equator, the inclination
738/// is zero. At the magnetic poles, the inclination is ±90°.
739///
740/// # Arguments
741/// - `latitude` - The WGS84 latitude in degrees
742/// - `longitude` - The WGS84 longitude in degrees
743/// - `altitude` - The WGS84 altitude in meters
744///
745/// # Returns
746/// The magnetic inclination angle in degrees
747///
748/// # Example
749/// ```rust
750/// use strapdown::earth;
751/// let latitude = 45.0;
752/// let longitude = -75.0;
753/// let altitude = 0.0;
754/// let inclination = earth::magnetic_inclination(&latitude, &longitude, &altitude);
755/// ```
756pub fn magnetic_inclination(latitude: &f64, longitude: &f64, altitude: &f64) -> f64 {
757    // Get the magnetic field vector in NED coordinates
758    let b_vector = calculate_magnetic_field(latitude, longitude, altitude);
759
760    // Horizontal component magnitude (North-East plane)
761    let b_h = (b_vector[0].powi(2) + b_vector[1].powi(2)).sqrt();
762
763    // Calculate inclination (dip angle)
764    // Positive downward, negative upward
765
766    (b_vector[2] / b_h).atan().to_degrees()
767}
768/// Calculate the magnetic declination (variation) at a given location
769///
770/// The magnetic declination is the angle between true north and magnetic north,
771/// positive eastward. This is essential for navigation as it represents the correction
772/// needed to convert between magnetic compass readings and true bearings.
773///
774/// # Arguments
775/// - `latitude` - The WGS84 latitude in degrees
776/// - `longitude` - The WGS84 longitude in degrees
777/// - `altitude` - The WGS84 altitude in meters
778///
779/// # Returns
780/// The magnetic declination angle in degrees
781///
782/// # Example
783/// ```rust
784/// use strapdown::earth;
785/// let latitude = 45.0;
786/// let longitude = -75.0;
787/// let altitude = 0.0;
788/// let declination = earth::magnetic_declination(&latitude, &longitude, &altitude);
789/// ```
790pub fn magnetic_declination(latitude: &f64, longitude: &f64, altitude: &f64) -> f64 {
791    // Get the magnetic field vector in NED coordinates
792    let b_vector = calculate_magnetic_field(latitude, longitude, altitude);
793
794    // Calculate declination (variation)
795    // Positive eastward, negative westward
796
797    (b_vector[1] / b_vector[0]).atan().to_degrees()
798}
799/// Calculate the magnetic anomaly at a given location
800pub fn magnetic_anomaly(
801    magnetic_field: GeomagneticField,
802    mag_x: f64,
803    mag_y: f64,
804    mag_z: f64,
805) -> f64 {
806    // f64::NAN * latitude * longitude * altitude * mag_x * mag_y * mag_z // Placeholder for magnetic anomaly calculation to squash warnings
807    let obs = (mag_x.powi(2) + mag_y.powi(2) + mag_z.powi(2)).sqrt();
808    obs - (magnetic_field.f().value as f64)
809}
810// === Unit tests ===
811#[cfg(test)]
812mod tests {
813    use super::*;
814    use assert_approx_eq::assert_approx_eq;
815    const KM: f64 = 1000.0;
816    #[test]
817    fn vector_to_skew_symmetric() {
818        let v: Vector3<f64> = Vector3::new(1.0, 2.0, 3.0);
819        let skew: Matrix3<f64> = super::vector_to_skew_symmetric(&v);
820        assert_eq!(skew[(0, 1)], -v[2]);
821        assert_eq!(skew[(0, 2)], v[1]);
822        assert_eq!(skew[(1, 0)], v[2]);
823        assert_eq!(skew[(1, 2)], -v[0]);
824        assert_eq!(skew[(2, 0)], -v[1]);
825        assert_eq!(skew[(2, 1)], v[0]);
826    }
827    #[test]
828    fn skew_symmetric_to_vector() {
829        let v: Vector3<f64> = Vector3::new(1.0, 2.0, 3.0);
830        let skew: Matrix3<f64> = super::vector_to_skew_symmetric(&v);
831        let v2: Vector3<f64> = super::skew_symmetric_to_vector(&skew);
832        assert_eq!(v, v2);
833    }
834    #[test]
835    fn gravity() {
836        // test polar gravity
837        let latitude: f64 = 90.0;
838        let grav = super::gravity(&latitude, &0.0);
839        assert_approx_eq!(grav, GP);
840        // test equatorial gravity
841        let latitude: f64 = 0.0;
842        let grav = super::gravity(&latitude, &0.0);
843        assert_approx_eq!(grav, GE);
844    }
845    #[test]
846    fn gravitation() {
847        // test equatorial gravity
848        let latitude: f64 = 0.0;
849        let altitude: f64 = 0.0;
850        let grav: Vector3<f64> = super::gravitation(&latitude, &0.0, &altitude);
851        assert_approx_eq!(grav[0], 0.0);
852        assert_approx_eq!(grav[1], 0.0);
853        assert_approx_eq!(grav[2], (GE + 0.0339), 1e-4);
854        // test polar gravity
855        let latitude: f64 = 90.0;
856        let grav: Vector3<f64> = super::gravitation(&latitude, &0.0, &altitude);
857        assert_approx_eq!(grav[0], 0.0);
858        assert_approx_eq!(grav[1], 0.0);
859        assert_approx_eq!(grav[2], GP, 1e-2);
860    }
861    #[test]
862    fn magnetic_radial_field() {
863        // Using magnetic co-latitude [0, 180]
864        let lat: f64 = 0.0;
865        let b_r: f64 = calculate_radial_magnetic_field(lat.to_radians(), MEAN_RADIUS);
866        assert_approx_eq!(b_r, -2.0 * MAGNETIC_FIELD_STRENGTH, 1e-7);
867        let lat: f64 = 180.0;
868        let b_r: f64 = calculate_radial_magnetic_field(lat.to_radians(), MEAN_RADIUS);
869        assert_approx_eq!(b_r, 2.0 * MAGNETIC_FIELD_STRENGTH, 1e-7);
870        let lat: f64 = 90.0;
871        let b_r: f64 = calculate_radial_magnetic_field(lat.to_radians(), MEAN_RADIUS);
872        assert_approx_eq!(b_r, 0.0, 1e-7);
873    }
874    #[test]
875    fn wgs84_to_magnetic() {
876        let lat: f64 = 80.8;
877        let lon: f64 = -72.8;
878        let (mag_lat, mag_lon) = super::wgs84_to_magnetic(&lat, &lon);
879        assert_approx_eq!(mag_lat, 0.0, 1e-7);
880        assert_approx_eq!(mag_lon, 0.0, 1e-7);
881    }
882    #[test]
883    fn eci_to_ecef() {
884        let time: f64 = 30.0;
885        let rot: Matrix3<f64> = super::eci_to_ecef(time);
886        assert_approx_eq!(rot[(0, 0)], (RATE * time).cos(), 1e-7);
887        assert_approx_eq!(rot[(0, 1)], (RATE * time).sin(), 1e-7);
888        assert_approx_eq!(rot[(1, 0)], -(RATE * time).sin(), 1e-7);
889        assert_approx_eq!(rot[(1, 1)], (RATE * time).cos(), 1e-7);
890        let rot_t = ecef_to_eci(time);
891        assert_approx_eq!(rot_t[(0, 0)], (RATE * time).cos(), 1e-7);
892        assert_approx_eq!(rot_t[(0, 1)], -(RATE * time).sin(), 1e-7);
893        assert_approx_eq!(rot_t[(1, 0)], (RATE * time).sin(), 1e-7);
894        assert_approx_eq!(rot_t[(1, 1)], (RATE * time).cos(), 1e-7);
895        assert_approx_eq!(rot_t[(2, 2)], 1.0, 1e-7);
896    }
897    #[test]
898    fn ecef_to_lla() {
899        let latitude: f64 = 45.0;
900        let longitude: f64 = 90.0;
901        let rot: Matrix3<f64> = super::ecef_to_lla(&latitude, &longitude);
902        assert_approx_eq!(
903            rot[(0, 0)],
904            -longitude.to_radians().sin() * latitude.to_radians().cos(),
905            1e-7
906        );
907        assert_approx_eq!(
908            rot[(0, 1)],
909            -longitude.to_radians().sin() * latitude.to_radians().sin(),
910            1e-7
911        );
912        assert_approx_eq!(rot[(0, 2)], latitude.to_radians().cos(), 1e-7);
913        assert_approx_eq!(rot[(1, 0)], -longitude.to_radians().sin(), 1e-7);
914        assert_approx_eq!(rot[(1, 1)], longitude.to_radians().cos(), 1e-7);
915        assert_approx_eq!(
916            rot[(2, 0)],
917            -latitude.to_radians().cos() * longitude.to_radians().cos(),
918            1e-7
919        );
920        assert_approx_eq!(
921            rot[(2, 1)],
922            -latitude.to_radians().cos() * longitude.to_radians().sin(),
923            1e-7
924        );
925        assert_approx_eq!(rot[(2, 2)], -latitude.to_radians().sin(), 1e-7);
926    }
927    #[test]
928    fn lla_to_ecef() {
929        let latitude: f64 = 45.0;
930        let longitude: f64 = 90.0;
931        let rot1: Matrix3<f64> = super::lla_to_ecef(&latitude, &longitude);
932        let rot2: Matrix3<f64> = super::ecef_to_lla(&latitude, &longitude).transpose();
933        assert_approx_eq!(rot1[(0, 0)], rot2[(0, 0)], 1e-7);
934        assert_approx_eq!(rot1[(0, 1)], rot2[(0, 1)], 1e-7);
935        assert_approx_eq!(rot1[(0, 2)], rot2[(0, 2)], 1e-7);
936        assert_approx_eq!(rot1[(1, 0)], rot2[(1, 0)], 1e-7);
937        assert_approx_eq!(rot1[(1, 1)], rot2[(1, 1)], 1e-7);
938        assert_approx_eq!(rot1[(1, 2)], rot2[(1, 2)], 1e-7);
939        assert_approx_eq!(rot1[(2, 0)], rot2[(2, 0)], 1e-7);
940        assert_approx_eq!(rot1[(2, 1)], rot2[(2, 1)], 1e-7);
941        assert_approx_eq!(rot1[(2, 2)], rot2[(2, 2)], 1e-7);
942    }
943    #[test]
944    fn test_meters_ned_to_dlat_dlon() {
945        // Test the conversion from North/East meters to latitude/longitude deltas
946
947        // At the equator, 1 degree of latitude is approximately 111.32 km
948        // and 1 degree of longitude is approximately 111.32 km as well
949        let lat_rad = 0.0; // equator
950        let alt_m = 0.0; // sea level
951
952        // Test northward offset
953        let (dlat, dlon) = meters_ned_to_dlat_dlon(lat_rad, alt_m, 1852.0, 0.0);
954        assert_approx_eq!(dlat.abs(), (1.0 / 60.0 as f64).to_radians(), 0.0001); // ~1 degree latitude change
955        assert_approx_eq!(dlon.abs(), 0.0, 0.0001); // ~0 longitude change
956
957        // Test eastward offset
958        let (dlat, dlon) = meters_ned_to_dlat_dlon(lat_rad, alt_m, 0.0, 1852.0);
959        assert!(dlat.abs() < 0.0001); // ~0 latitude change
960        assert_approx_eq!(dlon.abs(), (1.0 / 60.0 as f64).to_radians(), 0.0001); // ~1 degree longitude change
961
962        // Test at 45 degrees north, where longitude degrees are shorter
963        let lat_rad = 45.0_f64.to_radians();
964
965        // At 45°N, 1 degree of longitude is about 111.32 * cos(45°) = 78.7 km
966        let (dlat, dlon) = meters_ned_to_dlat_dlon(lat_rad, alt_m, 0.0, 111.320);
967        assert_approx_eq!(dlat.abs(), 0.0, 0.0001); // ~0 latitude change
968        assert_approx_eq!(dlon.abs(), 0.0, 0.0001); // ~1 degree longitude change
969    }
970
971    #[test]
972    fn zero_distance() {
973        let lat = 40.0_f64.to_radians();
974        let lon = -75.0_f64.to_radians();
975        let d = haversine_distance(lat, lon, lat, lon);
976        assert!(d.abs() < 1e-9, "Zero distance should be ~0, got {}", d);
977    }
978
979    #[test]
980    fn quarter_circumference_equator() {
981        // From (0,0) to (0,90°E) is a quarter of Earth's circumference
982        let d = haversine_distance(0.0, 0.0, 0.0, 90_f64.to_radians());
983        let expected = std::f64::consts::FRAC_PI_2 * 6_371_000.0; // R * π/2
984        let err = (d - expected).abs();
985        assert!(err < 1e-6 * expected, "Error too large: got {}, expected {}", d, expected);
986    }
987
988    #[test]
989    fn antipodal_points() {
990        // (0,0) vs (0,180°E) → half Earth's circumference
991        let d = haversine_distance(0.0, 0.0, 0.0, 180_f64.to_radians());
992        let expected = std::f64::consts::PI * 6_371_000.0; // R * π
993        let err = (d - expected).abs();
994        assert!(err < 1e-6 * expected, "Error too large: got {}, expected {}", d, expected);
995    }
996
997    #[test]
998    fn known_baseline_nyc_to_london() {
999        // Approx coordinates
1000        let nyc_lat = 40.7128_f64.to_radians();
1001        let nyc_lon = -74.0060_f64.to_radians();
1002        let lon_lat = 51.5074_f64.to_radians();
1003        let lon_lon = -0.1278_f64.to_radians();
1004
1005        let d = haversine_distance(nyc_lat, nyc_lon, lon_lat, lon_lon);
1006        // Real-world great-circle distance ~5567 km
1007        assert!((d / KM - 5567.0).abs() < 50.0, "NYC-LON distance off: {} km", d / KM);
1008    }
1009}