diff --git a/notebooks/15_flightplanning_tuto.ipynb b/notebooks/15_flightplanning_tuto.ipynb index 2d1e229b8c..9fede7e6d8 100644 --- a/notebooks/15_flightplanning_tuto.ipynb +++ b/notebooks/15_flightplanning_tuto.ipynb @@ -73,7 +73,20 @@ "source": [ "import datetime\n", "\n", + "from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import (\n", + " AircraftState,\n", + ")\n", + "from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import (\n", + " PerformanceModelEnum,\n", + ")\n", + "from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import (\n", + " PhaseEnum,\n", + ")\n", + "from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import (\n", + " RatingEnum,\n", + ")\n", "from skdecide.hub.domain.flight_planning.domain import FlightPlanningDomain, WeatherDate\n", + "from skdecide.hub.domain.flight_planning.flightplanning_utils import plot_network\n", "from skdecide.hub.solver.astar import Astar\n", "\n", "# reload\n", @@ -149,6 +162,35 @@ "cost_function = \"fuel\"" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Definition of the aircraft initial state\n", + "Now, we define the aircraft state. This implies picking an aircraft performance model : `OPENAP` or `POLL_SCHUMANN`" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "acState = AircraftState(\n", + " model_type=\"A320\", # only for OPENAP and POLL_SCHUMANN\n", + " performance_model_type=PerformanceModelEnum.POLL_SCHUMANN, # PerformanceModelEnum.OPENAP\n", + " gw_kg=80_000,\n", + " zp_ft=10_000,\n", + " mach_cruise=0.7,\n", + " cas_climb_kts=250,\n", + " cas_descent_kts=220,\n", + " phase=PhaseEnum.CLIMB,\n", + " rating_level=RatingEnum.MCL,\n", + " cg=0.3,\n", + " gamma_air_deg=0,\n", + ")" + ] + }, { "attachments": {}, "cell_type": "markdown", @@ -166,29 +208,28 @@ "outputs": [], "source": [ "domain_factory = lambda: FlightPlanningDomain(\n", - " origin,\n", - " destination,\n", - " aircraft,\n", - " weather_date=weather_date,\n", - " heuristic_name=heuristic,\n", - " perf_model_name=\"openap\", # a/c performance model\n", + " origin=origin,\n", + " destination=destination,\n", + " aircraft_state=acState,\n", " objective=cost_function,\n", - " fuel_loop=False,\n", - " graph_width=\"normal\",\n", + " heuristic_name=heuristic,\n", + " weather_date=weather_date,\n", + " cruise_height_min=35_000,\n", + " cruise_height_max=42_000,\n", + " graph_width=\"medium\", # small, medium, large, xlarge\n", + " nb_vertical_points=5, # flight levels in cruise\n", + " nb_forward_points=5,\n", + " nb_lateral_points=7, # must be odd\n", ")\n", "\n", "domain = domain_factory()" ] }, { - "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ - "## Solving and rendering out the flight planning domain\n", - "\n", - "We use here an A* solver as mentionned before. \n", - "We also use the custom rollout proposed to have some visualization during the flight planning generation." + "We can plot the graph:" ] }, { @@ -197,22 +238,18 @@ "metadata": {}, "outputs": [], "source": [ - "with Astar(\n", - " heuristic=lambda d, s: d.heuristic(s), domain_factory=domain_factory, parallel=False\n", - ") as solver:\n", - " solver.solve()\n", - " domain.custom_rollout(solver=solver)" + "plot_network(domain)" ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ - "## Changing aircraft performance model\n", - "\n", - "One of the new features of the flight planning domain is the addition of another aircraft performance model. Indeed, the default is OpenAP (`openap`) but we can now choose [Poll-Schumann](https://elib.dlr.de/135592/1/Poll_Schumann_estimation_method_fuel_burn_performance_aircraft_cruise_part_1_fundamentals_2020.pdf) (`PS`), which is more accurate.\n", + "## Solving and rendering out the flight planning domain\n", "\n", - "Thus, we can run the solver on the domain with a Poll-Schumann A/C performance model:" + "We use here an A* solver as mentionned before. \n", + "We also use the custom rollout proposed to have some visualization during the flight planning generation." ] }, { @@ -221,34 +258,20 @@ "metadata": {}, "outputs": [], "source": [ - "domain_factory = lambda: FlightPlanningDomain(\n", - " origin,\n", - " destination,\n", - " aircraft,\n", - " weather_date=weather_date,\n", - " heuristic_name=heuristic,\n", - " perf_model_name=\"PS\", # a/c performance model\n", - " objective=cost_function,\n", - " fuel_loop=False,\n", - " graph_width=\"normal\",\n", - ")\n", - "\n", - "domain = domain_factory()\n", - "\n", - "with Astar(\n", - " heuristic=lambda d, s: d.heuristic(s), domain_factory=domain_factory, parallel=False\n", - ") as solver:\n", - " solver.solve()\n", - " domain.custom_rollout(solver=solver)" + "solver = Astar(\n", + " domain_factory=domain_factory,\n", + " heuristic=lambda d, s: d.heuristic(s),\n", + " parallel=False,\n", + ")" ] }, { - "cell_type": "markdown", + "cell_type": "code", + "execution_count": null, "metadata": {}, + "outputs": [], "source": [ - "## Longer routes\n", - "\n", - "Finally, we will make a long haul flight: Cartagena (ICAO: SKCG) - Toulouse (ICAO: LFBO), with an A380. For computational purposes, we will also modify the heuristic function:" + "solver.solve()" ] }, { @@ -257,37 +280,20 @@ "metadata": {}, "outputs": [], "source": [ - "heuristic = \"lazy_fuel\"\n", - "\n", - "origin = \"SKCG\"\n", - "destination = \"LFBO\"\n", - "aircraft = \"A388\"\n", - "\n", - "domain_factory = lambda: FlightPlanningDomain(\n", - " origin,\n", - " destination,\n", - " aircraft,\n", - " weather_date=weather_date,\n", - " heuristic_name=heuristic,\n", - " perf_model_name=\"PS\", # a/c performance model\n", - " objective=cost_function,\n", - " fuel_loop=False,\n", - " graph_width=\"normal\",\n", - ")\n", - "\n", - "domain = domain_factory()\n", - "\n", - "with Astar(\n", - " heuristic=lambda d, s: d.heuristic(s), domain_factory=domain_factory, parallel=False\n", - ") as solver:\n", - " solver.solve()\n", - " domain.custom_rollout(solver=solver)" + "domain.custom_rollout(solver=solver, make_img=True)" ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] } ], "metadata": { "kernelspec": { - "display_name": "Python 3 (ipykernel)", + "display_name": "test_dev_skdecide", "language": "python", "name": "python3" }, @@ -301,7 +307,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.10.13" + "version": "3.9.19" } }, "nbformat": 4, diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/base.py b/skdecide/hub/domain/flight_planning/aircraft_performance/base.py deleted file mode 100644 index 8cd078734a..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/base.py +++ /dev/null @@ -1,98 +0,0 @@ -# models fuel flows -# typing -import math -from inspect import signature -from typing import Optional - -import numpy as np -import openap -from openap.extra.aero import crossover_alt, distance, fpm, ft, kts, latlon, mach2tas - -# other -from openap.prop import aircraft - -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils import ( - pollschumann, -) -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, -) - - -class AircraftPerformanceModel: - def __init__(self, actype: str, perf_model: str = None): - self.perf_model_name = perf_model - - if perf_model == "openap": - self.perf_model = OpenAP(actype) - elif perf_model == "PS": - print("Poll-Schumann model") - self.perf_model = PollSchumannModel(actype) - else: - raise ValueError(f"Unknown performance model: {perf_model}") - - def compute_fuel_consumption( - self, - values_current: dict[str, float], - delta_time: float, - vs: Optional[float] = 0.0, - ) -> float: - - return self.perf_model.compute_fuel_consumption( - values_current, delta_time, vs=vs - ) - - def compute_crossover_altitude(self) -> float: - return self.perf_model.compute_crossover_altitude() - - -# create OpenAP class that inherits from the base class -class OpenAP(AircraftPerformanceModel): - def __init__(self, actype: str): - self.ac = aircraft(actype) - self.fuel_flow = openap.FuelFlow(ac=actype, polydeg=2).enroute - - def compute_fuel_consumption( - self, - values_current: dict[str, float], - delta_time: float, - vs: Optional[float] = 0.0, - ) -> float: - - mass_current, altitude_current, speed_current = ( - values_current["mass"], - values_current["alt"], - values_current["speed"], - ) - if "vs" in signature(self.fuel_flow).parameters: - ff = self.fuel_flow(mass_current, speed_current, altitude_current, vs=vs) - else: - path_angle = math.degrees(np.arctan2(vs * fpm, speed_current * kts)) - ff = self.fuel_flow( - mass_current, speed_current, altitude_current, path_angle=path_angle - ) - - return delta_time * ff - - def compute_crossover_altitude(self, cas, mach) -> float: - return crossover_alt(cas, mach) - - -# create aircraft performance model based on Poll-Schumann model that inherits from the base class -class PollSchumannModel(AircraftPerformanceModel): - def __init__(self, actype: str): - self.actype = actype - self.fuel_flow = pollschumann.FuelFlow(actype) - - def compute_fuel_consumption( - self, - values_current: dict[str, float], - delta_time: float, - vs: Optional[float] = 0.0, - ) -> float: - ff = self.fuel_flow(values_current, delta_time=delta_time, vs=vs) - - return delta_time * ff - - def compute_crossover_altitude(self) -> float: - return load_aircraft_engine_params(self.actype)["p_inf_co"] diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/bean/aircraft_state.py b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/aircraft_state.py new file mode 100644 index 0000000000..373001993f --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/aircraft_state.py @@ -0,0 +1,144 @@ +from dataclasses import dataclass +from typing import List, Optional + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.four_dimensions_state import ( + FourDimensionsState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.weather_state import ( + WeatherState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, +) + + +@dataclass +class AircraftState(FourDimensionsState): + """ + Class representing an aircraft state and variables. + Aircraft state: dynamic and weather state + """ + + def __init__( + self, + performance_model_type: PerformanceModelEnum = None, + model_type: Optional[str] = None, + zp_ft: Optional[float] = None, + gw_kg: Optional[float] = None, + cg: Optional[float] = None, + weather_state: Optional[WeatherState] = None, + tas_meters_per_sec: Optional[float] = None, + mach: Optional[float] = None, + mach_cruise: Optional[float] = None, + cas_climb_kts: Optional[float] = None, + cas_descent_kts: Optional[float] = None, + total_temperature_k: Optional[float] = None, + total_pressure_pa: Optional[float] = None, + # Flight + ground_dist_m: Optional[float] = None, + gamma_air_deg: Optional[float] = None, + cost_index: Optional[float] = None, # kg / min + rocd_ft_min: Optional[float] = None, + # aero + cl: Optional[float] = None, + lift_n: Optional[float] = None, + cx: Optional[float] = None, + drag_n: Optional[float] = None, + # propu + is_one_eo: Optional[bool] = False, + is_air_cond_on: Optional[bool] = False, + rating_level: Optional[RatingEnum] = None, + tsp: Optional[float] = None, # reduced tsp + thrust_n: Optional[float] = None, + fuel_flow_kg_per_sec: Optional[float] = None, + # phase + phase: Optional[PhaseEnum] = None, + ): + + self.performance_model_type = performance_model_type + + self.model_type = model_type + + self.zp_ft = zp_ft + self.gw_kg = gw_kg + self.cg = cg + + self.weather_state = weather_state + + self.tas_meters_per_sec = tas_meters_per_sec + self.mach = mach + self.mach_cruise = mach_cruise + self.cas_climb_kts = cas_climb_kts + self.cas_descent_kts = cas_descent_kts + self.total_temperature_k = total_temperature_k + self.total_pressure_pa = total_pressure_pa + + self.ground_dist_m = ground_dist_m + self.gamma_air_deg = gamma_air_deg + self.cost_index = cost_index + self.rocd_ft_min = rocd_ft_min + + self.cl = cl + self.lift_n = lift_n + self.cx = cx + self.drag_n = drag_n + + self.is_one_eo = is_one_eo + self.is_air_cond_on = is_air_cond_on + self.rating_level = rating_level + self.tsp = tsp + self.thrust_n = thrust_n + self.fuel_flow_kg_per_sec = fuel_flow_kg_per_sec + + self.phase = phase + + self.time_step = None + + if self.performance_model_type.name == PerformanceModelEnum.OPENAP.name: + self._init_openap_settings() + elif ( + self.performance_model_type.name == PerformanceModelEnum.POLL_SCHUMANN.name + ): + self._init_pollschumann_settings() + else: + raise ValueError("Error in aircraft state settings init.") + + def _init_openap_settings(self): + from openap.prop import aircraft + + ac_params = aircraft(self.model_type) + + self.MTOW = ac_params["mtow"] + self.MFC = ac_params["limits"]["MFC"] + self.MMO = ac_params["cruise"]["mach"] + + def _init_pollschumann_settings(self): + from skdecide.hub.domain.flight_planning.aircraft_performance.utils.poll_schumann_utils.engine_loader import ( + load_aircraft_engine_params, + ) + + ac_params = load_aircraft_engine_params(self.model_type) + + self.MTOW = ac_params["amass_mtow"] + self.MMO = ac_params["max_mach_num"] + self.MFC = ac_params["amass_mtow"] - ac_params["amass_mzfw"] + + def update_settings( + self, + gw_kg: Optional[float] = None, + zp_ft: Optional[float] = None, + mach: Optional[float] = None, + ): + + if gw_kg is not None: + self.gw_kg = gw_kg + if zp_ft is not None: + self.zp_ft = zp_ft + if mach is not None: + self.mach = mach diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/bean/atmos_isa.py b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/atmos_isa.py new file mode 100644 index 0000000000..503bc46a19 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/atmos_isa.py @@ -0,0 +1,56 @@ +from openap.extra.aero import ft + +TK = 273.15 + + +def temperature(altitude_ft, disa=0.0): + # Setup the dictionnary containing constants depending on zones + temp_constant = {} + temp_constant["zone1"] = {"A": 288.15, "B": -6.5e-3} + + temp_constant["zone2"] = {"A": 216.65, "B": 0.0} + + temp_constant["zone3"] = {"A": 196.65, "B": 1e-3} + + temp_constant["zone4"] = {"A": 139.05, "B": 2.8e-3} + + temp_constant["zone5"] = {"A": 270.65, "B": 0.0} + + altitude_m = altitude_ft * ft + + if altitude_m <= 11000: + zone = "zone1" + temperature_k = ( + temp_constant[zone]["A"] + temp_constant[zone]["B"] * altitude_m + disa + ) + elif altitude_m <= 20000: + zone = "zone2" + temperature_k = ( + temp_constant[zone]["A"] + temp_constant[zone]["B"] * altitude_m + disa + ) + elif altitude_m <= 32000: + zone = "zone3" + temperature_k = ( + temp_constant[zone]["A"] + temp_constant[zone]["B"] * altitude_m + disa + ) + + elif altitude_m <= 47000: + zone = "zone4" + temperature_k = ( + temp_constant[zone]["A"] + temp_constant[zone]["B"] * altitude_m + disa + ) + + else: + zone = "zone5" + temperature_k = ( + temp_constant[zone]["A"] + temp_constant[zone]["B"] * altitude_m + disa + ) + + return temperature_k + + +def disa_alt_temp(altitude_ft: float, temperature_K: float = 288.15): + + disa = temperature_K - temperature(altitude_ft, disa=0.0) + + return disa diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/bean/four_dimensions_state.py b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/four_dimensions_state.py new file mode 100644 index 0000000000..0b1d87c9c7 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/four_dimensions_state.py @@ -0,0 +1,14 @@ +from dataclasses import dataclass +from typing import Optional + + +@dataclass +class FourDimensionsState: + """ + Class representing a 4-D state (3D position and time) + """ + + latitude_deg: Optional[float] = None + longitude_deg: Optional[float] = None + zp_ft: Optional[float] = None # pressure altitude + time_sec: Optional[float] = None diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/bean/speed_schedule.py b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/speed_schedule.py new file mode 100644 index 0000000000..beeb318ef8 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/speed_schedule.py @@ -0,0 +1,12 @@ +from dataclasses import dataclass + + +@dataclass +class SpeedSchedule: + """ + Bean to store speed schedule law for climb or descent + """ + + cas_low_kt: float = 250 # CAS under 10'000 ft + cas_high_kt: float = None # CAS above 10'000 ft + mach: float = None # Mach law diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/bean/weather_state.py b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/weather_state.py new file mode 100644 index 0000000000..2d77e33ad1 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/bean/weather_state.py @@ -0,0 +1,17 @@ +from dataclasses import dataclass, field +from typing import Optional + + +@dataclass +class WeatherState: + """ + Class representing the atmosphere state + """ + + static_temperature_k: Optional[float] = None + static_pressure_pa: Optional[float] = None + rho_kg_m3: Optional[float] = None + mu_pa_s: Optional[float] = None + nu_m2_s: Optional[float] = None + d_isa: Optional[float] = None + tailwind_m_per_sec: Optional[float] = None diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/__init__.py similarity index 100% rename from skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/__init__.py rename to skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/__init__.py diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/__init__.py similarity index 100% rename from skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/__init__.py rename to skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/__init__.py diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/_openap_aerodynamics_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/_openap_aerodynamics_service.py new file mode 100644 index 0000000000..16e0971e94 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/_openap_aerodynamics_service.py @@ -0,0 +1,76 @@ +import math + +import numpy as np +from openap.drag import Drag +from openap.extra.aero import T0, R, a0, beta, ft, g0, kts + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service.speed_conversion_service import ( + SpeedConversionService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.aerodynamics_settings_interface import ( + AerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.openap_aerodynamics_settings import ( + OpenapAerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, +) + + +class _OpenapAerodynamicsService(AerodynamicsSettings): + performance_model_type = PerformanceModelEnum.OPENAP + + speedconversion_service = SpeedConversionService() + atmosphere_service = AtmosphereService() + + def init_settings(self, model_path: str) -> OpenapAerodynamicsSettings: + drag = Drag(ac=model_path) + + return OpenapAerodynamicsSettings(drag=drag, sref=drag.aircraft["wing"]["area"]) + + def compute_drag_coefficient( + self, + aerodynamics_settings: OpenapAerodynamicsSettings, + aircraft_state: AircraftState, + ) -> float: + cd0 = aerodynamics_settings.drag.polar["clean"]["cd0"] + + sweep = math.radians(aerodynamics_settings.drag.aircraft["wing"]["sweep"]) + tc = aerodynamics_settings.drag.aircraft["wing"]["t/c"] + if tc is None: + tc = 0.11 + + cos_sweep = math.cos(sweep) + mach_crit = ( + 0.87 + - 0.108 / cos_sweep + - 0.1 * aircraft_state.cl / (cos_sweep**2) + - tc / cos_sweep + ) / cos_sweep + + dmach = np.where( + aircraft_state.mach - mach_crit <= 0, 0, aircraft_state.mach - mach_crit + ) + + dCdw = np.where(dmach, 20 * dmach**4, 0) + + return cd0 + dCdw + + def compute_crossover( + self, + aerodynamics_settings: OpenapAerodynamicsSettings, + aircraft_state: AircraftState, + ) -> float: + v_cas = aircraft_state.cas_climb_kts * kts + delta = ((0.2 * (v_cas / a0) ** 2 + 1) ** 3.5 - 1) / ( + (0.2 * aircraft_state.mach_cruise**2 + 1) ** 3.5 - 1 + ) + h = T0 / beta * (delta ** (-1 * R * beta / g0) - 1) + return h / ft diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/_poll_schumann_aerodynamics_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/_poll_schumann_aerodynamics_service.py new file mode 100644 index 0000000000..081ce03b2b --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/_poll_schumann_aerodynamics_service.py @@ -0,0 +1,154 @@ +import math + +import numpy as np + +import skdecide.hub.domain.flight_planning.weather_interpolator.weather_tools.std_atm as std_atm +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service.speed_conversion_service import ( + SpeedConversionService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.aerodynamics_settings_interface import ( + AerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.poll_schumann_aerodynamics_settings import ( + PollSchumannAerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.utils.poll_schumann_utils.aircraft_parameters import ( + crossover_pressure_altitude, + impact_pressure_max_operating_limits, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.utils.poll_schumann_utils.engine_loader import ( + load_aircraft_engine_params, +) + + +class _PollSchumannAerodynamicsService(AerodynamicsSettings): + performance_model_type = PerformanceModelEnum.POLL_SCHUMANN + + speedconversion_service = SpeedConversionService() + + def init_settings(self, model_path: str) -> PollSchumannAerodynamicsSettings: + ac_parameters = load_aircraft_engine_params(model_path) + + return PollSchumannAerodynamicsSettings( + ac_parameters=ac_parameters, sref=ac_parameters["wing_surface_area"] + ) + + def compute_drag_coefficient( + self, + aerodynamics_settings: PollSchumannAerodynamicsSettings, + aircraft_state: AircraftState, + ) -> float: + reynolds = self._compute_reynolds(aerodynamics_settings, aircraft_state) + cf = self._compute_skin_friction_coefficient(reynolds=reynolds) + cd_0 = self._compute_zero_lift_drag_coefficient( + aerodynamics_settings=aerodynamics_settings, cf=cf + ) + e_ls = self._compute_oswald_efficiency_factor( + aerodynamics_settings=aerodynamics_settings, cd_0=cd_0 + ) + cd_wave = self._compute_wave_drag_coefficient( + aerodynamics_settings=aerodynamics_settings, aircraft_state=aircraft_state + ) + + return ( + cd_0 + + cd_wave + + aircraft_state.cl**2 + / ( + math.pi + * e_ls + * aerodynamics_settings.ac_parameters["wing_aspect_ratio"] + ) + ) + + def _compute_reynolds( + self, + aerodynamics_settings: PollSchumannAerodynamicsSettings, + aircraft_state: AircraftState, + ) -> float: + gamma = 1.4 + R = 287.05 + + mu_inf = ( + 1.458e-6 + * (aircraft_state.weather_state.static_temperature_k**1.5) + / (110.4 + aircraft_state.weather_state.static_temperature_k) + ) + return ( + aerodynamics_settings.ac_parameters["wing_surface_area"] ** 0.5 + * aircraft_state.mach + * (aircraft_state.weather_state.static_pressure_pa / mu_inf) + * (gamma / (R * aircraft_state.weather_state.static_temperature_k)) ** 0.5 + ) + + def _compute_skin_friction_coefficient(self, reynolds: float) -> float: + return 0.0269 / (reynolds**0.14) + + def _compute_zero_lift_drag_coefficient( + self, aerodynamics_settings: PollSchumannAerodynamicsSettings, cf: float + ) -> float: + return cf * aerodynamics_settings.ac_parameters["psi_0"] + + def _compute_oswald_efficiency_factor( + self, aerodynamics_settings: PollSchumannAerodynamicsSettings, cd_0: float + ) -> float: + numer = 1.0 + + k1 = 0.80 * (1 - 0.53 * aerodynamics_settings.ac_parameters["cos_sweep"]) * cd_0 + denom = ( + 1.0 + + 0.03 + + aerodynamics_settings.ac_parameters["delta_2"] + + math.pi * k1 * aerodynamics_settings.ac_parameters["wing_aspect_ratio"] + ) + + return numer / denom + + def _compute_wave_drag_coefficient( + self, + aerodynamics_settings: PollSchumannAerodynamicsSettings, + aircraft_state: AircraftState, + ) -> float: + mach = aircraft_state.mach + cl = aircraft_state.cl + + m_cc = aerodynamics_settings.ac_parameters["wing_constant"] - 0.10 * ( + cl / aerodynamics_settings.ac_parameters["cos_sweep"] ** 2 + ) + x = mach * aerodynamics_settings.ac_parameters["cos_sweep"] / m_cc + + c_d_w = np.where( + x < aerodynamics_settings.ac_parameters["j_2"], + 0.0, + aerodynamics_settings.ac_parameters["cos_sweep"] ** 3 + * aerodynamics_settings.ac_parameters["j_1"] + * (x - aerodynamics_settings.ac_parameters["j_2"]) ** 2, + ) + + output = np.where( + x < aerodynamics_settings.ac_parameters["x_ref"], + c_d_w, + c_d_w + + aerodynamics_settings.ac_parameters["j_3"] + * (x - aerodynamics_settings.ac_parameters["x_ref"]) ** 4, + ) + + return output + + def compute_crossover( + self, + aerodynamics_settings: PollSchumannAerodynamicsSettings, + aircraft_state: AircraftState, + ) -> float: + return crossover_pressure_altitude( + max_mach_num=aircraft_state.mach_cruise, + p_i_max=impact_pressure_max_operating_limits( + max_mach_num=aircraft_state.mach_cruise + ), + ) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/aerodynamics_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/aerodynamics_service.py new file mode 100644 index 0000000000..9fe38f3c2f --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/aerodynamics_service.py @@ -0,0 +1,50 @@ +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service._openap_aerodynamics_service import ( + _OpenapAerodynamicsService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service._poll_schumann_aerodynamics_service import ( + _PollSchumannAerodynamicsService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.aerodynamics_settings_interface import ( + AerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) + + +class AerodynamicsService: + """ + Main aerodynamics service class to be handled + """ + + def __init__(self): + self.all_aerodynamics_services = { + PerformanceModelEnum.OPENAP: _OpenapAerodynamicsService(), + PerformanceModelEnum.POLL_SCHUMANN: _PollSchumannAerodynamicsService(), + } + + def init_settings( + self, model_path: str, performance_model_type: PerformanceModelEnum + ) -> AerodynamicsSettings: + return self.all_aerodynamics_services[performance_model_type].init_settings( + model_path + ) + + def compute_drag_coefficient( + self, aerodynamics_settings: AerodynamicsSettings, aircraft_state: AircraftState + ) -> float: + + return self.all_aerodynamics_services[ + aerodynamics_settings.performance_model_type + ].compute_drag_coefficient(aerodynamics_settings, aircraft_state) + + def compute_crossover( + self, aerodynamics_settings: AerodynamicsSettings, aircraft_state: AircraftState + ) -> float: + + return self.all_aerodynamics_services[ + aerodynamics_settings.performance_model_type + ].compute_crossover(aerodynamics_settings, aircraft_state) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/aerodynamics_service_interface.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/aerodynamics_service_interface.py new file mode 100644 index 0000000000..97336dfa7f --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/aerodynamics_service_interface.py @@ -0,0 +1,40 @@ +from abc import ABC, abstractmethod + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.aerodynamics_settings_interface import ( + AerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) + + +class AerodynamicsServiceInterface(ABC): + """ + Interface for Aerodynamics Services + """ + + @property + @abstractmethod + def performance_model_type(self) -> PerformanceModelEnum: + raise NotImplementedError + + @abstractmethod + def init_settings( + self, model_path: str, performance_model_type: PerformanceModelEnum + ) -> AerodynamicsSettings: + raise NotImplementedError + + @abstractmethod + def compute_drag_coefficient( + self, settings: AerodynamicsSettings, aircraft_state: AircraftState + ) -> float: + raise NotImplementedError + + @abstractmethod + def compute_crossover( + self, settings: AerodynamicsSettings, aircraft_state: AircraftState + ) -> float: + raise NotImplementedError diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/speed_conversion_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/speed_conversion_service.py new file mode 100644 index 0000000000..bce52ccc58 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/service/speed_conversion_service.py @@ -0,0 +1,97 @@ +import math + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.weather_state import ( + WeatherState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.isa_atmosphere_service import ( + ISAAtmosphereService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.isa_atmosphere_settings import ( + IsaAtmosphereSettings, +) + + +class SpeedConversionService: + """ + Class used for classical speed conversion (MACH, TAS, CAS) + """ + + _GAMMA = 1.4 + _KT_TO_MS = 1852.0 / 3600.0 + + def convert_speed_to_kt(self, speed_ms: float) -> float: + return speed_ms / self._KT_TO_MS + + def convert_speed_to_ms(self, speed_kt: float) -> float: + return speed_kt * self._KT_TO_MS + + def convert_mach_to_cas_kt(self, mach: float, weather_state: WeatherState) -> float: + """ + Mach to CAS conversion + :param mach: Input mach number + :param weather_state: Current weather state + :return: CAS speed in kt + """ + + # Retrieve the ISA weather state ( + weather_state_isa = ISAAtmosphereService().retrieve_weather_state( + IsaAtmosphereSettings(), AircraftState(zp_ft=0) + ) + + a0 = AtmosphereService().get_sound_celerity( + static_temperature_k=weather_state_isa.static_temperature_k + ) + + cas = 1.0 + (self._GAMMA - 1.0) / 2.0 * mach**2 + cas = ( + weather_state.static_pressure_pa + * math.pow(cas, self._GAMMA / (self._GAMMA - 1.0)) + - weather_state.static_pressure_pa + ) + cas += weather_state_isa.static_pressure_pa + cas = math.pow( + cas / weather_state_isa.static_pressure_pa, + (self._GAMMA - 1.0) / self._GAMMA, + ) + cas += -1 + cas *= 2 / (self._GAMMA - 1.0) * a0**2 + cas = math.sqrt(cas) + + return cas / self._KT_TO_MS + + def convert_cas_to_mach(self, cas_kt: float, weather_state: WeatherState) -> float: + """ + CAS to Mach conversion + :param :cas_kt: Input CAS speed in kt + :param weather_state: Current weather state + :return: MACH number + """ + + # Retrieve the ISA weather state ( + weather_state_isa = ISAAtmosphereService().retrieve_weather_state( + IsaAtmosphereSettings(), AircraftState(zp_ft=0) + ) + + a0 = AtmosphereService().get_sound_celerity( + static_temperature_k=weather_state_isa.static_temperature_k + ) + + mach = 1.0 + (self._GAMMA - 1.0) / 2.0 * (cas_kt * self._KT_TO_MS / a0) ** 2 + mach = ( + weather_state_isa.static_pressure_pa + * math.pow(mach, self._GAMMA / (self._GAMMA - 1.0)) + - weather_state_isa.static_pressure_pa + ) + mach += weather_state.static_pressure_pa + mach *= 1 / weather_state.static_pressure_pa + mach = math.pow(mach, (self._GAMMA - 1.0) / self._GAMMA) - 1 + mach = 2 * mach / (self._GAMMA - 1.0) + mach = math.sqrt(mach) + + return mach diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/utils/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/__init__.py similarity index 100% rename from skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/utils/__init__.py rename to skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/__init__.py diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/aerodynamics_settings_interface.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/aerodynamics_settings_interface.py new file mode 100644 index 0000000000..e31501831c --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/aerodynamics_settings_interface.py @@ -0,0 +1,16 @@ +from abc import ABC +from dataclasses import dataclass + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) + + +@dataclass +class AerodynamicsSettings(ABC): + """ + Dataclass to aggregate all the aerodynamics settings + """ + + performance_model_type: PerformanceModelEnum = None + sref: float = None diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/openap_aerodynamics_settings.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/openap_aerodynamics_settings.py new file mode 100644 index 0000000000..44c1b2caaa --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/openap_aerodynamics_settings.py @@ -0,0 +1,23 @@ +from dataclasses import dataclass + +from openap.drag import Drag + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.aerodynamics_settings_interface import ( + AerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) + + +@dataclass +class OpenapAerodynamicsSettings(AerodynamicsSettings): + """ + Aerodynamics settings for OpenAP models + """ + + drag: Drag = None + sref: float = None + + def __post_init__(self): + self.performance_model_type = PerformanceModelEnum.OPENAP diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/poll_schumann_aerodynamics_settings.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/poll_schumann_aerodynamics_settings.py new file mode 100644 index 0000000000..7d2d81fffa --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/aero/settings/poll_schumann_aerodynamics_settings.py @@ -0,0 +1,22 @@ +from dataclasses import dataclass +from typing import Dict + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.aerodynamics_settings_interface import ( + AerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) + + +@dataclass +class PollSchumannAerodynamicsSettings(AerodynamicsSettings): + """ + Aerodynamics settings for Poll Schumann models + """ + + ac_parameters: Dict[str, float] = None + sref: float = None + + def __post_init__(self): + self.performance_model_type = PerformanceModelEnum.POLL_SCHUMANN diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/performance_model_enum.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/performance_model_enum.py new file mode 100644 index 0000000000..3283aff7ef --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/performance_model_enum.py @@ -0,0 +1,10 @@ +from enum import Enum + + +class PerformanceModelEnum(Enum): + """ + Enum referencing all the performance models + """ + + OPENAP = 1 + POLL_SCHUMANN = 2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/performance_settings.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/performance_settings.py new file mode 100644 index 0000000000..cb43216896 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/performance_settings.py @@ -0,0 +1,18 @@ +from dataclasses import dataclass + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.aerodynamics_settings_interface import ( + AerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.settings.propulsion_settings_interface import ( + PropulsionSettings, +) + + +@dataclass +class PerformanceSettings: + """ + Dataclass to aggregate all the performance settings + """ + + aerodynamics_settings: AerodynamicsSettings + propulsion_settings: PropulsionSettings diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/phase_enum.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/phase_enum.py new file mode 100644 index 0000000000..6446329de1 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/phase_enum.py @@ -0,0 +1,12 @@ +from enum import Enum + + +class PhaseEnum(Enum): + """ + Enum for phase + """ + + TAKE_OFF = 1 + CLIMB = 2 + CRUISE = 3 + DESCENT = 4 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/_openap_propulsion_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/_openap_propulsion_service.py new file mode 100644 index 0000000000..2416cd76e8 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/_openap_propulsion_service.py @@ -0,0 +1,112 @@ +from openap.extra.aero import ft, mach2tas +from openap.fuel import FuelFlow +from openap.thrust import Thrust + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service.speed_conversion_service import ( + SpeedConversionService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service.propulsion_service_interface import ( + PropulsionServiceInterface, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.settings.openap_propulsion_settings import ( + OpenapPropulsionSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, +) + + +class _OpenapPropulsionService(PropulsionServiceInterface): + """ + Implementation of propulsion service for OpenAP models + """ + + performance_model_type = PerformanceModelEnum.OPENAP + + speedconversion_service = SpeedConversionService() + atmosphere_service = AtmosphereService() + + def init_settings(self, model_path: str) -> OpenapPropulsionSettings: + fuel = FuelFlow(ac=model_path) + thrust = Thrust(ac=model_path) + + return OpenapPropulsionSettings( + fuel=fuel, thrust=thrust, sref=fuel.aircraft["wing"]["area"] + ) + + def compute_total_fuel_flow_kg_per_sec( + self, + propulsion_settings: OpenapPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + + tas_meters_per_sec = mach2tas(aircraft_state.mach, aircraft_state.zp_ft * ft) + + try: + vs = ( + (aircraft_state.zp_ft - aircraft_state.zp_ft_memory[-1]) + * 60 + / aircraft_state.time_step + ) + except: + vs = 0 + + return propulsion_settings.fuel.enroute( + mass=aircraft_state.gw_kg, + tas=self.speedconversion_service.convert_speed_to_kt(tas_meters_per_sec), + alt=aircraft_state.zp_ft, + vs=vs, + ) + + def compute_total_net_thrust_n( + self, + propulsion_settings: OpenapPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + tas_meters_per_sec = mach2tas(aircraft_state.mach, aircraft_state.zp_ft * ft) + + if aircraft_state.phase == PhaseEnum.CRUISE: + return propulsion_settings.thrust.cruise( + tas=self.speedconversion_service.convert_speed_to_kt( + tas_meters_per_sec + ), + alt=aircraft_state.zp_ft, + ) + elif aircraft_state.phase == PhaseEnum.CLIMB: + return propulsion_settings.thrust.climb( + tas=self.speedconversion_service.convert_speed_to_kt( + tas_meters_per_sec + ), + alt=aircraft_state.zp_ft, + roc=aircraft_state.rocd_ft_min, + ) + elif aircraft_state.phase == PhaseEnum.DESCENT: + return propulsion_settings.thrust.descent_idle( + tas=self.speedconversion_service.convert_speed_to_kt( + tas_meters_per_sec + ), + alt=aircraft_state.zp_ft, + ) + + def compute_min_rating( + self, + propulsion_settings: OpenapPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + pass + + def compute_max_rating( + self, + propulsion_settings: OpenapPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + pass diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/_poll_schumann_propulsion_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/_poll_schumann_propulsion_service.py new file mode 100644 index 0000000000..988a05b4a0 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/_poll_schumann_propulsion_service.py @@ -0,0 +1,281 @@ +import math + +import numpy as np + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service._poll_schumann_aerodynamics_service import ( + _PollSchumannAerodynamicsService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.settings.poll_schumann_aerodynamics_settings import ( + PollSchumannAerodynamicsSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service.propulsion_service_interface import ( + PropulsionServiceInterface, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.settings.poll_schumann_propulsion_settings import ( + PollSchumannPropulsionSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.utils.poll_schumann_utils.engine_loader import ( + load_aircraft_engine_params, +) + + +class _PollSchumannPropulsionService(PropulsionServiceInterface): + """ + Implementation of propulsion servisce for OpenAP models + """ + + performance_model_type = PerformanceModelEnum.POLL_SCHUMANN + aerodynamics_service = _PollSchumannAerodynamicsService() + + def init_settings(self, model_path: str) -> PollSchumannPropulsionSettings: + ac_parameters = load_aircraft_engine_params(model_path) + + self.aerodynamics_settings = PollSchumannAerodynamicsSettings( + PerformanceModelEnum.POLL_SCHUMANN, ac_parameters=ac_parameters + ) + + return PollSchumannPropulsionSettings( + ac_parameters=ac_parameters, sref=ac_parameters["wing_surface_area"] + ) + + def compute_total_fuel_flow_kg_per_sec( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + ff_min = self._fuel_flow_idle(propulsion_settings, aircraft_state) + ff_max = self._equivalent_fuel_flow_rate_at_cruise( + propulsion_settings, aircraft_state + ) + + ff = self._fuel_mass_flow_rate(propulsion_settings, aircraft_state) + if aircraft_state.phase.name == "DESCENT": + ff_max = 0.3 * propulsion_settings.ac_parameters["ff_max_sls"] + + return np.clip(ff, ff_min, ff_max) + + def compute_total_net_thrust_n( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + theta_rad = math.radians(aircraft_state.gamma_air_deg) + # TODO: Implement acceleration + dv_dt = 0.0 + + cd = self.aerodynamics_service.compute_drag_coefficient( + self.aerodynamics_settings, aircraft_state + ) + + f_thrust = ( + ( + aircraft_state.gw_kg + * 9.807 + * math.cos(theta_rad) + * (cd / aircraft_state.cl) + ) + + (aircraft_state.gw_kg * 9.807 * math.sin(theta_rad)) + + (aircraft_state.gw_kg * dv_dt) + ) + + return max(f_thrust, 0.0) + + def compute_min_rating( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + pass + + def compute_max_rating( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + pass + + def _fuel_flow_idle( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + """ + Calculate minimum fuel mass flow rate at flight idle conditions. + """ + + x = aircraft_state.zp_ft / 10_000.0 + return propulsion_settings.ac_parameters["ff_idle_sls"] * ( + 1.0 - 0.178 * x + 0.0085 * x**2 + ) + + def _equivalent_fuel_flow_rate_at_cruise( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + theta_amb = aircraft_state.weather_state.static_temperature_k / 288.15 + delta_amb = aircraft_state.weather_state.static_pressure_pa / 101325.0 + + denom = (theta_amb**3.8 / delta_amb) * np.exp(0.2 * aircraft_state.mach**2) + denom = np.clip(denom, 1.0, None) + + return propulsion_settings.ac_parameters["ff_max_sls"] / denom + + def _fuel_mass_flow_rate( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + gamma = 1.4 + R = 287.05 + q_fuel = 43e6 + + eta = self.__overall_propulsion_efficiency(propulsion_settings, aircraft_state) + ct = self.__compute_thrust_coefficient(propulsion_settings, aircraft_state) + return ( + (gamma / 2) + * (ct * aircraft_state.mach**3 / eta) + * (gamma * R * aircraft_state.weather_state.static_temperature_k) ** 0.5 + * aircraft_state.weather_state.static_pressure_pa + * propulsion_settings.ac_parameters["wing_surface_area"] + / q_fuel + ) + + def __compute_thrust_coefficient( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + ct = self.___engine_thrust_coefficient(propulsion_settings, aircraft_state) + ct_eta_b = self.___thrust_coefficient_at_max_efficiency( + propulsion_settings, aircraft_state + ) + ct_available = self.___max_available_thrust_coefficient( + propulsion_settings, aircraft_state, ct_eta_b=ct_eta_b + ) + return np.clip(ct, 0, ct_available) + + def ___engine_thrust_coefficient( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + gamma = 1.4 + f_thrust = self.compute_total_net_thrust_n(propulsion_settings, aircraft_state) + + return f_thrust / ( + 0.5 + * gamma + * aircraft_state.weather_state.static_pressure_pa + * aircraft_state.mach**2 + * propulsion_settings.ac_parameters["wing_surface_area"] + ) + + def ___thrust_coefficient_at_max_efficiency( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + m_over_m_des = aircraft_state.mach / propulsion_settings.ac_parameters["m_des"] + h_2 = ( + (1.0 + 0.55 * aircraft_state.mach) + / (1.0 + 0.55 * propulsion_settings.ac_parameters["m_des"]) + ) / (m_over_m_des**2) + + return h_2 * propulsion_settings.ac_parameters["c_t_des"] + + def ___max_available_thrust_coefficient( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ct_eta_b: float, + ) -> float: + tr_max = self.___normalised_max_throttle_parameter( + propulsion_settings, aircraft_state + ) + + ct_max_over_ct_eta_b = 1.0 + 2.5 * (tr_max - 1.0) + return ct_max_over_ct_eta_b * ct_eta_b * (1.0 + 0.05) + + def ___normalised_max_throttle_parameter( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + return ( + propulsion_settings.ac_parameters["tet_mcc"] + / aircraft_state.weather_state.static_temperature_k + ) / ( + propulsion_settings.ac_parameters["tr_ec"] + * ( + 1.0 + - 0.53 + * (aircraft_state.mach - propulsion_settings.ac_parameters["m_ec"]) ** 2 + ) + * (1.0 + 0.2 * aircraft_state.mach**2) + ) + + def __overall_propulsion_efficiency( + self, + propulsion_settings: PollSchumannPropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + ct_eta_b = self.___thrust_coefficient_at_max_efficiency( + propulsion_settings, aircraft_state + ) + + # ct = np.clip(ct, 0, ct_available) + ct = self.__compute_thrust_coefficient(propulsion_settings, aircraft_state) + eta_over_eta_b_min = 0.5 + + eta_over_eta_b = self.____propulsion_efficiency_over_max_propulsion_efficiency( + aircraft_state, ct, ct_eta_b + ) + + if eta_over_eta_b_min is not None: + eta_over_eta_b.clip(min=eta_over_eta_b_min, out=eta_over_eta_b) + + eta_b = ( + propulsion_settings.ac_parameters["eta_1"] + * aircraft_state.mach ** propulsion_settings.ac_parameters["eta_2"] + ) + + return eta_over_eta_b * eta_b + + def ____propulsion_efficiency_over_max_propulsion_efficiency( + self, aircraft_state: AircraftState, ct: float, ct_eta_b: float + ) -> float: + ct_over_c_t_eta_b = ct / ct_eta_b + + sigma = np.where( + aircraft_state.mach < 0.4, 1.3 * (0.4 - aircraft_state.mach), 0.0 + ) + + eta_over_eta_b_low = ( + 10.0 + * (1.0 + 0.8 * (sigma - 0.43) - 0.6027 * sigma * 0.43) + * ct_over_c_t_eta_b + + 33.3333 + * (-1.0 - 0.97 * (sigma - 0.43) + 0.8281 * sigma * 0.43) + * (ct_over_c_t_eta_b**2) + + 37.037 + * (1.0 + (sigma - 0.43) - 0.9163 * sigma * 0.43) + * (ct_over_c_t_eta_b**3) + ) + eta_over_eta_b_hi = ( + (1.0 + (sigma - 0.43) - sigma * 0.43) + + (4.0 * sigma * 0.43 - 2.0 * (sigma - 0.43)) * ct_over_c_t_eta_b + + ((sigma - 0.43) - 6 * sigma * 0.43) * (ct_over_c_t_eta_b**2) + + 4.0 * sigma * 0.43 * (ct_over_c_t_eta_b**3) + - sigma * 0.43 * (ct_over_c_t_eta_b**4) + ) + return np.where(ct_over_c_t_eta_b < 0.3, eta_over_eta_b_low, eta_over_eta_b_hi) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/propulsion_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/propulsion_service.py new file mode 100644 index 0000000000..2c246c7c44 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/propulsion_service.py @@ -0,0 +1,136 @@ +from copy import deepcopy + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service._openap_propulsion_service import ( + _OpenapPropulsionService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service._poll_schumann_propulsion_service import ( + _PollSchumannPropulsionService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.settings.propulsion_settings_interface import ( + PropulsionSettings, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, +) + + +class PropulsionService: + """ + Main propulsion service class to be handled + """ + + def __init__(self): + self.all_propulsion_services = { + PerformanceModelEnum.OPENAP: _OpenapPropulsionService(), + PerformanceModelEnum.POLL_SCHUMANN: _PollSchumannPropulsionService(), + } + + def init_settings( + self, model_path: str, performance_model_type: PerformanceModelEnum + ) -> PropulsionSettings: + return self.all_propulsion_services[performance_model_type].init_settings( + model_path + ) + + def compute_total_net_thrust_n( + self, + propulsion_settings: PropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + return self.all_propulsion_services[ + propulsion_settings.performance_model_type + ].compute_total_net_thrust_n(propulsion_settings, aircraft_state) + + def compute_total_fuel_flow_kg_per_sec( + self, + propulsion_settings: PropulsionSettings, + aircraft_state: AircraftState, + ) -> float: + return self.all_propulsion_services[ + propulsion_settings.performance_model_type + ].compute_total_fuel_flow_kg_per_sec(propulsion_settings, aircraft_state) + + def compute_min_rating( + self, + propulsion_settings: PropulsionSettings, + aircraft_state: AircraftState, + ) -> RatingEnum: + return self.all_propulsion_services[ + propulsion_settings.performance_model_type + ].compute_min_rating(propulsion_settings, aircraft_state) + + def compute_max_rating( + self, + propulsion_settings: PropulsionSettings, + aircraft_state: AircraftState, + ) -> RatingEnum: + return self.all_propulsion_services[ + propulsion_settings.performance_model_type + ].compute_max_rating(propulsion_settings, aircraft_state) + + def compute_tsp_from_thrust( + self, + propulsion_settings: PropulsionSettings, + aircraft_state: AircraftState, + target_thrust_n: float, + ) -> float: + aircraft_state_copy = deepcopy(aircraft_state) + if aircraft_state.is_one_eo: + aircraft_state_copy.rating_level = RatingEnum.MCN + elif aircraft_state.phase == PhaseEnum.TAKE_OFF: + aircraft_state_copy.rating_level = RatingEnum.T0N + else: + aircraft_state_copy.rating_level = RatingEnum.MCL + + tsp_max = self.compute_max_rating( + propulsion_settings=propulsion_settings, aircraft_state=aircraft_state_copy + ) + aircraft_state_copy.tsp = tsp_max + thrust_max = self.compute_total_net_thrust_n( + propulsion_settings=propulsion_settings, aircraft_state=aircraft_state_copy + ) + + if target_thrust_n > thrust_max: + raise Exception("Target thrust exceeds min") + + tsp_min = self.compute_min_rating( + propulsion_settings=propulsion_settings, aircraft_state=aircraft_state_copy + ) + aircraft_state_copy.tsp = tsp_min + thrust_min = self.compute_total_net_thrust_n( + propulsion_settings=propulsion_settings, aircraft_state=aircraft_state_copy + ) + + if target_thrust_n < thrust_min: + raise Exception("Target thrust exceeds min") + + computed_thrust_n = 0 + trial_tsp = tsp_min + (tsp_max - tsp_min) / (thrust_max - thrust_min) * ( + target_thrust_n - thrust_min + ) + while abs(target_thrust_n - computed_thrust_n) > 0.5: + aircraft_state_copy.tsp = trial_tsp + computed_thrust_n = self.compute_total_net_thrust_n( + propulsion_settings=propulsion_settings, + aircraft_state=aircraft_state_copy, + ) + if thrust_min < computed_thrust_n < target_thrust_n: + tsp_min = trial_tsp + thrust_min = computed_thrust_n + elif thrust_max > computed_thrust_n > target_thrust_n: + tsp_max = trial_tsp + thrust_max = computed_thrust_n + + trial_tsp = tsp_min + (tsp_max - tsp_min) / (thrust_max - thrust_min) * ( + target_thrust_n - thrust_min + ) + return trial_tsp diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/propulsion_service_interface.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/propulsion_service_interface.py new file mode 100644 index 0000000000..4619948d7b --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/service/propulsion_service_interface.py @@ -0,0 +1,52 @@ +from abc import ABC, abstractmethod + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.settings.propulsion_settings_interface import ( + PropulsionSettings, +) + + +class PropulsionServiceInterface(ABC): + """ + Interface defining propulsion services + """ + + @property + @abstractmethod + def performance_model_type(self) -> PerformanceModelEnum: + raise NotImplementedError + + @abstractmethod + def init_settings( + self, model_path: str, performance_model_type: PerformanceModelEnum + ) -> PropulsionSettings: + raise NotImplementedError + + @abstractmethod + def compute_total_net_thrust_n( + self, propulsion_settings: PropulsionSettings, aircraft_state: AircraftState + ) -> float: + raise NotImplementedError + + @abstractmethod + def compute_total_fuel_flow_kg_per_sec( + self, propulsion_settings: PropulsionSettings, aircraft_state: AircraftState + ) -> float: + raise NotImplementedError + + @abstractmethod + def compute_max_rating( + self, propulsion_settings: PropulsionSettings, aircraft_state: AircraftState + ) -> float: + raise NotImplementedError + + @abstractmethod + def compute_min_rating( + self, propulsion_settings: PropulsionSettings, aircraft_state: AircraftState + ) -> float: + raise NotImplementedError diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/openap_propulsion_settings.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/openap_propulsion_settings.py new file mode 100644 index 0000000000..008aa0fc72 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/openap_propulsion_settings.py @@ -0,0 +1,24 @@ +from dataclasses import dataclass + +from openap.fuel import FuelFlow +from openap.thrust import Thrust + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.settings.propulsion_settings_interface import ( + PropulsionSettings, +) + + +@dataclass +class OpenapPropulsionSettings(PropulsionSettings): + """ + Propulsion settings for OpenAP models + """ + + fuel: FuelFlow = None + thrust: Thrust = None + + def __post_init__(self): + self.performance_model_type = PerformanceModelEnum.OPENAP diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/poll_schumann_propulsion_settings.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/poll_schumann_propulsion_settings.py new file mode 100644 index 0000000000..e58ef8a7a7 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/poll_schumann_propulsion_settings.py @@ -0,0 +1,22 @@ +from dataclasses import dataclass +from typing import Dict + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.settings.propulsion_settings_interface import ( + PropulsionSettings, +) + + +@dataclass +class PollSchumannPropulsionSettings(PropulsionSettings): + """ + Propulsion settings for OpenAP models + """ + + ac_parameters: Dict[str, float] = None + sref: float = None + + def __post_init__(self): + self.performance_model_type = PerformanceModelEnum.POLL_SCHUMANN diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/propulsion_settings_interface.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/propulsion_settings_interface.py new file mode 100644 index 0000000000..52abc4df1e --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/propulsion/settings/propulsion_settings_interface.py @@ -0,0 +1,17 @@ +from abc import ABC +from dataclasses import dataclass + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, +) + + +@dataclass +class PropulsionSettings(ABC): + """ + Abstract dataclass for propulsion service settings + """ + + performance_model_type: PerformanceModelEnum = None + nb_engines: int = None + sref: float = None diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/performance/rating_enum.py b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/rating_enum.py new file mode 100644 index 0000000000..963a7d156b --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/performance/rating_enum.py @@ -0,0 +1,16 @@ +from enum import Enum + +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, +) + + +class RatingEnum(Enum): + """ + Enum for phase + """ + + TO = {"phase": PhaseEnum.TAKE_OFF} + MCL = {"phase": PhaseEnum.CLIMB} + CR = {"phase": PhaseEnum.CRUISE} + IDLE = {"phase": None} diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/data/aircraft_engine_params.csv b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/data/aircraft_engine_params.csv deleted file mode 100644 index d960a5651a..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/data/aircraft_engine_params.csv +++ /dev/null @@ -1,63 +0,0 @@ -ICAO,Manufacturer,Type,Year_of_first_flight,n_engine,winglets,WV,MTOM_kg,MLM_kg,MZFM_kg,OEM_i_kg,MPM_i_kg,MZFM_MTOM,OEM_i_MTOM,MPM_i_MTOM,Sref_m2,span_m,bf_m,delta_2,cos_sweep,AR,psi_0,Xo,wing_constant,j_2,j_1,CL_do,etaL_D_do,nominal_F00_ISA_kn,mf_max_T_O_SLS_kg_s,mf_idle_SLS_kg_s,M_des,CT_des,eta_1,eta_2,Mec,Tec,FL_max,MMO,pi_max_pa,pinf_co_pa -A30B,Airbus,A300B4-200,1973,2,no,6,165000,134000,124000,88505,35495,0.752,0.536,0.215,260,44.83,5.64,0.032,0.8829,7.73,8.774,1.02,0.72,0.868,0.073,0.535,4.299,466.2,4.8,0.4,0.753,0.0339,0.318,0.545,0.674,4.945,390,0.82,20883,37618 -A306,Airbus,A300B4-600R,1983,2,no,0,170500,140000,130000,86220,43780,0.762,0.506,0.257,260,44.84,5.64,0.032,0.8829,7.73,7.804,1.015,0.721,0.871,0.076,0.519,5.328,524.9,5.08,0.42,0.753,0.0307,0.366,0.538,0.683,4.965,410,0.82,20883,37618 -A310,Airbus,A310-200,1982,2,no,8,138600,122000,112000,79207,32793,0.808,0.571,0.237,219,43.89,5.64,0.033,0.8829,8.8,8.376,1.014,0.744,0.869,0.073,0.558,5.703,443.5,4.29,0.38,0.772,0.0329,0.387,0.536,0.686,5.195,410,0.84,21866,37237 -A313,Airbus,A310-300,1982,2,no,0,150000,123000,113000,77397,35603,0.753,0.516,0.237,219,43.89,5.64,0.033,0.8829,8.8,8.213,1.01,0.746,0.869,0.074,0.55,5.656,480.3,4.51,0.39,0.772,0.0319,0.376,0.537,0.684,4.926,410,0.84,21866,37237 -A318,Airbus,A318-100,2002,2,no,5,68000,57500,53000,38818,14182,0.779,0.571,0.209,122.4,34.1,3.95,0.027,0.9063,9.5,7.471,0.995,0.754,0.871,0.075,0.564,5.332,199.3,2.06,0.21,0.753,0.0309,0.34,0.532,0.689,6.117,410,0.82,20883,37618 -A319,Airbus,A319-100,1995,2,no,6,73500,62500,58500,39725,18775,0.796,0.54,0.255,122.4,34.1,3.95,0.027,0.9063,9.5,7.701,0.995,0.755,0.871,0.075,0.569,5.062,212.5,1.99,0.21,0.753,0.0316,0.326,0.522,0.701,5.877,410,0.82,20883,37618 -A320,Airbus,A320-200,1987,2,no,0,73500,64500,60500,41244,19256,0.823,0.561,0.262,122.4,34.1,3.95,0.027,0.9063,9.5,8.395,1.007,0.75,0.869,0.073,0.59,5.053,224.6,2.15,0.22,0.753,0.0347,0.344,0.522,0.701,5.706,410,0.82,20883,37618 -A321,Airbus,A321-100,1993,2,no,8,89000,75500,71500,46856,24644,0.803,0.526,0.277,122.4,34.15,3.95,0.027,0.9063,9.53,8.631,1.009,0.748,0.869,0.073,0.591,5.019,269.3,2.69,0.25,0.753,0.0347,0.342,0.528,0.694,5.433,391,0.82,20883,37618 -A332,Airbus,A330-200,1992,2,no,52,233000,182000,170000,116840,53160,0.73,0.501,0.228,361.6,60.3,5.64,0.017,0.8686,10.06,6.692,0.987,0.762,0.872,0.076,0.528,6.899,609.5,5.94,0.49,0.786,0.025,0.371,0.535,0.686,5.404,410,0.86,22875,36865 -A333,Airbus,A330-300,1992,2,no,52,233000,187000,175000,120132,54868,0.751,0.516,0.235,361.6,60.3,5.64,0.017,0.8686,10.06,6.9,0.99,0.761,0.872,0.076,0.535,6.571,604.5,5.84,0.49,0.786,0.0258,0.36,0.534,0.687,5.511,410,0.86,22875,36865 -A338,Airbus,A330-800,2018,2,no,800,242000,186000,174000,132000,42000,0.719,0.545,0.174,374,64.00,5.64,0.016,0.8660,10.95,6.213,0.959,0.781,0.874,0.078,0.530,8.292,656,4.96,0.48,0.786,0.0229,0.399,0.445,0.763,6.243,414.5,0.86,22875,36865 -A339,Airbus,A330-900,2017,2,no,900,242000,191000,181000,135000,46000,0.748,0.558,0.190,374,64.00,5.64,0.016,0.8660,10.95,6.463,0.962,0.779,0.873,0.077,0.539,8.129,656,4.96,0.48,0.786,0.0239,0.401,0.445,0.763,6.229,414.5,0.86,22875,36865 -A342,Airbus,A340-200,1991,4,no,1,257000,181000,169000,125242,43758,0.658,0.487,0.17,361.6,60.3,5.64,0.017,0.8686,10.06,7.077,0.982,0.767,0.872,0.076,0.538,6.741,579.5,5.52,0.48,0.786,0.0261,0.368,0.498,0.725,5.778,415,0.86,22875,36865 -A343,Airbus,A340-300,1991,4,no,1,257000,186000,174000,125242,48758,0.677,0.487,0.19,361.6,60.3,5.64,0.017,0.8686,10.06,7.384,0.987,0.765,0.871,0.075,0.548,6.483,579.5,5.52,0.48,0.786,0.0273,0.363,0.498,0.725,5.891,415,0.86,22875,36865 -A345,Airbus,A340-500,2002,4,no,1,372000,243000,230000,170370,59630,0.618,0.458,0.16,437.3,63.45,5.64,0.016,0.8563,9.21,6.731,0.985,0.762,0.874,0.078,0.512,6.994,1036.4,8.79,0.92,0.796,0.0245,0.374,0.479,0.74,5.022,414.5,0.86,22875,36865 -A346,Airbus,A340-600,2001,4,no,1,368000,259000,245000,176364,68636,0.666,0.479,0.187,437.3,63.45,5.64,0.016,0.8563,9.21,7.057,0.991,0.759,0.873,0.077,0.523,7.091,1050.8,8.96,0.92,0.796,0.0258,0.39,0.479,0.74,5.103,415,0.86,22875,36865 -A359,Airbus,A350-900,2013,2,no,9,275000,207000,195700,146600,49100,0.712,0.533,0.179,445,64.75,5.96,0.017,0.848,9.42,6.14,0.962,0.791,0.874,0.078,0.493,8.601,758,5.64,0.58,0.82,0.0225,0.428,0.445,0.764,6.119,431,0.89,24441,36319 -A35K,Airbus,A350-1000,2016,2,yes,2,319000,236000,223000,155000,67300,0.699,0.486,0.211,465.0,64.75,5.96,0.017,0.8480,9.02,6.183,0.967,0.789,0.874,0.078,0.500,8.074,873,7.01,0.65,0.820,0.0223,0.396,0.467,0.749,6.170,414.5,0.89,24441,36319 -A388,Airbus,A380-800,2005,4,no,2,569000,391000,366000,275000,91000,0.643,0.483,0.16,845,79.8,7.142,0.016,0.866,7.54,6.132,0.967,0.794,0.876,0.082,0.446,7.478,1350.7,10.57,1.07,0.82,0.0216,0.398,0.47,0.747,5.981,431,0.89,24441,36319 -B712,Boeing,B717-200,1998,2,no,HGW,54884,49898,45586,31071,14515,0.831,0.566,0.264,92.75,28.4,3.4,0.029,0.9063,8.7,8.722,1.02,0.692,0.867,0.072,0.579,4.569,179,1.82,0.2,0.7,0.0365,0.349,0.545,0.675,5.626,371,0.82,20883,37618 -B732,Boeing,B737-200,1967,2,no,5,52390,46720,43092,27125,15967,0.823,0.518,0.305,99,28.35,3.76,0.035,0.9063,8.12,8.406,1.04,0.678,0.867,0.073,0.556,3.424,137.1,2.3,0.28,0.7,0.0358,0.276,0.627,0.557,4.631,370,0.82,20883,37618 -B733,Boeing,B737-300,1984,2,no,3,61236,51710,48308,32904,15404,0.789,0.537,0.252,102,28.9,3.76,0.034,0.9063,8.19,9.2,1.024,0.715,0.867,0.072,0.578,3.942,187.3,2.01,0.23,0.729,0.0384,0.311,0.534,0.688,5.642,390,0.82,20883,37618 -B734,Boeing,B737-400,1988,2,no,6,68039,56246,53070,33643,19427,0.78,0.494,0.286,102.5,28.9,3.76,0.034,0.9063,8.15,8.898,1.017,0.718,0.868,0.073,0.565,4.129,190.1,2.05,0.24,0.729,0.0365,0.316,0.534,0.688,5.65,370,0.82,20883,37618 -B735,Boeing,B737-500,1989,2,no,3,60555,49895,46494,31312,15182,0.768,0.517,0.251,103.7,28.9,3.76,0.034,0.9063,8.05,8.335,1.009,0.721,0.87,0.074,0.55,4.109,187.3,2.01,0.23,0.729,0.0346,0.306,0.534,0.688,5.621,370,0.82,20883,37618 -B736,Boeing,B737-600,1997,2,no,3,65544,55112,51936,36378,15558,0.792,0.555,0.237,124.6,34.3,3.76,0.024,0.9063,9.44,7.425,0.994,0.759,0.871,0.075,0.564,5.03,190,1.88,0.2,0.758,0.031,0.32,0.527,0.695,6.209,410,0.82,20883,37618 -B737,Boeing,B737-700,1997,2,no,3,70080,58604,55202,37648,17554,0.788,0.537,0.25,124.6,34.3,3.76,0.024,0.9063,9.44,7.611,0.997,0.758,0.871,0.075,0.567,5.086,214.1,2.18,0.21,0.758,0.0315,0.327,0.531,0.691,5.936,410,0.82,20883,37618 -B738,Boeing,B737-800,1997,2,no,3,79016,66361,61689,41413,20276,0.781,0.524,0.257,124.6,34.3,3.76,0.024,0.9063,9.44,8.182,1.005,0.754,0.87,0.074,0.581,4.999,233.4,2.43,0.22,0.758,0.0335,0.334,0.533,0.688,5.86,410,0.82,20883,37618 -B739,Boeing,B737-900ER,2006,2,no,2,85139,71350,67721,44676,23045,0.795,0.525,0.271,124.6,34.32,3.76,0.024,0.9063,9.45,7.928,1,0.756,0.87,0.075,0.571,5.022,233.4,2.43,0.22,0.758,0.032,0.326,0.533,0.688,5.947,410,0.82,20883,37618 -B37M,Boeing,B737 MAX 7,2018,2,yes,,80285,66043,62913,42033,20880,0.784,0.524,0.260,121.9,33.26,3.76,0.026,0.9063,9.08,7.585,0.976,0.779,0.872,0.076,0.573,6.239,248,2.00,0.19,0.763,0.0305,0.376,0.458,0.755,6.281,410.0,0.82,20883,37618 -B38M,Boeing,B737 MAX 8,2016,2,yes,,82644,69308,65952,45072,20880,0.798,0.545,0.253,121.9,33.26,3.76,0.026,0.9063,9.08,7.869,0.979,0.777,0.872,0.075,0.581,6.153,248,2.00,0.19,0.763,0.0316,0.379,0.458,0.755,6.253,410.0,0.82,20883,37618 -B39M,Boeing,B737 MAX 9,2017,2,yes,,88314,74343,70987,50107,20880,0.804,0.567,0.236,121.9,33.26,3.76,0.026,0.9063,9.08,8.058,0.994,0.769,0.872,0.076,0.599,6.184,248,2.00,0.19,0.763,0.0331,0.387,0.458,0.755,6.234,410.0,0.82,20883,37618 -B742,Boeing,B747-200B,1971,4,no,4,371900,285700,238780,175970,62810,0.642,0.473,0.169,511,59.64,6.5,0.024,0.7934,6.96,7.019,1.038,0.692,0.868,0.074,0.458,5.305,882.3,9.11,0.9,0.81,0.0259,0.336,0.541,0.679,4.622,450,0.9,24977,36141 -B743,Boeing,B747-300,1980,4,no,0,377800,260320,242630,174820,67810,0.642,0.463,0.179,511,59.64,6.5,0.024,0.7826,6.96,6.882,1.042,0.683,0.867,0.073,0.453,5.367,898.8,9.19,0.91,0.81,0.0253,0.337,0.542,0.679,4.992,450,0.9,24977,36141 -B744,Boeing,B747-400,1985,4,no,5,396894,285764,246075,178756,67319,0.62,0.45,0.17,547,64.44,6.5,0.02,0.7934,7.59,6.688,1.029,0.698,0.869,0.074,0.465,6.044,1021.3,9.79,0.82,0.81,0.0245,0.357,0.537,0.684,4.991,450,0.92,26070,35788 -B748,Boeing,B747-8F,2010,4,no,1,442253,345184,328854,197131,131723,0.744,0.446,0.298,594,68.4,6.5,0.018,0.7934,7.88,6.249,0.998,0.732,0.872,0.077,0.458,6.983,1199.2,9.81,0.87,0.83,0.0224,0.374,0.468,0.749,5.602,421,0.9,24977,36141 -B752,Boeing,B757-200,1982,2,no,4,113400,89800,83450,62100,21350,0.736,0.548,0.188,189,38.06,3.76,0.02,0.9063,7.66,7.102,0.986,0.77,0.874,0.078,0.496,5.469,358,3.64,0.35,0.772,0.0279,0.354,0.542,0.678,4.94,420,0.86,22875,36865 -B753,Boeing,B757-300,1998,2,no,2,122470,101610,95270,64580,30690,0.778,0.527,0.251,189,38.06,3.76,0.02,0.9063,7.66,7.594,0.992,0.767,0.873,0.077,0.509,5.106,358,3.64,0.35,0.772,0.0297,0.343,0.542,0.678,5.594,430,0.86,22875,36865 -B762,Boeing,B767-200ER,1984,2,no,6,179169,136078,117934,82377,35557,0.658,0.46,0.198,283.3,47.57,5.03,0.022,0.8526,7.99,6.963,0.999,0.726,0.871,0.076,0.488,5.848,504.4,4.86,0.41,0.772,0.0263,0.362,0.538,0.683,5.042,430,0.86,22875,36865 -B763,Boeing,B767-300,1986,2,no,2,158758,136078,126299,86069,40230,0.796,0.542,0.253,283.3,47.57,5.03,0.022,0.8526,7.99,6.297,0.989,0.73,0.873,0.077,0.47,6.027,504.4,4.86,0.41,0.772,0.024,0.355,0.538,0.683,4.895,431,0.86,22875,36865 -B764,Boeing,B767-400ER,1999,2,no,1,204116,158757,149685,103147,46538,0.733,0.505,0.228,283.3,51.92,5.03,0.019,0.8526,9.52,7.202,1.016,0.723,0.87,0.075,0.544,6.226,512.8,4.86,0.4,0.772,0.0278,0.366,0.534,0.688,5.607,450,0.86,22875,36865 -B77L,Boeing,B777-200LR,2005,2,no,1,347450,223168,209107,145150,63957,0.602,0.418,0.184,427.8,64.8,6.2,0.018,0.8517,9.82,6.504,0.986,0.772,0.873,0.078,0.519,7.397,1006.5,9.01,0.75,0.811,0.0239,0.377,0.486,0.735,5.078,431,0.89,24441,36319 -B772,Boeing,B777-200,1994,2,no,6,286900,206350,195030,135600,59430,0.68,0.473,0.207,427.8,60.93,6.2,0.021,0.8517,8.68,6.462,0.976,0.774,0.873,0.078,0.484,6.827,781.2,6.89,0.57,0.811,0.0235,0.368,0.49,0.731,5.441,431,0.89,24441,36319 -B77W,Boeing,B777-300ER,1994,2,no,1,351530,251290,237673,167820,69853,0.676,0.477,0.199,427.8,64.8,6.2,0.018,0.8517,9.82,7.159,0.998,0.767,0.872,0.076,0.542,7.171,1027.8,9.38,0.76,0.811,0.0264,0.388,0.489,0.732,5.045,431,0.89,24441,36319 -B773,Boeing,B777-300,1997,2,no,4,299370,237680,224530,159570,64960,0.75,0.533,0.217,427.8,60.93,6.2,0.021,0.8517,8.68,7.069,0.989,0.767,0.872,0.076,0.503,6.693,744.8,6.87,0.56,0.811,0.0258,0.382,0.507,0.716,5.802,431,0.89,24441,36319 -B788,Boeing,B787-8,2009,2,no,1,227930,172365,161025,117707,43318,0.706,0.516,0.19,360,60.12,5.77,0.018,0.8462,10.04,6.383,0.968,0.784,0.873,0.077,0.508,7.98,633,4.82,0.45,0.815,0.0238,0.409,0.445,0.764,6.06,431,0.9,24977,36141 -B789,Boeing,B787-9,2013,2,no,1,254011,192777,181437,128850,52587,0.714,0.507,0.207,360,60.12,5.77,0.018,0.8462,10.04,6.478,0.968,0.784,0.873,0.077,0.509,7.938,633,4.82,0.45,0.815,0.0239,0.408,0.445,0.764,6.126,431,0.9,24977,36141 -B78X,Boeing,B787-10,2017,2,no,,254011,201848,192776,135500,57276,0.759,0.533,0.225,377.0,60.12,5.77,0.018,0.8462,9.59,6.607,0.971,0.782,0.873,0.077,0.513,7.635,689,5.33,0.47,0.815,0.0243,0.397,0.448,0.762,6.185,411.0,0.9,24977,36141 -BCS1,Airbus,A220-100,2013,2,yes,,60781,51029,48987,35222,13765,0.806,0.579,0.226,115.0,32.50,3.51,0.023,0.8988,9.18,7.341,0.961,0.776,0.873,0.076,0.576,6.222,201,1.44,0.15,0.754,0.0304,0.367,0.393,0.785,6.227,410.0,0.82,20883,37618 -BCS3,Airbus,A220-300,2013,2,yes,,70896,61008,58060,37082,20978,0.819,0.523,0.296,115.0,32.50,3.51,0.023,0.8988,9.18,7.724,0.964,0.775,0.872,0.075,0.585,6.190,201,1.44,0.15,0.754,0.0316,0.373,0.393,0.785,6.258,410.0,0.82,20883,37618 -E135,Embraer,EMB-135LR,1995,2,no,0,20000,18500,15999,11500,4499,0.8,0.575,0.225,51.18,20.04,2.25,0.025,0.9239,7.85,8.018,1.012,0.709,0.869,0.074,0.562,3.429,66.1,0.72,0.09,0.704,0.037,0.273,0.541,0.68,6.609,370,0.78,18996,38408 -E145,Embraer,EMB-145LR,1995,2,no,0,22000,19300,17900,12114,5786,0.814,0.551,0.263,51.18,20.04,2.25,0.025,0.9239,7.85,8.38,1.018,0.706,0.868,0.073,0.57,3.686,74.3,0.82,0.1,0.704,0.0382,0.299,0.543,0.678,6.404,370,0.78,18996,38408 -E170,Embraer,EMB-170LR,2002,2,no,0,37200,32800,29800,20700,9100,0.801,0.556,0.245,72.72,25.3,3.15,0.031,0.9239,8.8,8.144,1.005,0.742,0.87,0.074,0.579,4.094,120.1,1.32,0.13,0.733,0.0355,0.296,0.533,0.688,6.314,410,0.82,20883,37618 -E195,Embraer,EMB-195STD,2004,2,no,0,48790,45000,42500,28700,13800,0.871,0.588,0.283,92.53,27.73,3,0.023,0.9239,8.31,8.034,1.001,0.765,0.871,0.075,0.56,4.2,162,1.67,0.17,0.758,0.0344,0.299,0.534,0.687,6.264,410,0.82,20883,37618 -MD82,Boeing,MD-82,1981,2,no,0,67812,58967,55338,35369,19969,0.816,0.522,0.294,112.3,32.85,3.35,0.021,0.9239,9.61,8.956,1.035,0.715,0.866,0.072,0.612,4.023,185.5,2.62,0.27,0.72,0.0376,0.302,0.611,0.583,5.328,370,0.84,21866,37237 -MD83,Boeing,MD-83,1984,2,no,0,72575,63276,55338,36145,19193,0.762,0.498,0.264,112.3,32.85,3.35,0.021,0.9239,9.61,8.856,1.031,0.716,0.867,0.072,0.607,3.903,193,2.71,0.27,0.72,0.0368,0.289,0.611,0.582,5.312,370,0.84,21866,37237 -GLF5,Gulfstream,G-550,1995,2,no,0,41277,34155,23587,22882,705,0.571,0.554,0.017,105.56,28.5,2.5,0.015,0.9063,7.69,6.702,0.995,0.765,0.873,0.077,0.508,5.514,137.5,1.49,0.17,0.772,0.0293,0.368,0.558,0.659,6.331,510,0.885,24176,36409 -CRJ9,Bombardier,CRJ-9,1999,2,no,0,38329,34065,32092,21350,10742,0.837,0.557,0.28,76.15,23.25,2.69,0.027,0.8988,7.1,7.351,1.001,0.739,0.872,0.076,0.504,4.13,120.9,1.33,0.13,0.753,0.0316,0.301,0.533,0.688,6.159,410,0.85,22367,37050 -DC93,Boeing,DC-9-32,1967,2,no,0,48988,44906,39463,25789,13674,0.806,0.526,0.279,93,28.44,3.35,0.028,0.9135,8.7,7.952,1.03,0.719,0.868,0.074,0.565,3.289,130.5,2.13,0.27,0.733,0.0343,0.242,0.627,0.556,4.673,370,0.84,21866,37237 -RJ1H,BAESystems,RJ-100,1987,4,no,0,44225,40142,37421,25640,11781,0.846,0.58,0.266,77.3,26.34,3.5,0.035,0.9659,8.98,9.769,1.008,0.689,0.869,0.073,0.621,3.251,124,1.43,0.18,0.65,0.0414,0.273,0.534,0.688,5.79,350,0.734,16955,39369 -B722,Boeing,727-200,1967,3,no,0,83820,70100,63560,44390,19170,0.758,0.53,0.229,157.9,32.92,3.76,0.026,0.848,6.86,7.902,1.058,0.687,0.865,0.072,0.499,3.423,203.8,3.41,0.42,0.77,0.0328,0.265,0.627,0.557,4.896,420,0.9,24977,36141 -A20N,Airbus,A320-NEO,2014,2,yes,54,79000,66300,62800,43600,19200,0.795,0.552,0.243,122.4,35.1,3.59,0.021,0.9063,10.07,7.531,0.956,0.786,0.873,0.076,0.598,6.521,255.8,1.77,0.18,0.753,0.0303,0.368,0.385,0.787,6.316,410,0.82,20883,37618 -A21N,Airbus,A321-NEO,2016,2,yes,52,93500,77300,73000,48000,25000,0.781,0.513,0.267,122.4,35.27,3.95,0.025,0.9063,10.16,8.035,0.96,0.785,0.872,0.075,0.61,5.857,255.8,1.77,0.18,0.753,0.0316,0.339,0.385,0.787,6.469,391,0.82,20883,37618 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/atmospheric_parameters.py b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/atmospheric_parameters.py deleted file mode 100644 index 7b5daa166e..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/atmospheric_parameters.py +++ /dev/null @@ -1,548 +0,0 @@ -# math and data -import math - -import numpy as np - -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - constants, - jet, -) -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - operational_limits as op_lim, -) - -# ---------------------- -# Atmospheric parameters -# ---------------------- - - -def reynolds_number( - wing_span: float, - wing_aspect_ratio: float, - mach_num: float, - air_temperature: float, - air_pressure: float, -) -> float: - """Calculate the Reynolds number. - - # Parameters - wing_span (float): - Wing surface area, [:math:`m`] - wing_aspect_ratio (float): - Wing aspect ratio, [:math:`-`] - mach_num (float): - Mach number, [:math:`-`] - air_temperature (float): - Air temperature, [:math:`K`] - air_pressure (float): - Air pressure, [:math:`Pa`] - - # Returns - float: Reynolds number, [:math:`-`] - """ - # compute wing chord - wing_chord = wing_span / wing_aspect_ratio - - # dynamic viscosity - mu_inf = dynamic_viscosity(air_temperature) - - # mach number - M_inf = mach_num - - # local speed of sound - a_inf = local_speed_of_sound(air_temperature) - - # density of dry air - rho_inf = air_density(air_pressure, air_temperature) - - return (rho_inf * a_inf / mu_inf) * wing_chord * M_inf - - -def local_speed_of_sound(air_temperature: float) -> float: - """Calculate the local speed of sound. - - # Parameters - air_temperature (float): - Air temperature, [:math:`K`] - - # Returns - float: Local speed of sound, [:math:`m/s`] - """ - return (constants.gamma * constants.R * air_temperature) ** 0.5 - - -def air_density(air_pressure: float, air_temperature: float) -> float: - """Calculate the air density. - - # Parameters - air_pressure (float): - Air pressure, [:math:`Pa`] - air_temperature (float): - Air temperature, [:math:`K`] - - # Returns - float: Air density, [:math:`kg/m^3`] - """ - return air_pressure / (constants.R * (air_temperature + 1e-8)) - - -def dynamic_viscosity(air_temperature: float) -> float: - """Calculate approximation of the dynamic viscosity. - - # Parameters - air_temperature (float): - Air temperature, [:math:`K`] - - # Returns - float: Dynamic viscosity, [:math:`kg m^{-1} s^{-1}`] - """ - - mu_Tref = 1.715e-5 - Tref = 273.15 - S = 110.4 - - return ( - mu_Tref - * (air_temperature / Tref) ** 1.5 - * (Tref + S) - / (air_temperature + S + 1e-6) - ) - - -# ------------------------------- -# Lift and drag coefficients -# ------------------------------- - - -def lift_coefficient( - wing_surface_area: float, - aircraft_mass: float, - air_pressure: float, - air_temperature: float, - mach_num: float, - climb_angle: float, -) -> float: - """Calculate the lift coefficient. - - # Parameters - wing_surface_area (float): - Wing surface area, [:math:`m^2`] - aircraft_mass (float): - Aircraft mass, [:math:`kg`] - air_pressure (float): - Air pressure, [:math:`Pa`] - mach_num (float): - Mach number, [:math:`-`] - climb_angle (float): - Climb angle, [:math:`deg`] - - # Returns - float: Lift coefficient, [:math:`-`] - """ - - lift_force = aircraft_mass * constants.g * np.cos(np.deg2rad(climb_angle)) - air_speed = mach_num * local_speed_of_sound(air_temperature) - air_dens = air_density(air_pressure, air_temperature) - dynamic_pressure = air_dens * air_speed**2 / 2 - - return lift_force / (dynamic_pressure * wing_surface_area) - - -def skin_friction_coefficient(reynolds_number: float) -> float: - """Calculate the skin friction coefficient. - - # Parameters - reynolds_number (float): - Reynolds number, [:math:`-`] - - # Returns - float: Skin friction coefficient, [:math:`-`] - """ - return 0.0269 / (reynolds_number**0.14) - - -def zero_lift_drag_coefficient(c_f: float, psi_0: float) -> float: - """Calculate the zero-lift drag coefficient. - - # Parameters - c_f (float): - Skin friction coefficient, [:math:`-`] - psi_0 (float): - Miscellaneous drag factor, [:math:`-`] - - # Returns - float: Zero-lift drag coefficient, [:math:`-`] - """ - return c_f * psi_0 - - -def oswald_efficiency_factor( - c_drag_0: float, aircraft_parameters: dict[str, float] -) -> float: - """Calculate the Oswald efficiency factor. - - # Parameters - c_drag_0 (float): - Zero-lift drag coefficient, [:math:`-`] - aircraft_parameters (dict[str, float]): - Aircraft parameters. - - # Returns - float: Oswald efficiency factor, [:math:`-`] - """ - numer = 1.075 if aircraft_parameters["winglets"] == "no" else 1.0 - k1 = _non_vortex_lift_dependent_drag_factor( - c_drag_0, aircraft_parameters["cos_sweep"] - ) - denom = 1.04 + math.pi * k1 * aircraft_parameters["wing_aspect_ratio"] - - return numer / denom - - -def _non_vortex_lift_dependent_drag_factor(c_drag_0: float, cos_sweep: float) -> float: - """Calculate the miscellaneous lift-dependent drag factor. - - # Parameters - c_drag_0 (float): - Zero-lift drag coefficient, [:math:`-`] - cos_sweep (float): - Cosine of the wing sweep angle, [:math:`-`] - - # Returns - float: Miscellaneous lift-dependent drag factor, [:math:`-`] - """ - return 0.80 * (1 - 0.53 * cos_sweep) * c_drag_0 - - -def wave_drag_coefficient( - mach_num: float, c_lift: float, aircraft_parameters: dict[str, float] -) -> float: - """Calculate the wave drag coefficient. - - # Parameters - mach_num (float): - Mach number, [:math:`-`] - c_lift (float): - Lift coefficient, [:math:`-`] - aircraft_parameters (dict[str, float]): - Aircraft parameters. - - # Returns - float: Wave drag coefficient, [:math:`-`] - """ - m_cc = aircraft_parameters["wing_constant"] - 0.10 * ( - c_lift / aircraft_parameters["cos_sweep"] ** 2 - ) - x = mach_num * aircraft_parameters["cos_sweep"] / m_cc - - c_d_w = np.where( - x < aircraft_parameters["j_2"], - 0.0, - aircraft_parameters["cos_sweep"] ** 3 - * aircraft_parameters["j_1"] - * (x - aircraft_parameters["j_2"]) ** 2, - ) - - output = np.where( - x < aircraft_parameters["x_ref"], - c_d_w, - c_d_w + aircraft_parameters["j_3"] * (x - aircraft_parameters["x_ref"]) ** 4, - ) - - return output - - -def airframe_drag_coefficient( - c_drag_0: float, - c_drag_w: float, - c_lift: float, - e_ls: float, - wing_aspect_ratio: float, -) -> float: - """Calculate total airframe drag coefficient. - - # Parameters - c_drag_0 (float): - Zero-lift drag coefficient, [:math:`-`] - c_drag_w (float): - Wave drag coefficient, [:math:`-`] - c_lift (float): - Lift coefficient, [:math:`-`] - e_ls (float): - Oswald efficiency factor, [:math:`-`] - wing_aspect_ratio (float): - Wing aspect ratio, [:math:`-`] - - # Returns - float: Total airframe drag coefficient, [:math:`-`] - """ - return c_drag_0 + c_drag_w + c_lift**2 / (math.pi * e_ls * wing_aspect_ratio) - - -# ------------------- -# Engine parameters -# ------------------- - - -def thrust_force( - aircraft_mass: float, c_l: float, c_d: float, dv_dt: float, theta: float -) -> float: - """Calculate thrust force summed over all engines. - - # Parameters - aircraft_mass (float): - Aircraft mass, [:math:`kg`] - c_l (float): - Lift coefficient, [:math:`-`] - c_d (float): - Drag coefficient, [:math:`-`] - dv_dt (float): - Rate of change of velocity, [:math:`m/s^2`] - theta (float): - Flight path angle, [:math:`deg`] - - # Returns - float: Thrust force, [:math:`N`] - """ - theta_rad = math.radians(theta) - - f_thrust = ( - (aircraft_mass * constants.g * math.cos(theta_rad) * (c_d / c_l)) - + (aircraft_mass * constants.g * math.sin(theta_rad)) - + (aircraft_mass * dv_dt) - ) - return max(f_thrust, 0) - - -def engine_thrust_coefficient( - f_thrust: float, mach_num: float, air_pressure: float, wing_surface_area: float -) -> float: - """Calculate engine thrust coefficient. - - # Parameters - f_thrust (float): - Thrust force, [:math:`N`] - mach_num (float): - Mach number, [:math:`-`] - air_pressure (float): - Air pressure, [:math:`Pa`] - wing_surface_area (float): - Wing surface area, [:math:`m^2`] - - # Returns - float: Engine thrust coefficient, [:math:`-`] - """ - return f_thrust / ( - 0.5 * constants.gamma * air_pressure * mach_num**2 * wing_surface_area - ) - - -def overall_propulsion_efficiency( - mach_num: float, - c_t: float, - c_t_eta_b: float, - aircraft_parameters: dict[str, float], - eta_over_eta_b_min: float, -) -> float: - """Calculate overall propulsion efficiency. - - # Parameters - mach_num (float): - Mach number, [:math:`-`] - c_t (float): - Thrust coefficient, [:math:`-`] - c_t_eta_b (float): - Thrust coefficient at maximum efficiency, [:math:`-`] - aircraft_parameters (dict[str, float]): - Aircraft parameters. - eta_over_eta_b_min (float): - Minimum engine efficiency, [:math:`-`] - - # Returns - float: Overall propulsion efficiency, [:math:`-`] - """ - eta_over_eta_b = propulsion_efficiency_over_max_propulsion_efficiency( - mach_num, c_t, c_t_eta_b - ) - - if eta_over_eta_b_min is not None: - eta_over_eta_b.clip(min=eta_over_eta_b_min, out=eta_over_eta_b) - - eta_b = max_overall_propulsion_efficiency( - mach_num, aircraft_parameters["eta_1"], aircraft_parameters["eta_2"] - ) - - return eta_over_eta_b * eta_b - - -def propulsion_efficiency_over_max_propulsion_efficiency( - mach_num: float, c_t: float, c_t_eta_b: float -) -> float: - """Calculate propulsion efficiency over maximum propulsion efficiency. - - # Parameters - mach_num (float): - Mach number, [:math:`-`] - c_t (float): - Thrust coefficient, [:math:`-`] - c_t_eta_b (float): - Thrust coefficient at maximum efficiency, [:math:`-`] - - # Returns - float: Propulsion efficiency over maximum propulsion efficiency, [:math:`-`] - """ - c_t_over_c_t_eta_b = c_t / c_t_eta_b - - sigma = np.where(mach_num < 0.4, 1.3 * (0.4 - mach_num), 0.0) - - eta_over_eta_b_low = ( - 10.0 * (1.0 + 0.8 * (sigma - 0.43) - 0.6027 * sigma * 0.43) * c_t_over_c_t_eta_b - + 33.3333 - * (-1.0 - 0.97 * (sigma - 0.43) + 0.8281 * sigma * 0.43) - * (c_t_over_c_t_eta_b**2) - + 37.037 - * (1.0 + (sigma - 0.43) - 0.9163 * sigma * 0.43) - * (c_t_over_c_t_eta_b**3) - ) - eta_over_eta_b_hi = ( - (1.0 + (sigma - 0.43) - sigma * 0.43) - + (4.0 * sigma * 0.43 - 2.0 * (sigma - 0.43)) * c_t_over_c_t_eta_b - + ((sigma - 0.43) - 6 * sigma * 0.43) * (c_t_over_c_t_eta_b**2) - + 4.0 * sigma * 0.43 * (c_t_over_c_t_eta_b**3) - - sigma * 0.43 * (c_t_over_c_t_eta_b**4) - ) - return np.where(c_t_over_c_t_eta_b < 0.3, eta_over_eta_b_low, eta_over_eta_b_hi) - - -def thrust_coefficient_at_max_efficiency( - mach_num: float, m_des: float, c_t_des: float -) -> float: - """Calculate thrust coefficient at maximum overall propulsion efficiency for a given Mach Number. - - # Parameters - mach_num (float): - Mach number, [:math:`-`] - m_des (float): - Design Mach number, [:math:`-`] - c_t_des (float): - Thrust coefficient at design Mach number, [:math:`-`] - - # Returns - float: Thrust coefficient at maximum overall propulsion efficiency, [:math:`-`] - """ - m_over_m_des = mach_num / m_des - h_2 = ((1.0 + 0.55 * mach_num) / (1.0 + 0.55 * m_des)) / (m_over_m_des**2) - - return h_2 * c_t_des - - -def max_overall_propulsion_efficiency( - mach_num: float, eta_1: float, eta_2: float -) -> float: - """Calculate maximum overall propulsion efficiency. - - # Parameters - mach_num (float): - Mach number, [:math:`-`] - eta_1 (float): - Efficiency parameter 1, [:math:`-`] - eta_2 (float): - Efficiency parameter 2, [:math:`-`] - - # Returns - float: Maximum overall propulsion efficiency, [:math:`-`] - """ - return eta_1 * mach_num**eta_2 - - -# ------------------- -# Full comsumption -# ------------------- - - -def fuel_mass_flow_rate( - air_pressure: float, - air_temperature: float, - mach_num: float, - c_t: float, - eta: float, - wing_surface_area: float, - q_fuel: float, -) -> float: - """Calculate fuel mass flow rate. - - # Parameters - air_pressure (float): - Air pressure, [:math:`Pa`] - air_temperature (float): - Air temperature, [:math:`K`] - mach_num (float): - Mach number, [:math:`-`] - c_t (float): - Thrust coefficient, [:math:`-`] - eta (float): - Engine efficiency, [:math:`-`] - wing_surface_area (float): - Wing surface area, [:math:`m^2`] - q_fuel (float): - Fuel heating value, [:math:`J/kg`] - - # Returns - float: Fuel mass flow rate, [:math:`kg/s`] - """ - return ( - (constants.gamma / 2) - * (c_t * mach_num**3 / eta) - * (constants.gamma * constants.R * air_temperature * air_pressure) ** 0.5 - * air_pressure - * wing_surface_area - / q_fuel - ) - - -def fuel_flow_correction( - fuel_flow: float, - altitude_ft: float, - air_temperature: float, - air_pressure: float, - mach_num: float, - fuel_flow_idle_sls: float, - fuel_flow_max_sls: float, - flight_phase: str, -) -> float: - """Correct fuel flow. - - # Parameters - fuel_flow (float): - Fuel flow, [:math:`kg/s`] - altitude_ft (float): - Altitude, [:math:`ft`] - air_temperature (float): - Air temperature, [:math:`K`] - air_pressure (float): - Air pressure, [:math:`Pa`] - mach_num (float): - Mach number, [:math:`-`] - fuel_flow_idle_sls (float): - Fuel flow at idle at sea level, [:math:`kg/s`] - fuel_flow_max_sls (float): - Maximum fuel flow at sea level, [:math:`kg/s`] - flight_phase (str): - Flight phase, [:math:`-`] - - # Returns - float: Corrected fuel flow, [:math:`kg/s`] - """ - - ff_min = op_lim.fuel_flow_idle(fuel_flow_idle_sls, altitude_ft) - ff_max = jet.equivalent_fuel_flow_rate_at_cruise( - fuel_flow_max_sls, - (air_temperature / constants.T_msl), - (air_pressure / constants.p_surface), - mach_num, - ) - - if flight_phase == "descent": - ff_max = 0.3 * fuel_flow_max_sls - - return np.clip(fuel_flow, ff_min, ff_max) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/constants.py b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/constants.py deleted file mode 100644 index 03e5b21ed2..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/constants.py +++ /dev/null @@ -1,20 +0,0 @@ -# ratio specific heats -gamma: float = 1.4 - -# constant of air in the ideal gas law -R: float = 287.0500676 # J/(kg*K) - -# gravitational acceleration -g: float = 9.807 # m/s^2 - -# standard atmospheric temperature at mean sea level -T_msl: float = 288.15 - -# surface pressure, internation standard atmosphere -p_surface: float = 101325.0 - -# rate at which ISA ambient temperature falls with altitude -T_lapse_rate: float = -0.0065 - -# ISA height of the tropopause -h_tropopause: float = 11000.0 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/jet.py b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/jet.py deleted file mode 100644 index 5bd54060c2..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/jet.py +++ /dev/null @@ -1,104 +0,0 @@ -import numpy as np - -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - units, -) - - -def equivalent_fuel_flow_rate_at_cruise( - fuel_flow_sls: float, theta_amb: float, delta_amb: float, mach_num: float -) -> float: - """Convert fuel mass flow rate at sea level to equivalent fuel flow rate at cruise conditions. - - # Parameters - fuel_flow_sls (float): - Fuel mass flow rate at sea level, [:math:`kg/s`]. - theta_amb (float): - Ambient temperature ratio, [:math:`K`]. - delta_amb (float): - Ambient pressure ratio, [:math:`Pa`]. - mach_num (float): - Mach number, [:math:`-`]. - - # Returns - float: Equivalent fuel mass flow rate at cruise conditions, [:math:`kg/s`]. - """ - - denom = (theta_amb**3.8 / delta_amb) * np.exp(0.2 * mach_num**2) - # denominator must be >= 1, otherwise corrected_fuel_flow > fuel_flow_max_sls - denom = np.clip(denom, 1.0, None) - - return fuel_flow_sls / denom - - -def clip_mach_number( - true_airspeed: float, - air_temperature: float, - max_mach_number: float, -): - """Compute the Mach number from the true airspeed and ambient temperature. - - # Parameters - true_airspeed (float): - True airspeed, [:math:`m/s`]. - air_temperature (float): - Ambient temperature, [:math:`K`]. - max_mach_number (float): - Maximum permitted operational Mach number for aircraft type. - - # Returns - tuple[np.ndarray, np.ndarray]: Adjusted true airspeed and Mach number. - """ - - mach_num = units.tas_to_mach_number(true_airspeed, air_temperature) - - is_unrealistic = mach_num > max_mach_number - if not np.any(is_unrealistic): - return true_airspeed, mach_num - - max_tas = units.mach_number_to_tas(max_mach_number, air_temperature) - adjusted_mach_num = np.where(is_unrealistic, max_mach_number, mach_num) - adjusted_true_airspeed = np.where(is_unrealistic, max_tas, true_airspeed) - - return adjusted_true_airspeed, adjusted_mach_num - - -def rate_of_climb_descent( - altitude_current: float, altitude_next: float, delta_time: float -) -> float: - """Compute the rate of climb or descent (ft/min) from the path angle and speed. - - # Parameters - altitude_current (float): - Current altitude, [:math:`ft`]. - altitude_next (float): - Next altitude, [:math:`ft`]. - delta_time (float): - Time step, [:math:`s`]. - - # Returns - float: Rate of climb or descent, [:math:`ft/min`]. - """ - - delta_time_min = delta_time / 60.0 - - return (altitude_next - altitude_current) / (delta_time_min + 1e-8) - - -# TODO: if speed not constant, change this function -def acceleration(speed_current, delta_time) -> float: - """Calculate the acceleration/deceleration at each waypoint. - - # Parameters - speed_current (float): - Current speed, [:math:`kts`]. - delta_time (float): - Time step, [:math:`s`]. - - # Returns - float: Acceleration, [:math:`kts/s`]. - """ - - # here the speed is constant. - - return 0 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/operational_limits.py b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/operational_limits.py deleted file mode 100644 index 6fff99a480..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/operational_limits.py +++ /dev/null @@ -1,113 +0,0 @@ -# data - -import numpy as np - -# utils -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - constants, -) - - -def fuel_flow_idle(fuel_flow_idle_sls: float, altitude_ft: float) -> float: - """ - Calculate minimum fuel mass flow rate at flight idle conditions. - """ - - x = altitude_ft / 10_000.0 - return fuel_flow_idle_sls * (1.0 - 0.178 * x + 0.0085 * x**2) - - -def max_mach_number_by_altitude( - altitude_ft: float, - air_pressure: float, - max_mach_num: float, - p_i_max: float, - p_inf_co: float, - *, - atm_speed_limit: bool = True, - buffer: float = 0.02, -) -> float: - """ - Calculate maximum permitted Mach number at a given altitude. - - altitude_ft: current altitude (ft) - air_pressure: current air pressure (Pa) - max_mach_num: maximum Mach number - p_i_max: maximum dynamic pressure (Pa) - p_inf_co: critical pressure (Pa) - atm_speed_limit: whether to apply atmospheric speed limit - buffer: buffer for maximum Mach number - """ - - if atm_speed_limit: - p_i_max = np.where(altitude_ft < 10000.0, 10510.0, p_i_max) # type: ignore[assignment] - - return ( - np.where( # type: ignore[return-value] - air_pressure > p_inf_co, - 2.0**0.5 - * ((1.0 + (2.0 / constants.gamma) * (p_i_max / air_pressure)) ** 0.5 - 1.0) - ** 0.5, - max_mach_num, - ) - + buffer - ) - - -def max_available_thrust_coefficient( - air_temperature: float, - mach_number: float, - c_t_eta_b: float, - aircraft_parameters: dict[str, float], - *, - buffer: float = 0.05, -) -> float: - """ - Calculate maximum available thrust coefficient. - - Parameters - ---------- - air_temperature : ArrayOrFloat - Ambient temperature at each waypoint, [:math:`K`] - mach_number : ArrayOrFloat - Mach number at each waypoint. - c_t_eta_b : ArrayOrFloat - Thrust coefficient at maximum overall propulsion efficiency for a given Mach Number. - aircraft_parameters : PSAircraftEngineParams - Extracted aircraft and engine parameters. - buffer : float, optional - Additional buffer for maximum available thrust coefficient. The default value is 0.05, - which increases the maximum available thrust coefficient by 5%. - - Returns - ------- - ArrayOrFloat - Maximum available thrust coefficient that can be supplied by the engines. - """ - tr_max = _normalised_max_throttle_parameter( - air_temperature, - mach_number, - aircraft_parameters["tet_mcc"], - aircraft_parameters["tr_ec"], - aircraft_parameters["m_ec"], - ) - c_t_max_over_c_t_eta_b = 1.0 + 2.5 * (tr_max - 1.0) - return c_t_max_over_c_t_eta_b * c_t_eta_b * (1.0 + buffer) - - -def _normalised_max_throttle_parameter( - air_temperature: float, - mach_number: float, - tet_mcc: float, - tr_ec: float, - m_ec: float, -) -> float: - """ - Calculate normalised maximum throttle parameter. - """ - - return (tet_mcc / air_temperature) / ( - tr_ec - * (1.0 - 0.53 * (mach_number - m_ec) ** 2) - * (1.0 + 0.2 * mach_number**2) - ) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/units.py b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/units.py deleted file mode 100644 index f4ca4887cc..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/units.py +++ /dev/null @@ -1,77 +0,0 @@ -# data -import numpy as np - -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - constants, -) - - -def ft_to_pl(h: float) -> float: - """ - Convert from altitude (ft) to pressure level (hPa). - Assumes the ICAO standard atmosphere. - """ - return m_to_pl(ft_to_m(h)) - - -def ft_to_m(ft: float) -> float: - """ - Convert length from feet to meter. - """ - return ft * 0.3048 - - -def m_to_pl(h): - """ - Convert from altitude (m) to pressure level (hPa). - """ - condlist = [h < constants.h_tropopause, h >= constants.h_tropopause] - funclist = [ - _low_altitude_m_to_pl, - _high_altitude_m_to_pl, - np.nan, - ] # nan passed through - return np.piecewise(h, condlist, funclist) - - -def _low_altitude_m_to_pl(h): - T_isa: np.ndarray = m_to_T_isa(h) - power_term = -constants.g / (constants.T_lapse_rate * constants.R) - return (constants.p_surface * (T_isa / constants.T_msl) ** power_term) / 100.0 - - -def _high_altitude_m_to_pl(h): - T_tropopause_isa = m_to_T_isa(np.asarray(constants.h_tropopause)) - power_term = -constants.g / (constants.T_lapse_rate * constants.R) - p_tropopause_isa = ( - constants.p_surface * (T_tropopause_isa / constants.T_msl) ** power_term - ) - inside_exp = (-constants.g / (constants.R * T_tropopause_isa)) * ( - h - constants.h_tropopause - ) - return p_tropopause_isa * np.exp(inside_exp) / 100.0 - - -def m_to_T_isa(h): - """ - Calculate the ambient temperature (K) for a given altitude (m). - """ - - h_min = np.minimum(h, constants.h_tropopause) - - return constants.T_msl + h_min * constants.T_lapse_rate - - -def tas_to_mach_number(true_airspeed, T): - """ - Calculate Mach number from true airspeed at a specified ambient temperature. - """ - - return true_airspeed / np.sqrt((constants.gamma * constants.R) * (T + 1e-8)) - - -def mach_number_to_tas(mach_number, T): - """ - Calculate true airspeed from the Mach number at a specified ambient temperature. - """ - return mach_number * np.sqrt((constants.gamma * constants.R) * T) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/pollschumann.py b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/pollschumann.py deleted file mode 100644 index d4f021d483..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/pollschumann.py +++ /dev/null @@ -1,206 +0,0 @@ -# data and maths -import math - -# typing -from typing import Optional - -import numpy as np - -# engine data loader -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, -) - -# utils -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - atmospheric_parameters as atm_params, -) -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - jet, -) -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - operational_limits as op_lim, -) -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - units, -) - -# aero -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.utils.aero import ( - ft, - kts, -) - -MIN_CRUISE_ALTITUDE = 20_000.0 - - -class FuelFlow: - """ - Fuel flow model based on Poll-Schumann model. - """ - - def __init__(self, actype: str): - """Initialisation of the fuel flow model based on Poll-Schumann model. - - # Parameters - actype (str): - Aircraft type for which the fuel flow model is created. - """ - - # load engine parameters for selected aircraft - self.aircraft_parameters = load_aircraft_engine_params(actype) - - def __call__( - self, - values_current: dict[str, float], - delta_time: float, - vs: Optional[float] = 0.0, - ) -> float: - """Compute fuel flow based on Poll-Schumann model. - - # Parameters - values_current (dict[str, float]): - Dictionary with current values of altitude [:math:`ft`], speed [:math:`kts`], temperature [:math:`K`], and mass [:math:`Kg`]. - delta_time (float): - Time step in seconds [:math:`s`]. - vs (Optional[float], optional): - Vertical speed [:math: `ft/min`]. Defaults to 0.0 ft/min. - - # Returns - float: Fuel flow, [:math:`Kg/s`]. - """ - - # values current - altitude_current = values_current["alt"] - air_temperature = values_current["temp"] - speed_current = values_current["speed"] * kts - mass_current = values_current["mass"] - - # values next - altitude_next = altitude_current + vs * delta_time / 60 # s -> min - # atmospheric quantities - air_pressure = units.ft_to_pl(altitude_current) * 100.0 - - # clip unrealistically high TAS - max_mach = op_lim.max_mach_number_by_altitude( - altitude_current, - air_pressure, - self.aircraft_parameters["max_mach_num"], - self.aircraft_parameters["p_i_max"], - self.aircraft_parameters["p_inf_co"], - atm_speed_limit=False, - buffer=0.02, - ) - - true_airspeed, mach_num = jet.clip_mach_number( - speed_current, air_temperature, max_mach - ) - - # Reynolds number - reynolds = atm_params.reynolds_number( - self.aircraft_parameters["wing_span"], - self.aircraft_parameters["wing_aspect_ratio"], - mach_num, - air_temperature, - air_pressure, - ) - - # Rate Of Climb and Descent; path angle; acceleration - rocd = jet.rate_of_climb_descent(altitude_current, altitude_next, delta_time) - path_angle = math.degrees( - (altitude_next - altitude_current) * ft / (true_airspeed * delta_time) - ) # approximation for small angles - - dv_dt = jet.acceleration(true_airspeed, delta_time) - - # aircraft performance parameters - c_lift = atm_params.lift_coefficient( - self.aircraft_parameters["wing_surface_area"], - mass_current, - air_pressure, - air_temperature, - mach_num, - path_angle, - ) - c_f = atm_params.skin_friction_coefficient(reynolds) - c_drag_0 = atm_params.zero_lift_drag_coefficient( - c_f, self.aircraft_parameters["psi_0"] - ) - e_ls = atm_params.oswald_efficiency_factor(c_drag_0, self.aircraft_parameters) - c_drag_w = atm_params.wave_drag_coefficient( - mach_num, c_lift, self.aircraft_parameters - ) - c_drag = atm_params.airframe_drag_coefficient( - c_drag_0, - c_drag_w, - c_lift, - e_ls, - self.aircraft_parameters["wing_aspect_ratio"], - ) - - # engine parameters and fuel consumption - thrust = atm_params.thrust_force( - mass_current, c_lift, c_drag, dv_dt, path_angle - ) - - c_t = atm_params.engine_thrust_coefficient( - thrust, - mach_num, - air_pressure, - self.aircraft_parameters["wing_surface_area"], - ) - c_t_eta_b = atm_params.thrust_coefficient_at_max_efficiency( - mach_num, - self.aircraft_parameters["m_des"], - self.aircraft_parameters["c_t_des"], - ) - - # correct fuel flow - c_t_available = op_lim.max_available_thrust_coefficient( - air_temperature, mach_num, c_t_eta_b, self.aircraft_parameters - ) - c_t = np.clip(c_t, 0, c_t_available) - - # engine efficiency - eta_over_eta_b_min = 0.5 - engine_efficiency = atm_params.overall_propulsion_efficiency( - mach_num, c_t, c_t_eta_b, self.aircraft_parameters, eta_over_eta_b_min - ) - - # fuel flow - q_fuel = 43.13e6 - fuel_flow = atm_params.fuel_mass_flow_rate( - air_pressure, - air_temperature, - mach_num, - c_t, - engine_efficiency, - self.aircraft_parameters["wing_surface_area"], - q_fuel, - ) - - # compute flight phase - rocd_threshold = 250.0 - cruise = ( - (rocd < rocd_threshold) - & (rocd > -rocd_threshold) - & (altitude_current > MIN_CRUISE_ALTITUDE) - ) - climb = ~cruise & (rocd > 0.0) - # descent = ~cruise & (rocd < 0.0) - - # convert to string - flight_phase = np.where(cruise, "cruise", np.where(climb, "climb", "descent")) - - self.fuel_flow = atm_params.fuel_flow_correction( - fuel_flow, - altitude_current, - air_temperature, - air_pressure, - mach_num, - self.aircraft_parameters["ff_idle_sls"], - self.aircraft_parameters["ff_max_sls"], - flight_phase, - ) - - return self.fuel_flow diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/utils/aero.py b/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/utils/aero.py deleted file mode 100644 index 50e4cfe1a4..0000000000 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/utils/aero.py +++ /dev/null @@ -1,2 +0,0 @@ -ft = 0.3048 # ft -> m -kts = 0.514444 # knot -> m/s diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/aircraft_parameters.py b/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/aircraft_parameters.py similarity index 89% rename from skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/aircraft_parameters.py rename to skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/aircraft_parameters.py index 55807644a3..1da68a4ba8 100644 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/parameters/aircraft_parameters.py +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/aircraft_parameters.py @@ -1,9 +1,8 @@ # math import numpy as np -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - constants, -) +gamma = 1.4 +p_surface = 101325.0 def turbine_entry_temperature_at_max_take_off(first_flight: float) -> float: @@ -48,9 +47,9 @@ def impact_pressure_max_operating_limits(max_mach_num: float) -> float: the speed at sea level in the ISA that has the same impact pressure. """ v_cas_mo_over_c_msl = max_calibrated_airspeed_over_speed_of_sound(max_mach_num) - return constants.p_surface * ( - (1.0 + 0.5 * (constants.gamma - 1.0) * v_cas_mo_over_c_msl**2) - ** (constants.gamma / (constants.gamma - 1.0)) + return p_surface * ( + (1.0 + 0.5 * (gamma - 1.0) * v_cas_mo_over_c_msl**2) + ** (gamma / (gamma - 1.0)) - 1.0 ) @@ -82,7 +81,7 @@ def crossover_pressure_altitude(max_mach_num: float, p_i_max: float) -> float: """ return p_i_max / ( 0.5 - * constants.gamma + * gamma * max_mach_num**2 * (1.0 + (max_mach_num**2 / 4.0) + (max_mach_num**4 / 40.0)) ) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/data/aircraft_engine_params.csv b/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/data/aircraft_engine_params.csv new file mode 100644 index 0000000000..55d31a28cb --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/data/aircraft_engine_params.csv @@ -0,0 +1,68 @@ +ICAO,Manufacturer,Type,Year_of_first_flight,n_engine,winglets,WV,MTOM_kg,MLM_kg,MZFM_kg,OEM_i_kg,MPM_i_kg,MZFM_MTOM,OEM_i_MTOM,MPM_i_MTOM,Sref_m2,span_m,bf_m,delta_2,cos_sweep,AR,psi_0,Xo,wing_constant,j_2,j_1,CL_do,etaL_D_do,nominal_F00_ISA_kn,mf_max_T_O_SLS_kg_s,mf_idle_SLS_kg_s,M_des,CT_des,eta_1,eta_2,Mec,Tec,FL_max,MMO,pi_max_pa,pinf_co_pa,nominal_opr,nominal_bpr,nominal_fpr +A20N,Airbus,A320-NEO,2014,2,yes,54,79000,66300,62800,43600,19200,0.794936709,0.551898734,0.243037975,122.4,35.1,3.59,0.02092207,0.906307767,10.06544118,7.519168898,0.956139347,0.786244088,0.872610625,0.075611461,0.597752236,6.437505219,255.7834783,1.771291826,0.179714609,0.7527,0.030225318,0.363162533,0.38526913,0.787080092,6.248203519,410,0.82,20882.78822,37618.41516,34.13434783,11.63652174,1.65 +A21N,Airbus,A321-NEO,2016,2,yes,52,93500,77300,73000,48000,25000,0.780748663,0.513368984,0.267379679,122.4,35.27,3.95,0.025084952,0.906307767,10.16317729,8.080988052,0.973612104,0.776932809,0.873049689,0.077052255,0.626442739,6.502543201,255.7834783,1.771291826,0.179714609,0.7527,0.032774858,0.379556514,0.38526913,0.787080092,6.202228431,391.0104987,0.82,20882.78822,37618.41516,34.13434783,11.63652174,1.65 +A306,Airbus,A300B4-600R,1983,2,no,0,170500,140000,130000,86220,43780,0.762463343,0.50568915,0.256774194,260,44.84,5.64,0.031641495,0.882947568,7.733175385,7.803846371,1.014875092,0.721487903,0.871400617,0.076160146,0.519478424,5.296827535,524.8533333,5.078666667,0.424,0.7527,0.030658862,0.364210924,0.537766667,0.683259556,5.336387723,410,0.82,20882.78822,37618.41516,31.52666667,4.933333333,1.65 +A30B,Airbus,A300B4-200,1973,2,no,6,165000,134000,124000,88505,35495,0.751515152,0.536393939,0.215121212,260,44.83,5.64,0.031655613,0.882947568,7.729726538,8.774193537,1.036099444,0.711780698,0.86836702,0.07391802,0.548381029,4.318482734,466.2,4.8029,0.4,0.7527,0.034997635,0.321789379,0.54535,0.674344,4.93205278,390,0.82,20882.78822,37618.41516,26.47,4.6,1.65 +A310,Airbus,A310-200,1982,2,no,8,138600,122000,112000,79207,32793,0.808080808,0.571479076,0.236601732,219,43.89,5.64,0.033026081,0.882947568,8.796036986,8.375562451,1.013898087,0.743809599,0.868659927,0.073287068,0.557549017,5.65582168,443.525,4.2895,0.3842,0.772,0.032940786,0.383837958,0.53568125,0.685649,5.373550789,410,0.84,21865.62405,37237.40235,26.3725,5.025,1.65 +A313,Airbus,A310-300,1982,2,no,0,150000,123000,113000,77397,35603,0.753333333,0.51598,0.237353333,219,43.89,5.64,0.033026081,0.882947568,8.796036986,8.212622174,1.024582936,0.737571745,0.869516104,0.074562862,0.563576336,5.602548625,480.258,4.5104,0.3946,0.772,0.032853327,0.375278919,0.5369325,0.68421856,5.364267817,410,0.84,21865.62405,37237.40235,28.184,4.97,1.65 +A318,Airbus,A318-100,2002,2,no,5,68000,57500,53000,38818,14182,0.779411765,0.570852941,0.208558824,122.4,34.1,3.95,0.026835855,0.906307767,9.500081699,7.471444005,0.995441823,0.753958954,0.870956053,0.075008678,0.563947374,5.333478382,199.2533333,2.060666667,0.211333333,0.7527,0.030936248,0.340355901,0.532458333,0.689288889,6.031933509,410,0.82,20882.78822,37618.41516,25.43333333,5.166666667,1.65 +A319,Airbus,A319-100,1995,2,no,6,73500,62500,58500,39725,18775,0.795918367,0.54047619,0.255442177,122.4,34.1,3.95,0.026835855,0.906307767,9.500081699,7.700920319,0.995030706,0.754823537,0.870775437,0.074774133,0.568723265,5.098135499,212.4783333,1.987166667,0.212,0.7527,0.031550436,0.328,0.521633125,0.70104451,5.849202578,410,0.82,20882.78822,37618.41516,25.33833333,5.6425,1.65 +A320,Airbus,A320-200,1987,2,no,0,73500,64500,60500,41244,19256,0.823129252,0.561142857,0.261986395,122.4,34.1,3.95,0.026835855,0.906307767,9.500081699,8.395287612,1.006597506,0.749584382,0.868903458,0.073191605,0.59039895,5.259100576,224.638,2.1462,0.2239,0.7527,0.034652548,0.358,0.5218265,0.70084087,5.588929572,410,0.82,20882.78822,37618.41516,26.909,5.634,1.65 +A321,Airbus,A321-100,1993,2,no,8,89000,75500,71500,46856,24644,0.803370787,0.52647191,0.276898876,122.4,34.15,3.95,0.02675733,0.906307767,9.527961601,8.631216449,1.023748365,0.740171309,0.869023229,0.074059188,0.606338494,4.98823425,269.3142857,2.690571429,0.246285714,0.7527,0.0358593,0.342780897,0.52832,0.693868454,5.741120348,391.0006562,0.82,20882.78822,37618.41516,31.16285714,5.348571429,1.65 +A332,Airbus,A330-200,1992,2,no,52,233000,182000,170000,116840,53160,0.729613734,0.501459227,0.228154506,361.6,60.3,5.64,0.017496597,0.868631486,10.05555863,6.691783708,0.986539447,0.762475042,0.872047153,0.076050268,0.528141489,6.875896605,609.465,5.93725,0.4895,0.786475,0.02499242,0.37,0.535055625,0.68636059,5.728484511,410,0.86,22875.41229,36864.52979,34.20375,5.0525,1.65 +A333,Airbus,A330-300,1992,2,no,52,233000,187000,175000,120132,54868,0.751072961,0.515587983,0.235484979,361.6,60.3,5.64,0.017496597,0.868631486,10.05555863,6.899510103,0.989985236,0.76102049,0.871552208,0.075532661,0.535352593,7.128484765,604.4625,5.839875,0.49225,0.786475,0.025831756,0.391045891,0.534117188,0.687423438,5.727838461,410,0.86,22875.41229,36864.52979,33.67251837,5.09375,1.65 +A338,Airbus,A330-800,2018,2,no,,242000,186000,174000,132000,42000,0.719008264,0.545454545,0.173553719,374,64,5.64,0.015532031,0.866025375,10.95187166,6.212990529,0.958877916,0.780583541,0.873631599,0.077578309,0.530216374,8.328327417,655.6,4.956,0.482,0.786,0.022900369,0.400414909,0.44525,0.7634,6.246060604,414.5,0.86,22875.41229,36864.52979,45.4,9,1.65 +A339,Airbus,A330-900,2017,2,no,,242000,191000,181000,135000,46000,0.747933884,0.55785124,0.190082645,374,64,5.64,0.015532031,0.866025375,10.95187166,6.46325095,0.96246813,0.779169206,0.873192286,0.076918011,0.539469135,8.110705591,655.6,4.956,0.482,0.786,0.023887738,0.399788387,0.44525,0.7634,6.232485988,414.5,0.86,22875.41229,36864.52979,45.4,9,1.65 +A342,Airbus,A340-200,1991,4,no,1,257000,181000,169000,125242,43758,0.657587549,0.487322957,0.170264591,361.6,60.3,5.64,0.017496597,0.868631486,10.05555863,7.076588203,0.994839196,0.759754196,0.872370296,0.076725978,0.551202388,6.689573974,579.4666667,5.516,0.4824,0.786475,0.026833302,0.367,0.497575,0.724576,5.643739289,415,0.86,22875.41229,36864.52979,29.95,6.7,1.65 +A343,Airbus,A340-300,1991,4,no,1,257000,186000,174000,125242,48758,0.677042802,0.487322957,0.189719844,361.6,60.3,5.64,0.017496597,0.868631486,10.05555863,7.383954096,1.000285382,0.7573768,0.871649368,0.076010212,0.561474717,6.610070249,579.4666667,5.516,0.4824,0.786475,0.028082741,0.372580342,0.497575,0.724576,5.663601105,415,0.86,22875.41229,36864.52979,29.95,6.7,1.65 +A345,Airbus,A340-500,2002,4,no,1,372000,243000,230000,170370,59630,0.61827957,0.457983871,0.160295699,437.3,63.45,5.64,0.015802469,0.856267054,9.206271438,6.730844314,0.984937415,0.761952208,0.873638932,0.078182371,0.511999654,6.777298015,1036.4,8.786666667,0.92,0.796125,0.024513506,0.361959064,0.479375,0.74,5.668646964,414.5013123,0.86,22875.41229,36864.52979,36.17666667,7.5,1.65 +A346,Airbus,A340-600,2001,4,no,1,368000,259000,245000,176364,68636,0.66576087,0.47925,0.18651087,437.3,63.45,5.64,0.015802469,0.856267054,9.206271438,7.056855481,0.990652069,0.759481269,0.872973519,0.077394212,0.523156024,6.815977225,1050.8,8.96,0.92,0.796125,0.025814567,0.37517065,0.479375,0.74,5.68183304,415,0.86,22875.41229,36864.52979,36.67,7.5,1.65 +A359,Airbus,A350-900,2013,2,no,9,275000,207000,195700,146600,49100,0.711636364,0.533090909,0.178545455,445,64.75,5.96,0.016945054,0.848048064,9.421488764,6.140290359,0.962361567,0.791413177,0.873943906,0.078227432,0.493332851,8.125436058,758,5.638,0.582,0.82025,0.022496843,0.404691496,0.4450225,0.76353184,6.122466226,431.0006562,0.89,24441.49186,36319.05391,41.095,9.01,1.65 +A35K,Airbus,A350-1000,2016,2,yes,2,316000,236000,223000,156000,67000,0.705696203,0.493670886,0.212025316,465,64.75,5.96,0.016945054,0.848048064,9.016263441,6.183084792,0.966883665,0.788899107,0.87362679,0.077787748,0.499564827,8.147693431,873.4,7.014,0.65,0.82025,0.022347631,0.399824282,0.46709,0.74925344,6.172981137,414.5,0.89,24441.49186,36319.05391,48.57,8.04,1.65 +A388,Airbus,A380-800,2005,4,no,2,569000,391000,366000,275000,91000,0.643233743,0.483304042,0.159929701,845,79.8,7.142,0.016020051,0.866025375,7.536142012,6.132045576,0.966638255,0.794400187,0.875962464,0.081840299,0.446446426,7.498481785,1350.653333,10.56933333,1.072,0.82025,0.021624953,0.398677354,0.470199167,0.746999716,5.869080111,431.0006562,0.89,24441.49186,36319.05391,38.07666667,7.903333333,1.65 +B37M,Boeing,B737 MAX 7,2018,2,yes,,80285,66043,62913,42033,20880,0.783620851,0.523547363,0.260073488,121.875,33.26,3.76,0.02556002,0.906307767,9.076739282,7.585063721,0.975506932,0.778868312,0.872091922,0.075686978,0.572742665,6.295944315,247.6,2.0025,0.189,0.763285024,0.030537405,0.379940115,0.458445,0.75520576,6.283950827,410,0.82,20882.78822,37618.41516,40.14,8.42,1.65 +B38M,Boeing,B737 MAX 8/8-200,2016,2,yes,,82644,69308,65952,45072,20880,0.798025265,0.545375345,0.25264992,121.875,33.26,3.76,0.02556002,0.906307767,9.076739282,7.869374698,0.97906074,0.77729995,0.871570728,0.075098953,0.581003295,6.209094863,247.6,2.0025,0.189,0.763285024,0.031631133,0.382601025,0.458445,0.75520576,6.256185757,410,0.82,20882.78822,37618.41516,40.14,8.42,1.65 +B39M,Boeing,B737 MAX 9,2017,2,yes,,88314,74343,70987,50107,20880,0.803802342,0.567373236,0.236429105,121.875,33.26,3.76,0.02556002,0.906307767,9.076739282,8.05844544,0.994198601,0.76872365,0.87201018,0.076256786,0.598926212,6.239926908,247.6,2.0025,0.189,0.763285024,0.033089092,0.39018692,0.458445,0.75520576,6.236986266,410,0.82,20882.78822,37618.41516,40.14,8.42,1.65 +B712,Boeing,B717-200,1998,2,no,HGW,54884,49898,45586,31071,14515,0.83058815,0.566121274,0.264466876,92.75,28.4,3.4,0.028664947,0.906307767,8.69606469,8.722339782,1.035797278,0.684750239,0.867306999,0.07298002,0.593541399,4.555779693,179.025,1.8155,0.201,0.7,0.037603724,0.350583851,0.545179375,0.67454851,5.998301413,370.9973753,0.82,20882.78822,37618.41516,30.4725,4.6075,1.65 +B722,Boeing,727-200,1967,2,no,0,83820,70100,63560,44390,19170,0.758291577,0.529587211,0.228704366,157.9,32.92,3.76,0.026090718,0.848048064,6.863371754,7.901954881,1.057801221,0.686729187,0.86502235,0.07205027,0.499213735,3.689723246,203.75625,3.4058625,0.41835,0.77,0.03284992,0.286,0.626595938,0.556514178,4.631875613,420,0.9,24977.42649,36140.62533,16.539375,1.02875,1.65 +B732,Boeing,B737-200,1967,2,no,5,52390,46720,43092,27125,15967,0.822523382,0.517751479,0.304771903,99,28.35,3.76,0.035180302,0.906307767,8.118409091,8.406144658,1.040134437,0.677684157,0.866573271,0.072538149,0.55647915,3.340772824,137.0738462,2.302092308,0.280215385,0.7,0.035879744,0.26934358,0.626585,0.556532787,4.655496203,370,0.82,20882.78822,37618.41516,16.59230769,1.029230769,1.65 +B733,Boeing,B737-300,1984,2,no,3,61236,51710,48308,32904,15404,0.788882357,0.537330982,0.251551375,102,28.9,3.76,0.033854001,0.906307767,8.188333333,9.200303497,1.023913881,0.715234635,0.867001262,0.072169037,0.577795554,4.096979487,187.3,2.014,0.234,0.728575,0.038442568,0.322802793,0.533975,0.687584,5.504887402,390,0.82,20882.78822,37618.41516,23.335,5.1,1.65 +B734,Boeing,B737-400,1988,2,no,6,68039,56246,53070,33643,19427,0.779993827,0.494466409,0.285527418,102.5,28.9,3.76,0.033854001,0.906307767,8.148390244,8.898192984,1.032441891,0.710077823,0.868386618,0.073800023,0.579192045,4.13010135,190.1266667,2.054666667,0.236,0.728575,0.037719014,0.318517837,0.533975,0.687584,5.587042978,370,0.82,20882.78822,37618.41516,23.63333333,5.1,1.65 +B735,Boeing,B737-500,1989,2,no,3,60555,49895,46494,31312,15182,0.76779787,0.517083643,0.250714227,103.7,28.9,3.76,0.033854001,0.906307767,8.054098361,8.33451025,1.009337993,0.721164574,0.869653399,0.074113442,0.550008118,4.05463838,187.3,2.014,0.234,0.728575,0.034586216,0.301940508,0.533975,0.687584,5.694014409,370,0.82,20882.78822,37618.41516,23.335,5.1,1.65 +B736,Boeing,B737-600,1997,2,no,3,65544,55112,51936,36378,15558,0.792383742,0.555016477,0.237367265,124.6,34.3,3.76,0.024033523,0.906307767,9.442134831,7.424658581,0.99420637,0.75916017,0.871081977,0.0751116,0.56354659,5.269028449,189.9709091,1.880909091,0.197454545,0.757525,0.030955608,0.335074122,0.527356818,0.69491914,5.900578607,410,0.82,20882.78822,37618.41516,23.16272727,5.390909091,1.65 +B737,Boeing,B737-700,1997,2,no,3,70080,58604,55202,37648,17554,0.787699772,0.537214612,0.25048516,124.6,34.3,3.76,0.024033523,0.906307767,9.442134831,7.610623423,0.997092665,0.757625964,0.870727093,0.074802808,0.567363946,5.021956077,214.1278261,2.175826087,0.209652174,0.757525,0.031490511,0.323004185,0.530809783,0.691125898,5.90211253,410,0.82,20882.78822,37618.41516,25.6326087,5.239130435,1.65 +B738,Boeing,B737-800,1997,2,no,3,79016,66361,61689,41413,20276,0.780715298,0.524109041,0.256606257,124.6,34.3,3.76,0.024033523,0.906307767,9.442134831,8.181516743,1.00523362,0.753742328,0.86950188,0.073769983,0.581267312,4.983308444,233.3695652,2.432434783,0.218695652,0.757525,0.033462541,0.332681166,0.533381522,0.688252824,5.90333496,410,0.82,20882.78822,37618.41516,27.74869565,5.126086957,1.65 +B739,Boeing,B737-900ER,2006,2,no,2,85139,71350,67721,44676,23045,0.795416906,0.524741893,0.270675014,124.6,34.32,3.76,0.024005521,0.906307767,9.453149278,7.92834468,1.013309441,0.748758647,0.870784513,0.075460257,0.585041361,5.003070394,233.3695652,2.432434783,0.218695652,0.757525,0.032950004,0.326763054,0.533381522,0.688252824,6.102506148,410,0.82,20882.78822,37618.41516,27.74869565,5.126086957,1.65 +B742,Boeing,B747-200B,1971,4,no,4,371900,285700,238780,175970,62810,0.642054316,0.473164829,0.168889486,511,59.64,6.5,0.023756444,0.793353296,6.960723288,7.019056156,1.038495569,0.69161267,0.867976442,0.073665148,0.45831945,5.337545419,882.3333333,9.1104,0.89784,0.81,0.025930712,0.338481202,0.541406667,0.679024462,4.612144185,450,0.9,24977.42649,36140.62533,24.73333333,4.773333333,1.65 +B743,Boeing,B747-300,1980,4,no,0,377800,260320,242630,174820,67810,0.642218105,0.462731604,0.179486501,511,59.64,6.5,0.023756444,0.782608111,6.960723288,6.881751548,1.041627795,0.68253174,0.867287749,0.073197605,0.452943745,5.374951837,898.8126316,9.187157895,0.909452632,0.81,0.025344181,0.337122346,0.541757895,0.678611479,5.0506812,450,0.9,24977.42649,36140.62533,25.81736842,4.757894737,1.65 +B744,Boeing,B747-400,1985,4,no,5,396894,285764,246075,178756,67319,0.620001814,0.450387257,0.169614557,547,64.44,6.5,0.020349121,0.793353296,7.591432541,6.688263979,1.029069691,0.698340832,0.868929586,0.074170378,0.464992693,6.027234116,1021.254118,9.786509804,0.822909804,0.81,0.024511914,0.355811516,0.537298284,0.683798564,5.296210572,450,0.92,26070.46918,35788.4714,30.57901961,4.953921569,1.65 +B748,Boeing,B747-8F,2010,4,no,1,442253,345184,328854,197131,131723,0.743587946,0.445742595,0.297845351,594,68.4,6.5,0.018061113,0.793353296,7.876363636,6.248755182,0.997894651,0.732488325,0.872320594,0.076747175,0.457551278,7.386886339,1199.22,9.808,0.87,0.8299,0.022440249,0.395291631,0.46765875,0.74884564,5.888619001,421.0006562,0.9,24977.42649,36140.62533,42.975,8.015,1.65 +B752,Boeing,B757-200,1982,2,no,4,113400,89800,83450,62100,21350,0.735890653,0.547619048,0.188271605,189,38.06,3.76,0.019519474,0.906307767,7.664357672,7.102482242,0.985678149,0.770287681,0.873576345,0.078107881,0.496548327,5.358463362,357.962,3.6404,0.3454,0.772,0.027960973,0.347178893,0.54209675,0.678212322,5.37738391,420,0.86,22875.41229,36864.52979,26.909,4.743,1.65 +B753,Boeing,B757-300,1998,2,no,2,122470,101610,95270,64580,30690,0.777904793,0.527312811,0.250591982,189,38.06,3.76,0.019519474,0.906307767,7.664357672,7.593716886,1.005262025,0.759572707,0.87301803,0.077746352,0.522123205,5.260668861,357.962,3.6404,0.3454,0.772,0.030631737,0.355109179,0.54209675,0.678212322,5.884200369,430,0.86,22875.41229,36864.52979,26.909,4.743,1.65 +B762,Boeing,B767-200ER,1984,2,no,6,179169,136078,117934,82377,35557,0.658227707,0.459772617,0.19845509,283.3,47.57,5.03,0.022361435,0.852640133,7.987662902,6.962665875,1.012922549,0.718636663,0.871373991,0.076077449,0.50014418,5.891145984,504.4066667,4.8587,0.407266667,0.772,0.027161252,0.367680713,0.537596042,0.683456066,5.407506184,430,0.86,22875.41229,36864.52979,30.22716667,4.940833333,1.65 +B763,Boeing,B767-300,1995,2,no,2,158758,136078,126299,86069,40230,0.795544162,0.542139609,0.253404553,283.3,47.57,5.03,0.022361435,0.852640133,7.987662902,6.296852184,0.988567215,0.730450667,0.872804122,0.077119108,0.469638583,6.001519547,504.4066667,4.8587,0.407266667,0.772,0.02403592,0.353,0.537596042,0.683456066,5.537312075,431.0006562,0.86,22875.41229,36864.52979,30.22716667,4.940833333,1.65 +B764,Boeing,B767-400ER,1999,2,no,1,204116,158757,149685,103147,46538,0.733333007,0.505335202,0.227997805,283.3,51.92,5.03,0.018771397,0.852640133,9.515306742,7.202171898,1.015950634,0.72271456,0.869996123,0.074730057,0.543871305,6.148190272,512.7957895,4.861157895,0.399794737,0.772,0.027844828,0.361414229,0.533975,0.687584,5.831334305,450,0.86,22875.41229,36864.52979,30.55605263,5.1,1.65 +B772,Boeing,B777-200,1994,2,no,6,286900,206350,195030,135600,59430,0.679783897,0.47263855,0.207145347,427.8,60.93,6.2,0.020708613,0.851726902,8.678038569,6.461822217,0.987569999,0.767369197,0.873764241,0.078399473,0.495253823,6.781321287,781.2292857,6.885785714,0.5735,0.8106,0.024180523,0.367,0.490319375,0.730970427,5.71612393,431.0006562,0.89,24441.49186,36319.05391,37.69964286,7.018928571,1.65 +B773,Boeing,B777-300,1997,2,no,4,299370,237680,224530,159570,64960,0.750008351,0.533019341,0.21698901,427.8,60.93,6.2,0.020708613,0.851726902,8.678038569,7.06941142,1.002684301,0.759514113,0.872187708,0.076713703,0.51471757,6.864081938,744.7577778,6.869444444,0.561,0.8106,0.026557394,0.393961604,0.507218472,0.715573354,5.802646414,431.0006562,0.89,24441.49186,36319.05391,36.31444444,6.276111111,1.65 +B77L,Boeing,B777-200LR,2005,2,no,1,347450,223168,209107,145150,63957,0.601833357,0.417757951,0.184075407,427.8,64.8,6.2,0.018308947,0.851726902,9.81542777,6.503715019,0.985544142,0.772137202,0.873492551,0.077988704,0.519417863,7.585117015,1006.5,9.01,0.75,0.8106,0.02389309,0.386398306,0.4859725,0.73464544,5.820183704,431.0006562,0.89,24441.49186,36319.05391,40.985,7.21,1.65 +B77W,Boeing,B777-300ER,2002,2,no,1,351530,251290,237673,167820,69853,0.676110147,0.4773988,0.198711348,427.8,64.8,6.2,0.018308947,0.851726902,9.81542777,7.159075436,0.997868415,0.76653828,0.872013573,0.076372489,0.541566421,7.183146325,1027.8,9.38,0.76,0.8106,0.026449404,0.388746118,0.48893,0.73215776,5.59316908,431.0006562,0.89,24441.49186,36319.05391,42.24,7.08,1.65 +B788,Boeing,B787-8,2009,2,no,1,227930,172365,161025,117707,43318,0.706466898,0.516417321,0.190049577,377,60.12,5.77,0.018422293,0.846193133,9.587306101,6.382579903,0.968083144,0.783757191,0.873178246,0.077083447,0.508399177,8.025698576,633.0491892,4.822891892,0.453081081,0.815425,0.023810747,0.411614512,0.445062466,0.763508702,6.062664522,431.0006562,0.9,24977.42649,36140.62533,42.93635135,9.008243243,1.65 +B789,Boeing,B787-9,2013,2,no,1,254011,192777,181437,128850,52587,0.714287964,0.507261497,0.207026467,377,60.12,5.77,0.018422293,0.846193133,9.587306101,6.477888019,0.968258434,0.783684365,0.873156144,0.077053182,0.508801657,8.027179776,633.0491892,4.822891892,0.453081081,0.815425,0.023856026,0.412147079,0.445062466,0.763508702,6.129298314,431.0334646,0.9,24977.42649,36140.62533,42.93635135,9.008243243,1.65 +B78X,Boeing,B787-10,2017,2,no,,254011,201848,192776,135500,57276,0.758927763,0.533441465,0.225486298,377,60.12,5.77,0.018422293,0.846193133,9.587306101,6.607025807,0.970886833,0.78231171,0.872881338,0.076703182,0.512787007,7.704002339,688.56,5.332568421,0.474731579,0.815425,0.024318041,0.400356131,0.448435,0.76152064,6.188500149,411,0.9,24977.42649,36140.62533,46.44,8.86,1.65 +BCS1,Airbus,A220-100,2013,2,yes,,60781,51029,48987,35222,13765,0.805959099,0.579490301,0.226468798,115,32.5,3.505,0.023261586,0.898794024,9.184782609,7.341279884,0.960595004,0.776436689,0.872616965,0.075848076,0.575972879,6.185990497,200.8,1.438,0.148,0.753623188,0.030392966,0.364818967,0.3931525,0.78523744,6.230436775,410,0.82,20882.78822,37618.41516,36.1,11.29,1.65 +BCS3,Airbus,A220-200,2015,2,yes,,70896,61008,58060,37082,20978,0.818946062,0.523047845,0.295898217,115,32.5,3.505,0.023261586,0.898794024,9.184782609,7.724262518,0.963925925,0.775119863,0.872128778,0.075195994,0.585019236,6.055724131,200.8,1.438,0.148,0.753623188,0.031581624,0.365365479,0.3931525,0.78523744,6.261141077,410,0.82,20882.78822,37618.41516,36.1,11.29,1.65 +CRJ9,Bombardier,CRJ-9,1999,2,yes,0,38329,34065,32092,21350,10742,0.837277257,0.557019489,0.280257768,69,22.62,2.69,0.028284555,0.898794024,7.415426087,7.940977915,1.011391814,0.736978861,0.869436756,0.073972647,0.549943744,4.185393752,120.9433333,1.326366667,0.129766667,0.7527,0.034336494,0.304067923,0.5332925,0.68835296,5.960740978,410,0.85,22367.12483,37049.99171,23.44833333,5.13,1.65 +DC93,Boeing,DC-9-32,1967,2,no,0,48988,44906,39463,25789,13674,0.805564628,0.526435045,0.279129583,93,28.44,3.35,0.027749836,0.913545439,8.697135484,7.952009382,1.029517002,0.718504638,0.868319059,0.073625769,0.565164551,3.47919413,130.48,2.134,0.2732,0.7334,0.034308395,0.2565,0.626643333,0.556433529,4.641949038,370,0.84,21865.62405,37237.40235,16.31,1.026666667,1.65 +E135,Embraer,EMB-135LR,1995,2,no,0,20000,18500,15999,11500,4499,0.79995,0.575,0.22495,51.18,20.04,2.25,0.025211553,0.923879516,7.846846424,8.018356069,1.012322431,0.708748302,0.869299248,0.073869708,0.562009635,3.431268437,66.1,0.7178,0.0898,0.70445,0.036968374,0.27276541,0.5405725,0.68000224,5.917521821,370,0.78,18996.45555,38407.92089,17.22,4.81,1.65 +E145,Embraer,EMB-145LR,1995,2,no,0,22000,19300,17900,12114,5786,0.813636364,0.550636364,0.263,51.18,20.04,2.25,0.025211553,0.923879516,7.846846424,8.379769784,1.017505025,0.706378777,0.868482629,0.073274618,0.569734872,3.597812118,74.32,0.8244,0.095,0.70445,0.038245748,0.292084412,0.54262,0.67759456,5.917909369,370,0.78,18996.45555,38407.92089,19.06,4.72,1.65 +E170,Embraer,EMB-170LR,2002,2,yes,0,37200,32800,29800,20700,9100,0.801075269,0.556451613,0.244623656,72.72,25.3,3.15,0.031003453,0.923879516,8.802117712,8.103,1.005217924,0.744171061,0.869283909,0.073532873,0.598468911,4.066065719,120.114,1.31516,0.12908,0.7334,0.035430036,0.283999174,0.5332925,0.68835296,6.056766771,410,0.82,20882.78822,37618.41516,23.314,5.13,1.65 +E190,Embraer,EMB-190STD,2004,2,yes,,47790,43000,40800,27900,12900,0.853735091,0.583804143,0.269930948,86,27.71,2.74,0.019555011,0.923879516,8.928419767,7.898386381,0.99968373,0.769679725,0.870246567,0.074352897,0.594043088,4.6941615,167.4,1.74,0.176,0.757525,0.033846101,0.310223835,0.5342025,0.68732704,6.07089511,410,0.82,20882.78822,37618.41516,27.3,5.09,1.65 +E195,Embraer,EMB-195STD,2004,2,yes,0,48790,45000,42500,28700,13800,0.871080139,0.588235294,0.282844845,92.53,27.73,3,0.023408456,0.923879516,8.310309089,8.12816248,1.003277121,0.765946572,0.870141166,0.074388188,0.583581105,4.471913613,161.9811765,1.671294118,0.172823529,0.757525,0.034908937,0.310281044,0.5342025,0.68732704,6.07089511,410,0.82,20882.78822,37618.41516,26.53529412,5.09,1.65 +E290,Embraer,E190-E2,2016,2,no,,56400,49050,46700,33000,13700,0.828014184,0.585106383,0.242907801,110,33.72,3,0.0158306,0.923879516,10.33671273,6.992079637,0.949032729,0.805612509,0.873781408,0.077556026,0.57787765,6.546016199,185.58,1.3,0.14,0.758,0.029180534,0.367869793,0.3861,0.786904,6.267767387,410,0.82,20882.78822,37618.41516,33.27,11.6,1.65 +E295,Embraer,E195-E2,2017,2,no,,61500,54000,51850,35750,16100,0.843089431,0.581300813,0.261788618,110,35.12,3,0.014593635,0.923879516,11.21285818,7.518186583,0.955695668,0.804622027,0.872687085,0.075726997,0.613335059,6.348908893,200.6,1.42,0.14,0.758,0.031226955,0.360286236,0.39156,0.78564064,6.281663673,410,0.82,20882.78822,37618.41516,35.76,11.36,1.65 +E75L,Embraer,E170-200 (long wing),2002,2,yes,,40370,34100,32000,21890,10110,0.542234332,0.542234332,0.25043349,83,25,3,0.0288,0.923879516,7.530120482,7.971,1.001508411,0.741368946,0.870818124,0.075084185,0.556390672,3.87871406,120.114,1.31516,0.12908,0.733,0.034519925,0.283998994,0.5332925,0.68835296,6.057293054,410,0.82,20882.78822,37618.41516,23.314,5.13,1.65 +E75S,Embraer,E170-200 (short wing),2002,2,yes,,40370,34100,32000,21890,10110,0.542234332,0.542234332,0.25043349,83,25,3,0.0288,0.923879516,7.530120482,7.845214774,0.999386883,0.742337704,0.871132376,0.075370291,0.552407435,3.91652483,120.114,1.31516,0.12908,0.733,0.033926186,0.283867353,0.5332925,0.68835296,6.057293054,410,0.82,20882.78822,37618.41516,23.314,5.13,1.65 +GLF5,Gulfstream,G-550,1995,2,no,0,41277,34155,23587,21909,1678,0.571432032,0.530779853,0.040652179,105.56,28.5,2.5,0.015389351,0.906307767,7.694676014,6.702319588,0.99471301,0.76525366,0.872752056,0.077203567,0.508157359,5.5011112,137.54,1.494,0.166,0.772,0.029344031,0.367,0.5578625,0.658856,5.849906518,510,0.885,24176.14834,36408.88368,24.95,4.05,1.65 +MD82,Boeing,MD-82,1981,2,no,0,67812,58967,55338,35369,19969,0.816050257,0.521574353,0.294475904,112.3,32.85,3.35,0.020799307,0.923879516,9.60928317,8.955934197,1.034594007,0.714688042,0.866072122,0.0718649,0.612313936,3.987672179,185.48,2.621,0.2743,0.72,0.037613802,0.299388919,0.610813125,0.58259779,5.437458322,370,0.84,21865.62405,37237.40235,19.5075,1.7225,1.65 +MD83,Boeing,MD-83,1984,2,no,0,72575,63276,55338,36145,19193,0.762493972,0.498036514,0.264457458,112.3,32.85,3.35,0.020799307,0.923879516,9.60928317,8.85605389,1.046265541,0.708621624,0.866902498,0.073058432,0.62175399,3.897539841,193.04,2.708,0.2688,0.72,0.037907506,0.290478105,0.611325,0.581776,5.567055426,370,0.84,21865.62405,37237.40235,20.27,1.7,1.65 +RJ1H,BAESystems,RJ-100,1987,4,no,0,44225,40142,37421,25640,11781,0.846150367,0.579762578,0.26638779,77.3,26.34,3.5,0.035312994,0.965925819,8.975363519,9.769273679,1.023211827,0.681862045,0.868995494,0.074011851,0.636811428,3.247264845,124,1.4312,0.1812,0.65,0.042741457,0.274318931,0.533975,0.687584,5.677433606,350,0.734,16954.77401,39369.19067,13,5.1,1.65 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/engine_loader.py b/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/engine_loader.py similarity index 83% rename from skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/engine_loader.py rename to skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/engine_loader.py index 397272f5de..76e049c96e 100644 --- a/skdecide/hub/domain/flight_planning/aircraft_performance/poll_schumann_utils/engine_loader.py +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/utils/poll_schumann_utils/engine_loader.py @@ -2,8 +2,11 @@ import pandas as pd -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters import ( - aircraft_parameters as arc_params, +from .aircraft_parameters import ( + crossover_pressure_altitude, + impact_pressure_max_operating_limits, + turbine_entry_temperature_at_max_continuous_climb, + turbine_entry_temperature_at_max_take_off, ) PS_FILE_PATH = str(Path(__file__).parent / "data" / "aircraft_engine_params.csv") @@ -85,16 +88,14 @@ def load_aircraft_engine_params(actype: str): df["j_3"] = 70.0 df["f_00"] = df["f_00"] * 1_000.0 - df["tet_mto"] = arc_params.turbine_entry_temperature_at_max_take_off( + df["tet_mto"] = turbine_entry_temperature_at_max_take_off( df["Year_of_first_flight"].values ) - df["p_i_max"] = arc_params.impact_pressure_max_operating_limits( - df["max_mach_num"].values - ) - df["tet_mcc"] = arc_params.turbine_entry_temperature_at_max_continuous_climb( + df["p_i_max"] = impact_pressure_max_operating_limits(df["max_mach_num"].values) + df["tet_mcc"] = turbine_entry_temperature_at_max_continuous_climb( df["tet_mto"].values ) - df["p_inf_co"] = arc_params.crossover_pressure_altitude( + df["p_inf_co"] = crossover_pressure_altitude( df["max_mach_num"].values, df["p_i_max"].values ) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/atmosphere_model_enum.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/atmosphere_model_enum.py new file mode 100644 index 0000000000..c5b9e80cfe --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/atmosphere_model_enum.py @@ -0,0 +1,9 @@ +from enum import Enum + + +class AtmosphereModelEnum(Enum): + """ + Enum referencing all the implemented atmosphere models + """ + + ISA = 1 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/atmosphere_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/atmosphere_service.py new file mode 100644 index 0000000000..b20c7730f1 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/atmosphere_service.py @@ -0,0 +1,100 @@ +import math + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.four_dimensions_state import ( + FourDimensionsState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.weather_state import ( + WeatherState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.atmosphere_model_enum import ( + AtmosphereModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.isa_atmosphere_service import ( + ISAAtmosphereService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.atmosphere_settings_interface import ( + AtmosphereSettings, +) + + +class AtmosphereService: + """ + Class atmosphere variables computations and constants + """ + + # FMS definition of perfect fluid constants + _MU0 = 17.82 * math.pow(10, -6) # Dynamic viscosity Pa / s + _R = 287.053 + _GAMMA = 1.4 + + def __init__(self): + # Retrieve all the atmosphere services + self.all_atmosphere_services = {AtmosphereModelEnum.ISA: ISAAtmosphereService()} + + def retrieve_weather_state( + self, + atmosphere_settings: AtmosphereSettings, + four_dimensions_state: FourDimensionsState, + ) -> WeatherState: + """ + From the 4D state location and atmosphere settings, compute the weather state using the appropriate atmosphere service + :param atmosphere_settings: Settings defining the atmosphere (type, constants...) + :param four_dimensions_state: 4D state (zp, location, time) + :return: Weather state (Temperature, pressure...) + """ + weather_state = self.all_atmosphere_services[ + atmosphere_settings.atmosphere_model_type + ].retrieve_weather_state( + atmosphere_settings=atmosphere_settings, + four_dimensions_state=four_dimensions_state, + ) + + weather_state.rho_kg_m3 = self.get_volume_mass( + static_pressure_pa=weather_state.static_pressure_pa, + static_temperature_k=weather_state.static_temperature_k, + ) + weather_state.mu_pa_s = self.get_dynamic_viscosity( + static_temperature_k=weather_state.static_temperature_k + ) + weather_state.nu_m2_s = self.get_kinematic_viscosity( + static_pressure_pa=weather_state.static_pressure_pa, + static_temperature_k=weather_state.static_temperature_k, + ) + + return weather_state + + def get_dynamic_viscosity(self, static_temperature_k: float) -> float: + """ + FMS formula to compute Mu + :param static_temperature_k: static air temperature (K) + :return: Dynamic viscosity value + """ + + return ( + 0.0834434 + * self._MU0 + * math.pow(static_temperature_k, 1.5) + / (static_temperature_k + 110.4) + ) + + def get_volume_mass(self, static_pressure_pa: float, static_temperature_k: float): + """ + Density computation of a perfect gaz + :param static_pressure_pa: + :param static_temperature_k: + :return: + """ + return static_pressure_pa / (self._R * static_temperature_k) + + def get_kinematic_viscosity( + self, static_pressure_pa: float, static_temperature_k: float + ): + return self.get_dynamic_viscosity( + static_temperature_k=static_temperature_k + ) / self.get_volume_mass( + static_pressure_pa=static_pressure_pa, + static_temperature_k=static_temperature_k, + ) + + def get_sound_celerity(self, static_temperature_k: float): + return math.sqrt(self._GAMMA * self._R * static_temperature_k) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/atmosphere_service_interface.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/atmosphere_service_interface.py new file mode 100644 index 0000000000..7ae49d89b9 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/atmosphere_service_interface.py @@ -0,0 +1,44 @@ +from abc import ABC, abstractmethod + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.four_dimensions_state import ( + FourDimensionsState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.weather_state import ( + WeatherState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.atmosphere_model_enum import ( + AtmosphereModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.atmosphere_settings_interface import ( + AtmosphereSettings, +) + + +class AtmopshereServiceInterface(ABC): + """ + Interface defining atmosphere services template + """ + + @property + @abstractmethod + def atmosphere_model_type(self) -> AtmosphereModelEnum: + """ + Property defining the type of modelling + """ + raise NotImplementedError + + @abstractmethod + def retrieve_weather_state( + self, + atmosphere_settings: AtmosphereSettings, + four_dimensions_state: FourDimensionsState, + ) -> WeatherState: + """ + :param atmosphere_settings: + :param four_dimensions_state: + :return: + """ + raise NotImplementedError diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/isa_atmosphere_service.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/isa_atmosphere_service.py new file mode 100644 index 0000000000..336e89230f --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/service/isa_atmosphere_service.py @@ -0,0 +1,143 @@ +from typing import Optional + +import numpy as np + +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.four_dimensions_state import ( + FourDimensionsState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.weather_state import ( + WeatherState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.atmosphere_model_enum import ( + AtmosphereModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service_interface import ( + AtmopshereServiceInterface, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.isa_atmosphere_settings import ( + IsaAtmosphereSettings, +) + + +class ISAAtmosphereService(AtmopshereServiceInterface): + """ + Implementation of the ISA atmosphere + """ + + atmosphere_model_type = AtmosphereModelEnum.ISA + + ISA_T0_K = 288.15 + TEMP_GRAD = -1.9812 / 1000 # gradient temperature before tropopause + DEFAULT_TROPOPAUSE_FT = 36089 + + def retrieve_weather_state( + self, + atmosphere_settings: IsaAtmosphereSettings, + four_dimensions_state: FourDimensionsState, + ) -> WeatherState: + """ + From the aircraft state location and atmosphere settings, compute the weather state using the appropriate atmosphere service + :param atmosphere_settings: Settings defining the atmosphere (type, constants...) + :param four_dimensions_state: 4D state (zp, location, time) + :return: Weather state (Temperature, pressure...) + """ + alt_ft = four_dimensions_state.zp_ft + + if alt_ft is None: + raise Exception( + "Aircraft state zp must be initiated for isa atmosphere computation" + ) + + isa_temperature_k = self.__isa_temperature_k( + altitude_ft=alt_ft, tropo_ft=atmosphere_settings.tropopause_alt_ft + ) + + pressure_pa = self.__pressure(altitude_ft=alt_ft) + + return WeatherState( + static_temperature_k=isa_temperature_k + atmosphere_settings.d_isa, + static_pressure_pa=pressure_pa, + d_isa=atmosphere_settings.d_isa, + tailwind_m_per_sec=atmosphere_settings.tailwind_m_per_sec, + ) + + def __isa_temperature_k( + self, altitude_ft: float, tropo_ft: Optional[float] = None + ) -> float: + """Compute the temperature at the given altitude using a custom value for the tropopause altitude + Args: + altitude_ft (float): user altitude at which the temperature will be computed + tropo_ft (float): user custom tropopause altitude + Returns: + float: isa temperature (K) + """ + + return self.ISA_T0_K + self.TEMP_GRAD * min( + altitude_ft, + tropo_ft if tropo_ft is not None else self.DEFAULT_TROPOPAUSE_FT, + ) + + def __pressure(self, altitude_ft=0.0): + """ + Compute Static Pressure in Pa from altitude in ft + Remark: altitude is optional and can be provided as a float, + a numpy or a pd.series + :param altitude_ft: altitude (ft) (default : 0) + :return: pressure (Pa) + """ + + """ + The atmosphere is split into 5 zones: + - zone 1: pressure height up to 11000. m + - zone 2: pressure height btw 11000. to 20000. m + - zone 3: pressure height btw 20000. to 32000. m + - zone 4: pressure height btw 32000. to 47000. m + - zone 5: pressure height btw above 47000. m + on zone 1,3,4, pressure is computed using coefficient C, D, E: + pressure = (C + D * pressure height)^E + on zone 2 and 5, pressure is computed using coefficient F, G: + temperature = F * exp(G * pressure height) + """ + + press_constant = {} + press_constant["zone1"] = {"C": 8.9619638, "D": -0.20216125e-3, "E": 5.2558797} + press_constant["zone2"] = {"F": 128244.5, "G": -0.15768852e-3} + press_constant["zone3"] = {"C": 0.70551848, "D": 3.5876861e-6, "E": -34.163218} + press_constant["zone4"] = {"C": 0.34926867, "D": 7.0330980e-6, "E": -12.201149} + press_constant["zone5"] = {"F": 41828.420, "G": -0.12622656e-3} + + altitude_m = altitude_ft * 0.3048 + + if altitude_m < 11000.0: + zone = "zone1" + pressure_pa = np.power( + press_constant[zone]["C"] + press_constant[zone]["D"] * altitude_m, + press_constant[zone]["E"], + ) + + elif altitude_m < 20000.0: + zone = "zone2" + pressure_pa = press_constant[zone]["F"] * np.exp( + press_constant[zone]["G"] * altitude_m + ) + + elif altitude_m < 32000: + zone = "zone3" + pressure_pa = np.power( + press_constant[zone]["C"] + press_constant[zone]["D"] * altitude_m, + press_constant[zone]["E"], + ) + + elif altitude_m < 47000: + zone = "zone4" + pressure_pa = np.power( + press_constant[zone]["C"] + press_constant[zone]["D"] * altitude_m, + press_constant[zone]["E"], + ) + else: + zone = "zone5" + pressure_pa = press_constant[zone]["F"] * np.exp( + press_constant[zone]["G"] * altitude_m + ) + + return float(pressure_pa) diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/__init__.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/atmosphere_settings_interface.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/atmosphere_settings_interface.py new file mode 100644 index 0000000000..a58007f988 --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/atmosphere_settings_interface.py @@ -0,0 +1,15 @@ +from abc import ABC +from dataclasses import dataclass + +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.atmosphere_model_enum import ( + AtmosphereModelEnum, +) + + +@dataclass +class AtmosphereSettings(ABC): + """ + Abstract dataclass for aerodynamics service settings + """ + + atmosphere_model_type: AtmosphereModelEnum = None diff --git a/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/isa_atmosphere_settings.py b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/isa_atmosphere_settings.py new file mode 100644 index 0000000000..3d7659fcff --- /dev/null +++ b/skdecide/hub/domain/flight_planning/aircraft_performance/weather/settings/isa_atmosphere_settings.py @@ -0,0 +1,18 @@ +from dataclasses import dataclass + +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.atmosphere_model_enum import ( + AtmosphereModelEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.atmosphere_settings_interface import ( + AtmosphereSettings, +) + + +@dataclass +class IsaAtmosphereSettings(AtmosphereSettings): + tropopause_alt_ft: float = None # default tropopause ft + d_isa: float = 0 + tailwind_m_per_sec: float = 0 + + def __post_init__(self): + self.atmosphere_model_type = AtmosphereModelEnum.ISA diff --git a/skdecide/hub/domain/flight_planning/domain.py b/skdecide/hub/domain/flight_planning/domain.py index b05edf607f..5e20c9fab3 100644 --- a/skdecide/hub/domain/flight_planning/domain.py +++ b/skdecide/hub/domain/flight_planning/domain.py @@ -3,31 +3,59 @@ from enum import Enum # data and math -from math import asin, atan2, cos, radians, sin, sqrt +from math import asin, atan, atan2, cos, radians, sin, sqrt # typing -from typing import Any, Optional, Union +from typing import Any, Callable, Dict, Optional, Tuple, Type, Union # plotting import matplotlib.pyplot as plt +import networkx as nx +import numpy as np import pandas as pd # aircraft performance model from openap.extra.aero import bearing as aero_bearing -from openap.extra.aero import distance, ft, kts, latlon, mach2tas +from openap.extra.aero import ( + cas2mach, + cas2tas, + distance, + ft, + kts, + latlon, + mach2cas, + mach2tas, + nm, +) from openap.extra.nav import airport -from openap.prop import aircraft from pygeodesy.ellipsoidalVincenty import LatLon from skdecide import DeterministicPlanningDomain, ImplicitSpace, Solver, Space, Value from skdecide.builders.domain import Renderable, UnrestrictedActions - -# custom aircraft performance model -from skdecide.hub.domain.flight_planning.aircraft_performance.base import ( - AircraftPerformanceModel, +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.bean.atmos_isa import ( + disa_alt_temp, + temperature, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service.aerodynamics_service import ( + AerodynamicsService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service.propulsion_service import ( + PropulsionService, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, +) +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, ) -from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, +from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.isa_atmosphere_settings import ( + IsaAtmosphereSettings, ) from skdecide.hub.domain.flight_planning.flightplanning_utils import ( plot_full, @@ -39,21 +67,12 @@ from skdecide.hub.domain.flight_planning.weather_interpolator.weather_tools.interpolator.GenericInterpolator import ( GenericWindInterpolator, ) -from skdecide.hub.space.gym import EnumSpace, ListSpace, MultiDiscreteSpace +from skdecide.hub.domain.flight_planning.weather_interpolator.weather_tools.interpolator.WeatherInterpolator import ( + WeatherForecastInterpolator, +) +from skdecide.hub.space.gym import DiscreteSpace, EnumSpace, ListSpace, TupleSpace from skdecide.utils import load_registered_solver -try: - from IPython.display import clear_output as ipython_clear_output -except ImportError: - ipython_available = False -else: - ipython_available = True - - -def clear_output(wait=True): - if ipython_available: - ipython_clear_output(wait=wait) - class WeatherDate: day: int @@ -183,17 +202,18 @@ class State: """ trajectory: pd.DataFrame - pos: tuple[int, int, int] + id: Dict[str, float] - def __init__(self, trajectory, pos): + def __init__(self, trajectory, id): """Initialisation of a state - # Parameters + Args: trajectory : Trajectory information of the flight - pos : Current position in the airways graph + id: Node id in the airway graph """ self.trajectory = trajectory - self.pos = pos + self.id = id + if trajectory is not None: self.mass = trajectory.iloc[-1]["mass"] self.alt = trajectory.iloc[-1]["alt"] @@ -204,12 +224,11 @@ def __init__(self, trajectory, pos): self.time = None def __hash__(self): - # print(self.pos, self.mass, self.alt, self.time) - return hash((self.pos, int(self.mass), self.alt, int(self.time))) + return hash((self.id, int(self.mass), self.alt, int(self.time))) def __eq__(self, other): return ( - self.pos == other.pos + self.id == other.id and int(self.mass) == int(other.mass) and self.alt == other.alt and int(self.time) == int(other.time) @@ -217,7 +236,7 @@ def __eq__(self, other): def __ne__(self, other): return ( - self.pos != other.pos + self.id != other.id or int(self.mass) != int(other.mass) or self.alt != other.alt or int(self.time) != int(other.time) @@ -225,7 +244,7 @@ def __ne__(self, other): def __str__(self): return f"[{self.trajectory.iloc[-1]['ts']:.2f} \ - {self.pos} \ + {self.id} \ {self.trajectory.iloc[-1]['alt']:.2f} \ {self.trajectory.iloc[-1]['mass']:.2f}]" @@ -235,9 +254,9 @@ class H_Action(Enum): Horizontal action that can be perform by the aircraft """ - up = -1 + left = -1 straight = 0 - down = 1 + right = 1 class V_Action(Enum): @@ -362,7 +381,7 @@ class FlightPlanningDomain( T_state = State # Type of states T_observation = State # Type of observations - T_event = tuple[H_Action, V_Action] # Type of events + T_event = Tuple[H_Action, V_Action] # Type of events T_value = float # Type of transition values (rewards or costs) T_predicate = bool # Type of transition predicates (terminal states) T_info = None # Type of additional information in environment outcome @@ -372,25 +391,23 @@ def __init__( self, origin: Union[str, tuple], destination: Union[str, tuple], - actype: str, + aircraft_state: AircraftState, + cruise_height_min: float = 32_000.0, + cruise_height_max: float = 38_000.0, weather_date: Optional[WeatherDate] = None, - wind_interpolator: Optional[GenericWindInterpolator] = None, objective: str = "fuel", heuristic_name: str = "fuel", - perf_model_name: str = "openap", + wind_interpolator: Optional[GenericWindInterpolator] = None, constraints=None, nb_forward_points: int = 41, nb_lateral_points: int = 11, nb_vertical_points: Optional[int] = None, - take_off_weight: Optional[int] = None, fuel_loaded: Optional[float] = None, fuel_loop: bool = False, - fuel_loop_solver_cls: Optional[type[Solver]] = None, - fuel_loop_solver_kwargs: Optional[dict[str, Any]] = None, + fuel_loop_solver_cls: Optional[Type[Solver]] = None, + fuel_loop_solver_kwargs: Optional[Dict[str, Any]] = None, fuel_loop_tol: float = 1e-3, - climbing_slope: Optional[float] = None, - descending_slope: Optional[float] = None, - graph_width: Optional[str] = None, + graph_width: Optional[str] = "medium", res_img_dir: Optional[str] = None, starting_time: float = 3_600.0 * 8.0, ): @@ -401,70 +418,94 @@ def __init__( ICAO code of the airport, or a tuple (lat,lon,alt), of the origin of the flight plan. Altitude should be in ft destination (Union[str, tuple]): ICAO code of the airport, or a tuple (lat,lon,alt), of the destination of the flight plan. Altitude should be in ft - actype (str): - Aircarft type describe in openap datas (https://github.com/junzis/openap/tree/master/openap/data/aircraft) + aircraft_state (AircraftState) + Initial aircraft state. + cruise_height_min (float) + Minimum cruise height in ft + cruise_height_max (float) + Maximum cruise height in ft weather_date (WeatherDate, optional): Date for the weather, needed for days management. If None, no wind will be applied. - wind_interpolator (GenericWindInterpolator, optional): - Wind interpolator for the flight plan. If None, create one from the specified weather_date. - The data is either already present locally or be downloaded from https://www.ncei.noaa.gov objective (str, optional): Cost function of the flight plan. It can be either fuel, distance or time. Defaults to "fuel". heuristic_name (str, optional): Heuristic of the flight plan, it will guide the aircraft through the graph. It can be either fuel, distance or time. Defaults to "fuel". - perf_model_name (str, optional): - Aircraft performance model used in the flight plan. It can be either openap or PS (Poll-Schumann). Defaults to "openap". + wind_interpolator (GenericWindInterpolator, optional): + Wind interpolator for the flight plan. If None, create one from the specified weather_date. + The data is either already present locally or be downloaded from https://www.ncei.noaa.gov constraints (_type_, optional): Constraints dictionnary (keyValues : ['time', 'fuel'] ) to be defined in for the flight plan. Defaults to None. - nb_points_forward (int, optional): + nb_forward_points (int, optional): Number of forward nodes in the graph. Defaults to 41. - nb_points_lateral (int, optional): + nb_lateral_points (int, optional): Number of lateral nodes in the graph. Defaults to 11. - nb_points_vertical (int, optional): + nb_vertical_points (int, optional): Number of vertical nodes in the graph. Defaults to None. - take_off_weight (int, optional): - Take off weight of the aircraft. Defaults to None. fuel_loaded (float, optional): - Fuel loaded in the aricraft for the flight plan. Defaults to None. + Fuel loaded in the airscraft for the flight plan. Defaults to None. fuel_loop (bool, optional): Boolean to create a fuel loop to optimize the fuel loaded for the flight. Defaults to False fuel_loop_solver_cls (type[Solver], optional): Solver class used in the fuel loop. Defaults to LazyAstar. - fuel_loop_solver_kwargs (dict[str, Any], optional): + fuel_loop_solver_kwargs (Dict[str, Any], optional): Kwargs to initialize the solver used in the fuel loop. - climbing_slope (float, optional): - Climbing slope of the aircraft, has to be between 10.0 and 25.0. Defaults to None. - descending_slope (float, optional): - Descending slope of the aircraft, has to be between 10.0 and 25.0. Defaults to None. graph_width (str, optional): - Airways graph width, in ["tiny", "small", "normal", "large", "xlarge"]. Defaults to None + Airways graph width, in ["small", "medium", "large", "xlarge"]. Defaults to None res_img_dir (str, optional): Directory in which images will be saved. Defaults to None starting_time (float, optional): Start time of the flight, in seconds. Defaults to 8AM (3_600.0 * 8.0) """ + self.aircraft_state = aircraft_state + self.cruise_height_min = cruise_height_min + self.cruise_height_max = cruise_height_max + + # other objects for a/c performance + self.atmosphere_service = AtmosphereService() + self.propulsion_service = PropulsionService() + self.aerodynamics_service = AerodynamicsService() + + self.propulsion_settings = self.propulsion_service.init_settings( + model_path=self.aircraft_state.model_type, + performance_model_type=self.aircraft_state.performance_model_type, + ) + self.aerodynamics_settings = self.aerodynamics_service.init_settings( + model_path=self.aircraft_state.model_type, + performance_model_type=self.aircraft_state.performance_model_type, + ) + + self.alt_crossover = self.aerodynamics_service.compute_crossover( + aircraft_state=self.aircraft_state, + aerodynamics_settings=self.aerodynamics_settings, + ) # Initialisation of the origin and the destination self.origin, self.destination = origin, destination if isinstance(origin, str): # Origin is an airport ap1 = airport(origin) - self.lat1, self.lon1, self.alt1 = ap1["lat"], ap1["lon"], ap1["alt"] + self.lat1, self.lon1, self.alt1 = ( + ap1["lat"], + ap1["lon"], + ap1["alt"], + ) # altitude in feet else: # Origin is geographic coordinates self.lat1, self.lon1, self.alt1 = origin if isinstance(destination, str): # Destination is an airport ap2 = airport(destination) - self.lat2, self.lon2, self.alt2 = ap2["lat"], ap2["lon"], ap2["alt"] + self.lat2, self.lon2, self.alt2 = ( + ap2["lat"], + ap2["lon"], + ap2["alt"], + ) # altitude in feet else: # Destination is geographic coordinates self.lat2, self.lon2, self.alt2 = destination - self.start_time = starting_time - # Retrieve the aircraft datas in openap library - self.actype = actype - self.ac = aircraft(actype) - self.mach = self.ac["cruise"]["mach"] + self.aircraft_state.mach = cas2mach( + self.aircraft_state.cas_climb_kts * kts, h=self.alt1 * ft + ) # Initialisation of the objective & heuristic, the constraints and the wind interpolator if heuristic_name in ( @@ -491,19 +532,6 @@ def __init__( if wind_interpolator is None: self.weather_interpolator = self.get_weather_interpolator() - # Build network between airports - if graph_width: - all_graph_width = { - "tiny": 0.5, - "small": 0.75, - "normal": 1.0, - "large": 1.5, - "xlarge": 2.0, - } - graph_width = all_graph_width[graph_width] - else: - graph_width = 1.0 - self.nb_forward_points = nb_forward_points self.nb_lateral_points = nb_lateral_points @@ -511,17 +539,18 @@ def __init__( self.nb_vertical_points = nb_vertical_points else: self.nb_vertical_points = ( - int((self.ac["limits"]["ceiling"] - self.ac["cruise"]["height"]) / 1000) - + 1 + int((cruise_height_max - cruise_height_min) / 1000) + 1 ) + self.network = self.set_network( - LatLon(self.lat1, self.lon1, self.alt1 * ft), # alt ft -> meters - LatLon(self.lat2, self.lon2, self.alt2 * ft), # alt ft -> meters - self.nb_forward_points, - self.nb_lateral_points, - self.nb_vertical_points, - descending_slope=descending_slope, - climbing_slope=climbing_slope, + p0=LatLon(self.lat1, self.lon1, self.alt1 * ft), # alt ft -> meters + p1=LatLon(self.lat2, self.lon2, self.alt2 * ft), # alt ft -> meters + nb_forward_points=self.nb_forward_points, + nb_lateral_points=self.nb_lateral_points, + nb_vertical_points=self.nb_vertical_points, + cas_climb=self.aircraft_state.cas_climb_kts, + mach_cruise=self.aircraft_state.mach_cruise, + cas_descent=self.aircraft_state.cas_descent_kts, graph_width=graph_width, ) @@ -538,7 +567,9 @@ def __init__( fuel_loaded = fuel_optimisation( origin=origin, destination=destination, - actype=self.actype, + aircraft_state=self.aircraft_state, + cruise_height_min=cruise_height_min, + cruise_height_max=cruise_height_max, constraints=constraints, weather_date=weather_date, solver_cls=fuel_loop_solver_cls, @@ -546,105 +577,122 @@ def __init__( fuel_tol=fuel_loop_tol, ) # Adding fuel reserve (but we can't put more fuel than maxFuel) - fuel_loaded = min(1.1 * fuel_loaded, self.ac["limits"]["MFC"]) + fuel_loaded = min(1.1 * fuel_loaded, aircraft_state.MFC) elif fuel_loaded: self.constraints["fuel"] = ( 0.97 * fuel_loaded ) # Update of the maximum fuel there is to be used else: - fuel_loaded = self.ac["limits"]["MFC"] + fuel_loaded = aircraft_state.MFC self.fuel_loaded = fuel_loaded - assert ( - fuel_loaded <= self.ac["limits"]["MFC"] - ) # Ensure fuel loaded <= fuel capacity - - aircraft_params = load_aircraft_engine_params(actype) + assert fuel_loaded <= aircraft_state.MFC # Ensure fuel loaded <= fuel capacity self.start = State( - pd.DataFrame( + trajectory=pd.DataFrame( [ { "ts": self.start_time, "lat": self.lat1, "lon": self.lon1, - "mass": ( - aircraft_params["amass_mtow"] - if take_off_weight is None - else take_off_weight - - 0.8 * (self.ac["limits"]["MFC"] - self.fuel_loaded) - ), # Here we compute the weight difference between the fuel loaded and the fuel capacity - "mach": self.mach, + "mass": self.aircraft_state.gw_kg + - 0.8 * (self.aircraft_state.MFC - self.fuel_loaded), + "cas": self.aircraft_state.cas_climb_kts, + "mach": cas2mach( + self.aircraft_state.cas_climb_kts * kts, h=self.alt1 * ft + ), + "speed_type": "CAS", "fuel": 0.0, "alt": self.alt1, + "phase": "climb", } ] ), - (0, self.nb_lateral_points // 2, 0), + id=0, ) - self.perf_model = AircraftPerformanceModel(actype, perf_model_name) - self.perf_model_name = perf_model_name - self.res_img_dir = res_img_dir - self.cruising = self.alt1 * ft >= self.ac["cruise"]["height"] * 0.98 # Class functions - def _get_next_state(self, memory: D.T_state, action: D.T_event) -> D.T_state: """Compute the next state - # Parameters + Args: memory (D.T_state): The current state action (D.T_event): The action to perform - # Returns + Returns: D.T_state: The next state """ - trajectory = memory.trajectory.copy() - # Set intermediate destination point - next_x, next_y, next_z = memory.pos - - next_x += 1 + # Get current node information + current_node_id = memory.id + current_height = self.network.nodes[current_node_id]["height"] + current_heading = self.network.nodes[current_node_id]["heading"] + current_phase = self.network.nodes[current_node_id]["phase"] + current_speed = self.network.nodes[current_node_id]["speed"] + current_speed_type = self.network.nodes[current_node_id]["speed_type"] + + # Get successors information + node_successors = list(self.network.successors(current_node_id)) + successors_heights = np.array( + [self.network.nodes[node_id]["height"] for node_id in node_successors] + ) + successors_headings = np.array( + [self.network.nodes[node_if]["heading"] for node_if in node_successors] + ) - if action[0] == H_Action.up: - next_y += 1 - if action[0] == H_Action.down: - next_y -= 1 - if action[1] == V_Action.climb: - next_z += 1 - if action[1] == V_Action.descent: - next_z -= 1 + # Horizontal actions + if action[0].name == "straight": + index_headings = np.where(successors_headings == current_heading)[0] + elif action[0].name == "right": + index_headings = np.where(successors_headings > current_heading)[0] + elif action[0].name == "left": + index_headings = np.where(successors_headings < current_heading)[0] + else: + raise ValueError("The action is not recognized.") + + # Vertical actions + if action[1].name == "cruise": + index_heights = np.where(successors_heights == current_height)[0] + elif action[1].name == "climb": + index_heights = np.where(successors_heights > current_height)[0] + elif action[1].name == "descent": + index_heights = np.where(successors_heights < current_height)[0] + else: + raise ValueError("The action is not recognized.") - # Aircraft stays on the network - if ( - next_x >= self.nb_forward_points - or next_y < 0 - or next_y >= self.nb_lateral_points - or next_z < 0 - or next_z >= self.nb_vertical_points - ): + if len(index_headings) == 0 or len(index_heights) == 0: return memory - # Concatenate the two trajectories - - to_lat = self.network[next_x][next_y][next_z].lat - to_lon = self.network[next_x][next_y][next_z].lon - to_alt = ( - self.network[next_x][next_y][next_z].height / ft - ) # We compute the flight with altitude in ft, whereas the altitude in the network is in meters according to LatLon - - self.cruising = ( - to_alt * ft >= self.ac["cruise"]["height"] * 0.98 - ) # Check if the plane will be cruising in the next state - trajectory = self.flying(trajectory.tail(1), (to_lat, to_lon, to_alt)) + # Compute the intersection of the indexes to get the next node to reach + index = np.intersect1d(index_headings, index_heights) + if len(index) == 0: + return memory + else: + index = index[0] + + # Get the next node information + next_node = node_successors[index] + to_lat = self.network.nodes[next_node]["lat"] + to_lon = self.network.nodes[next_node]["lon"] + to_alt = self.network.nodes[next_node]["height"] / ft + + # Compute the next trajectory + trajectory = self.flying( + trajectory.tail(1), + (to_lat, to_lon, to_alt), + current_phase, + current_speed, + current_speed_type, + ) + # Update the next state state = State( pd.concat([memory.trajectory, trajectory], ignore_index=True), - (next_x, next_y, next_z), + next_node, ) return state @@ -652,20 +700,21 @@ def _get_transition_value( self, memory: D.T_state, action: D.T_event, - next_state: Optional[D.T_state] = None, + next_state: D.T_state, ) -> Value[D.T_value]: """ Get the value (reward or cost) of a transition. Set cost to distance travelled between points - # Parameters + Args: memory (D.T_state): The current state action (D.T_event): The action to perform next_state (Optional[D.T_state], optional): The next state. Defaults to None. - # Returns + Returns: Value[D.T_value]: Cost to go from memory to next state """ + # print(f"Old ID: {memory.id}, New ID: {next_state.id}") assert memory != next_state, "Next state is the same as the current state" if self.objective == "distance": cost = LatLon.distanceTo( @@ -705,16 +754,16 @@ def _get_goals_(self) -> Space[D.T_observation]: Set the end position as goal. """ - return ImplicitSpace(lambda x: x.pos[0] == self.nb_forward_points - 1) + return ImplicitSpace(lambda x: len(list(self.network.successors(x.id))) == 0) def _get_terminal_state_time_fuel(self, state: State) -> dict: """ Get the domain terminal state information to compare with the constraints - # Parameters + Args: state (State): terminal state to retrieve the information on fuel and time. - # Returns + Returns: dict: dictionnary containing both fuel and time information. """ fuel = 0.0 @@ -736,33 +785,55 @@ def _is_terminal(self, state: State) -> D.T_predicate: Stop an episode only when goal reached. """ - return state.pos[0] == self.nb_forward_points - 1 + current_node_id = state.id + # The state is terminal if it does not have any successors + return len(list(self.network.successors(current_node_id))) == 0 def _get_applicable_actions_from(self, memory: D.T_state) -> Space[D.T_event]: """ Get the applicable actions from a state. """ - x, y, z = memory.pos + # Get current node information + current_node_id = memory.id + current_height = self.network.nodes[current_node_id]["height"] + current_heading = self.network.nodes[current_node_id]["heading"] + + # Get successors information + node_successors = list(self.network.successors(current_node_id)) + successors_heights = np.array( + [self.network.nodes[node_id]["height"] for node_id in node_successors] + ) + successors_headings = np.array( + [self.network.nodes[node_if]["heading"] for node_if in node_successors] + ) + + # V_Action + index_climb = (np.where(successors_heights > current_height)[0], V_Action.climb) + index_descend = ( + np.where(successors_heights < current_height)[0], + V_Action.descent, + ) + index_cruise = ( + np.where(successors_heights == current_height)[0], + V_Action.cruise, + ) + # H_Action + index_straight = ( + np.where(successors_headings == current_heading), + H_Action.straight, + ) + index_right = (np.where(successors_headings > current_heading), H_Action.right) + index_left = (np.where(successors_headings < current_heading), H_Action.left) space = [] - if x < self.nb_forward_points - 1: - space.append((H_Action.straight, V_Action.cruise)) - if z < self.nb_vertical_points - 1 and self.cruising: - space.append((H_Action.straight, V_Action.climb)) - if z > 0 and self.cruising: - space.append((H_Action.straight, V_Action.descent)) - if y + 1 < self.nb_lateral_points: - space.append((H_Action.up, V_Action.cruise)) - if z < self.nb_vertical_points - 1 and self.cruising: - space.append((H_Action.up, V_Action.climb)) - if z > 0 and self.cruising: - space.append((H_Action.up, V_Action.descent)) - if y > 0: - space.append((H_Action.down, V_Action.cruise)) - if z < self.nb_vertical_points - 1 and self.cruising: - space.append((H_Action.down, V_Action.climb)) - if z > 0 and self.cruising: - space.append((H_Action.down, V_Action.descent)) + + for v_actions in [index_climb, index_descend, index_cruise]: + for h_actions in [index_straight, index_left, index_right]: + if len(v_actions[0]) > 0 and len(h_actions[0]) > 0: + # Compute intersection of the indexes + index = np.intersect1d(v_actions[0], h_actions[0]) + if len(index) > 0: + space.append((h_actions[1], v_actions[1])) return ListSpace(space) @@ -776,15 +847,18 @@ def _get_observation_space_(self) -> Space[D.T_observation]: """ Define observation space. """ - return MultiDiscreteSpace( - [self.nb_forward_points, self.nb_lateral_points, self.nb_vertical_points] + return TupleSpace( + ( + DiscreteSpace(self.network.number_of_nodes()), + DiscreteSpace(self.network.number_of_edges()), + ) ) def _render_from(self, memory: State, **kwargs: Any) -> Any: """ Render visually the map. - # Returns + Returns: matplotlib figure """ return plot_trajectory( @@ -810,6 +884,25 @@ def heuristic(self, s: D.T_state, heuristic_name: str = None) -> Value[D.T_value # current position pos = s.trajectory.iloc[-1] + self.aircraft_state.update_settings( + gw_kg=pos["mass"], + zp_ft=pos["alt"], + ) + + if pos["speed_type"] == "CAS": + self.aircraft_state.mach = cas2mach(pos["cas"] * kts, h=pos["alt"] * ft) + if pos["alt"] < self.alt_crossover: + self.aircraft_state.mach = min( + self.aircraft_state.mach, self.aircraft_state.mach_cruise + ) + else: + self.aircraft_state.mach = min(pos["mach"], self.aircraft_state.mach_cruise) + + self.aircraft_state.tsp = self.propulsion_service.compute_max_rating( + propulsion_settings=self.propulsion_settings, + aircraft_state=self.aircraft_state, + ) + # parameters lat_to, lon_to, alt_to = self.lat2, self.lon2, self.alt2 lat_start, lon_start, alt_start = self.lat1, self.lon1, self.alt1 @@ -831,6 +924,12 @@ def heuristic(self, s: D.T_state, heuristic_name: str = None) -> Value[D.T_value cost = distance_to_goal elif heuristic_name == "fuel": + if distance_to_goal != 0: + # angle of the plane + angle = atan((alt_to - pos["alt"]) * ft / distance_to_goal) + else: + angle = 0 + # bearing of the plane bearing_degrees = aero_bearing(pos["lat"], pos["lon"], lat_to, lon_to) @@ -846,16 +945,42 @@ def heuristic(self, s: D.T_state, heuristic_name: str = None) -> Value[D.T_value # temperature computations temp = self.weather_interpolator.interpol_field( - [pos["ts"], pos["alt"], pos["lat"], pos["lon"]], field="T" + [pos["ts"], (pos["alt"] + alt_to) / 2, pos["lat"], pos["lon"]], + field="temperature", ) # check for NaN values if math.isnan(temp): print("NaN values in temp") + # compute dISA + dISA = temp - temperature((pos["alt"] + alt_to) / 2, disa=0) + isa_atmosphere_settings = IsaAtmosphereSettings(d_isa=dISA) + + weather_state = self.atmosphere_service.retrieve_weather_state( + atmosphere_settings=isa_atmosphere_settings, + four_dimensions_state=self.aircraft_state, + ) + + self.aircraft_state.weather_state = weather_state + + delta = self.aircraft_state.weather_state.static_pressure_pa / 101325.0 + self.aircraft_state.cl = (2 * self.aircraft_state.gw_kg * 9.80665) / ( + delta + * 101325.0 + * 1.4 + * self.propulsion_settings.sref + * self.aircraft_state.mach**2 + * math.cos(angle) + ) + wspd = sqrt(wn * wn + we * we) - tas = mach2tas(pos["mach"], pos["alt"] * ft) # alt ft -> meters + tas = mach2tas( + self.aircraft_state.mach, self.aircraft_state.zp_ft * ft + ) # alt ft -> meters + + self.aircraft_state.tas_meters_per_sec = tas gs = compute_gspeed( tas=tas, @@ -864,31 +989,18 @@ def heuristic(self, s: D.T_state, heuristic_name: str = None) -> Value[D.T_value wind_direction=3 * math.pi / 2 - atan2(wn, we), ) - # override temp computation - values_current = { - "mass": pos["mass"], - "alt": pos["alt"], - "speed": tas / kts, - "temp": temp, - } - # compute "time to arrival" dt = distance_to_goal / gs if distance_to_goal == 0: return Value(cost=0) - if self.perf_model_name == "PS": - cost = self.perf_model.compute_fuel_consumption( - values_current, - delta_time=dt, - vs=(alt_to - pos["alt"]) * 60 / dt, - ) - else: - cost = self.perf_model.compute_fuel_consumption( - values_current, - delta_time=dt, - ) + ff = self.propulsion_service.compute_total_fuel_flow_kg_per_sec( + propulsion_settings=self.propulsion_settings, + aircraft_state=self.aircraft_state, + ) + + cost = ff * dt elif heuristic_name == "time": we, wn = 0, 0 @@ -940,8 +1052,9 @@ def set_network( nb_forward_points: int, nb_lateral_points: int, nb_vertical_points: int, - climbing_slope: float = None, - descending_slope: float = None, + cas_climb: float, + mach_cruise: float, + cas_descent: float, graph_width: float = None, ): """ @@ -961,352 +1074,721 @@ def set_network( A 3D matrix containing for each points its latitude, longitude, altitude between origin & destination. """ - cruise_alt_min = 31_000 * ft # maybe useful to change this - half_forward_points = nb_forward_points // 2 - half_lateral_points = nb_lateral_points // 2 - half_vertical_points = nb_vertical_points // 2 + # COORDINATES + lon_start, lat_start = p0.lon, p0.lat + lon_end, lat_end = p1.lon, p1.lat + + # CLIMB, DESCENT: rocd (in ft/min) + rocd_climb = 1500 + rocd_descent = 2000 + + # CLIMB: cas (in m/s) and mach + cas_climb1 = cas_climb * kts + cas_climb2 = cas_climb1 + mach_climb = mach_cruise + + # DESCENT: cas (in m/s) and mach + cas_descent1 = cas_descent * kts + cas_descent2 = cas_descent1 + cas_descent3 = cas_descent1 + mach_descent = mach_cruise + + # CRUISE: mach + mach_cruise = mach_cruise # mach_cruise + assert mach_cruise < 1, "Mach number should be less than 1" + + # ALTITUDES + alt_init = p0.height + alt_toc = self.cruise_height_min * ft + alt_max = self.cruise_height_max * ft + alt_final = p1.height + + # HEADING, BEARING and DISTANCE + total_distance = distance( + lat_start, lon_start, lat_end, lon_end, h=int(alt_final - alt_init) + ) + half_distance = total_distance / 2 + + # REMOVE + n_branches = nb_lateral_points + + # initialize an empty graph + graph = nx.DiGraph() + + # first node is the origin + graph.add_node( + 0, + parent_id=-1, + branch_id=0, + lat=lat_start, + lon=lon_start, + height=alt_init, + heading=aero_bearing(lat_start, lon_start, lat_end, lon_end), + dist_destination=total_distance, + dist_travelled=0, + ts=0, + phase="climb", + speed=cas_climb1 / kts, + speed_type="CAS", + ) - distp = ( - graph_width * p0.distanceTo(p1) * 0.022 - ) # meters, around 2.2%*graphwidth of the p0 to p1 distance + # define the width of the graph + if graph_width == "small": + alpha = 10 + elif graph_width == "medium": + alpha = 30 + elif graph_width == "large": + alpha = 45 + elif graph_width == "xlarge": + alpha = 60 + else: + raise ValueError("Graph width not defined or incorrect.") - descent_dist = min( - 300_000 - * ( - max(self.ac["cruise"]["height"] - p1.height, 0) - / self.ac["cruise"]["height"] - ), - p0.distanceTo(p1), - ) # meters - - climb_dist = 220_000 * ( - max(self.ac["cruise"]["height"] - p0.height, 0) - / self.ac["cruise"]["height"] - ) # meters - - total_distance = p0.distanceTo(p1) - if total_distance < (climb_dist + descent_dist): - climb_dist = total_distance * max( - (climb_dist / (climb_dist + descent_dist)) - 0.1, 0 - ) - descent_dist = total_distance * max( - descent_dist / (climb_dist + descent_dist) - 0.1, 0 - ) - possible_altitudes = [cruise_alt_min for k in range(nb_vertical_points)] + angles = np.linspace( + start=-alpha, stop=alpha, num=n_branches - 1, endpoint=True, dtype=float + ) + angles = np.insert(angles, 0, 0) + + ######################################################################################################## + ######################### FLIGHT PHASES SETUP ########################################################## + # CLIMB + n_steps_climb = 10 + imposed_altitudes_climb = np.array( + [alt_init / ft, 10_000, self.alt_crossover, alt_toc / ft] + ) + possible_altitudes_climb = ( + np.linspace(alt_init, alt_toc, num=n_steps_climb, endpoint=True) / ft + ) + possible_altitudes_climb = np.unique( + np.sort(np.append(possible_altitudes_climb, imposed_altitudes_climb)) + ) + time_steps_climb = ( + np.diff(possible_altitudes_climb) / rocd_climb * 60 + ) # seconds + + # CRUISE + n_steps_cruise = nb_forward_points + n_steps_cruise_climb = nb_vertical_points + possible_altitudes_cruise_climb = np.linspace( + alt_toc, alt_max, num=n_steps_cruise_climb, endpoint=True + ) - else: - possible_altitudes = [ - ( - min( - self.ac["cruise"]["height"] - + 2000 * ft * i - - (self.ac["cruise"]["height"] % 1000), - self.ac["limits"]["ceiling"], - ) - ) - for i in range(nb_vertical_points) - ] - if climbing_slope is not None: - climbing_ratio = climbing_slope - else: - climbing_ratio = ( - possible_altitudes[0] / climb_dist if climb_dist != 0 else 0 - ) - if descending_slope: - descending_ratio = descending_slope - else: - descending_ratio = ( - possible_altitudes[0] / descent_dist if descent_dist != 0 else 0 - ) - # Initialisation of the graph matrix - pt = [ - [ - [None for k in range(len(possible_altitudes))] - for j in range(nb_lateral_points) - ] - for i in range(nb_forward_points) - ] - - # set boundaries - for j in range(nb_lateral_points): - for k in range(nb_vertical_points): - pt[0][j][k] = p0 - pt[nb_forward_points - 1][j][k] = p1 - - # set climb phase - i_initial = 1 - if climbing_ratio != 0: - dist = 0 - alt = p0.height - while dist < climb_dist and i_initial != nb_forward_points: - - local_dist = ( - pt[i_initial - 1][half_lateral_points][ - half_vertical_points - ].distanceTo(p1) - ) / (nb_forward_points - i_initial) - dist += local_dist - alt += int(local_dist * climbing_ratio) - - for k in range(nb_vertical_points): - bearing = pt[i_initial - 1][half_lateral_points][ - k - ].initialBearingTo(p1) - pt[i_initial][half_lateral_points][k] = pt[i_initial - 1][ - half_lateral_points - ][k].destination( - local_dist, bearing, min(possible_altitudes[0], alt) - ) - i_initial += 1 - - # set last step, descent - i_final = 1 - if descending_ratio != 0: - dist = 0 - alt = p1.height - - while dist < descent_dist and i_final != nb_forward_points - 1: - local_dist = ( - pt[nb_forward_points - i_final][half_lateral_points][ - half_vertical_points - ].distanceTo(p0) - ) / (nb_forward_points - i_final) - dist += local_dist - alt += int(local_dist * descending_ratio) - - for k in range(nb_vertical_points): - bearing = pt[nb_forward_points - i_final][half_lateral_points][ - k - ].initialBearingTo(p0) - pt[nb_forward_points - i_final - 1][half_lateral_points][k] = pt[ - nb_forward_points - i_final - ][half_lateral_points][k].destination( - local_dist, bearing, min(possible_altitudes[0], alt) + # DESCENT + n_steps_descent = 5 + distance_start_descent = 150 * nm + imposed_altitudes_descent_prep = np.array( + [self.alt_crossover, 10_000, alt_final / ft] + ) + + ######################### END OF FLIGHT PHASES SETUP ################################################### + ######################################################################################################## + + ######################################################################################################## + ######################### BEGIN OF FLIGHT PHASE ######################################################## + + branches_ids = { + "climb": [], + "cruise": [], + "cruise_correction": [], + "descent": [], + } + for branch_id in range(n_branches): + parent_id = 0 + angle = angles[branch_id] + distance_halfway = half_distance / math.cos(math.radians(angle)) + parent = graph.nodes[parent_id] + parent_height = parent["height"] + + ###### CLIMB PHASE ###### + children_climb = [] + for index_climb, time_step_climb in enumerate(time_steps_climb): + parent = graph.nodes[parent_id] + parent_height = parent["height"] # in m + plane_heading_branch = ( + aero_bearing( + lat1=parent["lat"], + lon1=parent["lon"], + lat2=lat_end, + lon2=lon_end, ) - i_final += 1 - - # direct path between end of climbing and beginning of descent - for k in range(nb_vertical_points): - for i in range(i_initial, nb_forward_points - i_final + 1): - bearing = pt[i - 1][half_lateral_points][k].initialBearingTo(p1) - total_distance = pt[i - 1][half_lateral_points][k].distanceTo( - pt[nb_forward_points - 2][half_lateral_points][k] - ) - pt[i][half_lateral_points][k] = pt[i - 1][half_lateral_points][ - k - ].destination( - total_distance / (nb_forward_points - i), - bearing, - height=possible_altitudes[k], + + angle ) + height = possible_altitudes_climb[index_climb + 1] * ft + + # get the right speed according to the altitude + if height / ft < 10_000: + speed_type = "CAS" + cas_climb = cas_climb1 + elif height / ft <= self.alt_crossover: + speed_type = "CAS" + cas_climb = cas_climb2 + else: + speed_type = "MACH" + cas_climb = mach2cas(mach_climb, parent_height) - bearing = pt[half_forward_points - 1][half_lateral_points][ - k - ].initialBearingTo(pt[half_forward_points + 1][half_lateral_points][k]) - pt[half_forward_points][nb_lateral_points - 1][k] = pt[half_forward_points][ - half_lateral_points - ][k].destination( - distp * half_lateral_points, - bearing + 90, - height=pt[half_forward_points][half_lateral_points][k].height, - ) - pt[half_forward_points][0][k] = pt[half_forward_points][ - half_lateral_points - ][k].destination( - distp * half_lateral_points, - bearing - 90, - height=pt[half_forward_points][half_lateral_points][k].height, - ) + dt = time_step_climb + dx = cas2tas(cas_climb, h=height) * dt - for j in range(1, half_lateral_points + 1): - for k in range(len(possible_altitudes)): - # +j (left) - bearing = pt[half_forward_points][half_lateral_points + j - 1][ - k - ].initialBearingTo(pt[half_forward_points][nb_lateral_points - 1][k]) - total_distance = pt[half_forward_points][half_lateral_points + j - 1][ - k - ].distanceTo(pt[half_forward_points][nb_lateral_points - 1][k]) - pt[half_forward_points][half_lateral_points + j][k] = pt[ - half_forward_points - ][half_lateral_points + j - 1][k].destination( - total_distance / (half_lateral_points - j + 1), - bearing, - height=pt[half_forward_points][half_lateral_points][k].height, + # compute new position + lat, lon = latlon( + parent["lat"], parent["lon"], d=dx, brg=plane_heading_branch ) - # -j (right) - bearing = pt[half_forward_points][half_lateral_points - j + 1][ - k - ].initialBearingTo(pt[half_forward_points][0][k]) - total_distance = pt[half_forward_points][half_lateral_points - j + 1][ - k - ].distanceTo(pt[half_forward_points][0][k]) - pt[half_forward_points][half_lateral_points - j][k] = pt[ - half_forward_points - ][half_lateral_points - j + 1][k].destination( - total_distance / (half_lateral_points - j + 1), - bearing, - height=pt[half_forward_points][half_lateral_points][k].height, + + # add the new node + graph.add_node( + graph.number_of_nodes(), + parent_id=parent_id, + branch_id=branch_id, + lat=lat, + lon=lon, + height=height, + heading=plane_heading_branch, + dist_destination=distance(lat, lon, lat_end, lon_end), + dist_travelled=parent["dist_travelled"] + dx, + ts=parent["ts"] + dt, + phase="climb", + speed=cas_climb / kts if speed_type == "CAS" else mach_climb, + speed_type=speed_type, ) - for i in range(1, i_initial): - alt = pt[i][half_lateral_points][k].height - bearing = pt[i - 1][half_lateral_points + j][k].initialBearingTo( - pt[half_forward_points][half_lateral_points + j][k] - ) - total_distance = pt[i - 1][half_lateral_points + j][k].distanceTo( - pt[half_forward_points][half_lateral_points + j][k] - ) - pt[i][half_lateral_points + j][k] = pt[i - 1][ - half_lateral_points + j - ][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=alt, - ) - bearing = pt[i - 1][half_lateral_points - j][k].initialBearingTo( - pt[half_forward_points][half_lateral_points - j][k] - ) - total_distance = pt[i - 1][half_lateral_points - j][k].distanceTo( - pt[half_forward_points][half_lateral_points - j][k] - ) - pt[i][half_lateral_points - j][k] = pt[i - 1][ - half_lateral_points - j - ][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=alt, - ) - for i in range(i_initial, half_forward_points): - # first halp (p0 to np2) - bearing = pt[i - 1][half_lateral_points + j][k].initialBearingTo( - pt[half_forward_points][half_lateral_points + j][k] - ) - total_distance = pt[i - 1][half_lateral_points + j][k].distanceTo( - pt[half_forward_points][half_lateral_points + j][k] - ) - pt[i][half_lateral_points + j][k] = pt[i - 1][ - half_lateral_points + j - ][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=pt[i][half_lateral_points][k].height, + # add the edge + graph.add_edge(parent_id, graph.number_of_nodes() - 1) + + parent_id = graph.number_of_nodes() - 1 + + children_climb.append(parent_id) + + branches_ids["climb"].append(children_climb) + + distance_climb_to_destination = graph.nodes[ + branches_ids["climb"][branch_id][-1] + ]["dist_destination"] + distance_cruise = max( + distance_halfway + - graph.nodes[branches_ids["climb"][branch_id][-1]]["dist_travelled"], + distance_climb_to_destination - distance_start_descent, + ) # (distance_climb_to_destination - distance_start_descent) + distance_step = distance_cruise / n_steps_cruise + + # PREPARING CRUISE, ALTITUDE CHANGES + parent_id_after_climb = parent_id + # FIRST CRUISE PHASE + children_cruise = [] + dx_counter = 0 + for step_cruise_climb in range(n_steps_cruise_climb): + children_cruise_climb = [] + parent = graph.nodes[parent_id_after_climb] + parent_height = parent["height"] + target_altitude = possible_altitudes_cruise_climb[step_cruise_climb] + plane_heading_branch = ( + aero_bearing( + lat1=parent["lat"], + lon1=parent["lon"], + lat2=lat_end, + lon2=lon_end, ) + + angle + ) - bearing = pt[i - 1][half_lateral_points - j][k].initialBearingTo( - pt[half_forward_points][half_lateral_points - j][k] + # Allows for a step climb during cruise + if parent_height != target_altitude: + cas_cruise = mach2cas(mach_cruise, parent_height) + dz_cruise_climb = (target_altitude - parent_height) / ft + dt_cruise_climb = dz_cruise_climb / rocd_climb * 60 + dx_cruise_climb = cas_cruise * dt_cruise_climb + + # compute new position + lat, lon = latlon( + parent["lat"], + parent["lon"], + d=dx_cruise_climb, + brg=plane_heading_branch, ) - total_distance = pt[i - 1][half_lateral_points - j][k].distanceTo( - pt[half_forward_points][half_lateral_points - j][k] + + # add the new node + graph.add_node( + graph.number_of_nodes(), + parent_id=parent_id, + branch_id=branch_id, + lat=lat, + lon=lon, + height=target_altitude, + heading=plane_heading_branch, + dist_destination=distance(lat, lon, lat_end, lon_end), + dist_travelled=parent["dist_travelled"] + dx_cruise_climb, + ts=parent["ts"] + dt_cruise_climb, + phase="cruise", + speed=mach_cruise, + speed_type="MACH", ) - pt[i][half_lateral_points - j][k] = pt[i - 1][ - half_lateral_points - j - ][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=pt[i][half_lateral_points][k].height, + + parent_id = graph.number_of_nodes() - 1 + children_cruise_climb.append(parent_id) + + for _ in range(n_steps_cruise): + parent = graph.nodes[parent_id] + parent_distance_travelled = parent["dist_travelled"] + + if parent_distance_travelled > distance_halfway: + plane_heading_branch = aero_bearing( + parent["lat"], parent["lon"], lat_end, lon_end + ) + else: + plane_heading_branch = ( + aero_bearing(parent["lat"], parent["lon"], lat_end, lon_end) + + angle + ) + + dx = distance_step + dt = dx / cas2tas(mach2cas(mach_cruise, height), h=height) + dx_counter += dx + # compute new position + lat, lon = latlon( + parent["lat"], parent["lon"], d=dx, brg=plane_heading_branch ) - for i in range(1, abs(half_forward_points - i_final)): - # second half (np2 to p1) - bearing = pt[half_forward_points + i - 1][half_lateral_points + j][ - k - ].initialBearingTo( - pt[nb_forward_points - 1][half_lateral_points + j][k] + + dist_destination = distance(lat, lon, lat_end, lon_end) + + # add the new node + graph.add_node( + graph.number_of_nodes(), + parent_id=parent_id, + branch_id=branch_id, + lat=lat, + lon=lon, + height=target_altitude, + heading=plane_heading_branch, + dist_destination=dist_destination, + dist_travelled=parent["dist_travelled"] + dx, + ts=parent["ts"] + dt, + phase="cruise", + speed=mach_cruise, + speed_type="MACH", ) - total_distance = pt[half_forward_points + i - 1][ - half_lateral_points + j - ][k].distanceTo( - pt[nb_forward_points - 1][half_lateral_points + j][k] + + graph.add_edge(parent_id, graph.number_of_nodes() - 1) + + parent_id = graph.number_of_nodes() - 1 + + children_cruise_climb.append(parent_id) + # print(f"After Cruise 1, at: {dist_destination/nm} from destination; Traveled for {dx_counter/nm} nm") + children_cruise.append(children_cruise_climb) + branches_ids["cruise"].append(children_cruise) + + # SECOND CRUISE PHASE + children_cruise_correction = [] + for parent_group in branches_ids["cruise"][branch_id]: + if parent_group == []: + parent_group = branches_ids["climb"][branch_id] + children_cruise_climb_correction = [] + parent_id_after_first_cruise = parent_group[-1] + + distance_after_cruise = graph.nodes[parent_id_after_first_cruise][ + "dist_destination" + ] + imposed_descent_prep = np.unique( + np.sort( + np.concatenate( + ( + [ + graph.nodes[parent_id_after_first_cruise]["height"] + / ft + ], + imposed_altitudes_descent_prep, + ) + ) ) - pt[half_forward_points + i][half_lateral_points + j][k] = pt[ - half_forward_points + i - 1 - ][half_lateral_points + j][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=pt[half_forward_points + i][half_lateral_points][ - k - ].height, + ) + imposed_altitude_descent_diff = np.diff(imposed_descent_prep) + cas_descent_profile = mach2cas( + mach_descent, graph.nodes[parent_id_after_first_cruise]["height"] + ) # [mach2cas(mach_descent, graph.nodes[parent_id_after_first_cruise]["height"]), cas_descent3, cas_descent2, cas_descent1] + imposed_times_step_descent = ( + imposed_altitude_descent_diff / rocd_descent * 60 + ) + + # compute horizontal distance + dx_total = 0 + for _, time_step_descent in enumerate(imposed_times_step_descent): + dx = cas2tas(cas_descent_profile, h=height) * time_step_descent + dx_total += dx + + delta_distance_cruise = distance_after_cruise - dx_total + + if delta_distance_cruise < 0: + raise ValueError( + "With the current ROCD and DESCENT speed profile, the plane cannot reach the destination altitude." ) - bearing = pt[half_forward_points + i - 1][half_lateral_points - j][ - k - ].initialBearingTo( - pt[nb_forward_points - 1][half_lateral_points - j][k] + distance_step = delta_distance_cruise / 5 + + parent_height = graph.nodes[parent_id_after_first_cruise]["height"] + parent_id = parent_id_after_first_cruise + dx_counter = 0 + for _ in range(5): + parent = graph.nodes[parent_id] + parent_height = parent["height"] + parent_distance_travelled = parent["dist_travelled"] + + plane_heading_branch = aero_bearing( + parent["lat"], parent["lon"], lat_end, lon_end ) - total_distance = pt[half_forward_points + i - 1][ - half_lateral_points - j - ][k].distanceTo( - pt[nb_forward_points - 1][half_lateral_points - j][k] + + dx = distance_step + dt = dx / cas2tas(mach2cas(mach_cruise, height), h=height) + dx_counter += dx + + # compute new position + lat, lon = latlon( + parent["lat"], parent["lon"], d=dx, brg=plane_heading_branch ) - pt[half_forward_points + i][half_lateral_points - j][k] = pt[ - half_forward_points + i - 1 - ][half_lateral_points - j][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=pt[half_forward_points + i][half_lateral_points][ - k - ].height, + + dist_destination = distance(lat, lon, lat_end, lon_end) + + # add the new node + graph.add_node( + graph.number_of_nodes(), + parent_id=parent_id, + branch_id=branch_id, + lat=lat, + lon=lon, + height=parent_height, + heading=plane_heading_branch, + dist_destination=dist_destination, + dist_travelled=parent["dist_travelled"] + dx, + ts=parent["ts"] + dt, + phase="cruise", + speed=mach_cruise, + speed_type="MACH", ) - for i in range(abs(half_forward_points - i_final), half_forward_points): - alt = pt[half_forward_points + i - 1][half_lateral_points][k].height - bearing = pt[half_forward_points + i - 1][half_lateral_points + j][ - k - ].initialBearingTo( - pt[nb_forward_points - 1][half_lateral_points + j][k] + + graph.add_edge(parent_id, graph.number_of_nodes() - 1) + + parent_id = graph.number_of_nodes() - 1 + + children_cruise_climb_correction.append(parent_id) + + children_cruise_correction.append(children_cruise_climb_correction) + branches_ids["cruise_correction"].append(children_cruise_correction) + + # DESCENT PHASE + children_descent = [] + for parent_group in branches_ids["cruise_correction"][branch_id]: + children_descent_group = [] + parent_id_after_cruise_correction = parent_group[-1] + parent_height = graph.nodes[parent_id_after_cruise_correction]["height"] + parent_id = parent_id_after_cruise_correction + + imposed_altitudes_descent = np.concatenate( + ([parent_height / ft], imposed_altitudes_descent_prep) + ) + possible_altitudes_descent = ( + np.linspace( + alt_final, parent_height, num=n_steps_descent, endpoint=True ) - total_distance = pt[half_forward_points + i - 1][ - half_lateral_points + j - ][k].distanceTo( - pt[nb_forward_points - 1][half_lateral_points + j][k] + / ft + ) + possible_altitudes_descent = np.unique( + np.sort( + np.append(possible_altitudes_descent, imposed_altitudes_descent) ) - pt[half_forward_points + i][half_lateral_points + j][k] = pt[ - half_forward_points + i - 1 - ][half_lateral_points + j][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=alt, + )[::-1] + time_steps_descent = ( + -np.diff(possible_altitudes_descent)[::-1] / rocd_descent * 60 + ) # seconds + + dx_counter = 0 + for index_descent, time_step_descent in enumerate(time_steps_descent): + parent = graph.nodes[parent_id] + parent_height = parent["height"] + plane_heading_branch = aero_bearing( + parent["lat"], parent["lon"], lat_end, lon_end ) - bearing = pt[half_forward_points + i - 1][half_lateral_points - j][ - k - ].initialBearingTo( - pt[nb_forward_points - 1][half_lateral_points - j][k] + height = possible_altitudes_descent[index_descent + 1] * ft + + # get the right speed according to the altitude + if height / ft < 10_000: + speed_type = "CAS" + cas_descent = cas_descent2 + elif height / ft <= self.alt_crossover: + speed_type = "CAS" + cas_descent = cas_descent3 + else: + speed_type = "MACH" + cas_descent = mach2cas(mach_descent, height) + + dt = time_step_descent + dx = cas2tas(cas_descent, h=height) * dt + dx_counter += dx + + # compute new position + lat, lon = latlon( + parent["lat"], parent["lon"], d=dx, brg=plane_heading_branch ) - total_distance = pt[half_forward_points + i - 1][ - half_lateral_points - j - ][k].distanceTo( - pt[nb_forward_points - 1][half_lateral_points - j][k] + dist_destination = distance(lat, lon, lat_end, lon_end) + # add the new node + graph.add_node( + graph.number_of_nodes(), + parent_id=parent_id, + branch_id=branch_id, + lat=lat, + lon=lon, + height=height, + heading=plane_heading_branch, + dist_destination=dist_destination, + dist_travelled=parent["dist_travelled"] + dx, + ts=parent["ts"] + dt, + phase="descent", + speed=cas_descent / kts + if speed_type == "CAS" + else mach_descent, + speed_type=speed_type, ) - pt[half_forward_points + i][half_lateral_points - j][k] = pt[ - half_forward_points + i - 1 - ][half_lateral_points - j][k].destination( - total_distance / (half_forward_points - i + 1), - bearing, - height=alt, + + # add the edge + graph.add_edge(parent_id, graph.number_of_nodes() - 1) + + parent_id = graph.number_of_nodes() - 1 + + children_descent_group.append(parent_id) + # print(f"After Descent, at: {dist_destination/nm} from destination; Traveled for {dx_counter/nm} nm") + children_descent.append(children_descent_group) + + branches_ids["descent"].append(children_descent) + self.branches_ids = branches_ids + + ######################################################################################################## + ######################### START OF NODE CONNECTION ##################################################### + + for branch_id in range(n_branches): + ### CLIMB PHASE ### + # connect to branch on the left + if branch_id > 0: + for parent_id, child_id in zip( + branches_ids["climb"][branch_id][:-1], + branches_ids["climb"][branch_id - 1], + ): + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the right + if branch_id + 1 < n_branches: + for parent_id, child_id in zip( + branches_ids["climb"][branch_id][:-1], + branches_ids["climb"][branch_id + 1], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + parent_climb = branches_ids["climb"][branch_id][ + -1 + ] # last climb node from the branch + for altitude_index in range(n_steps_cruise_climb - 1): + child_cruise = branches_ids["cruise"][branch_id][altitude_index + 1][ + 0 + ] # first cruise node from the branch at altitude above + graph.add_edge(parent_climb, child_cruise) + + ### CRUISE + CORRECTION PHASES ### + for altitude_index in range(n_steps_cruise_climb): + current_altitude_nodes = branches_ids["cruise"][branch_id][ + altitude_index + ] + + ### CRUISE PHASE ### + # connect to altitude on bottom + if altitude_index > 0: + bottom_altitude_nodes = branches_ids["cruise"][branch_id][ + altitude_index - 1 + ] + for parent_id, child_id in zip( + current_altitude_nodes, bottom_altitude_nodes + ): + if altitude_index - 1 == 0: + # print(f"{parent_id} -> {child_id}") + graph.add_edge(parent_id, child_id) + else: + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the left + if branch_id > 0: + for parent_id, child_id in zip( + current_altitude_nodes, bottom_altitude_nodes + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the right + if branch_id + 1 < n_branches: + for parent_id, child_id in zip( + current_altitude_nodes, bottom_altitude_nodes + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to altitude on top + if altitude_index + 1 < n_steps_cruise_climb: + top_altitude_nodes = ( + branches_ids["cruise"][branch_id][altitude_index + 1] + if altitude_index + 1 < n_steps_cruise_climb + else [] ) + for parent_id, child_id in zip( + current_altitude_nodes, top_altitude_nodes + ): + if child_id + 1 in top_altitude_nodes: + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the left + if branch_id > 0: + for parent_id, child_id in zip( + current_altitude_nodes, top_altitude_nodes + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the right + if branch_id + 1 < n_branches: + for parent_id, child_id in zip( + current_altitude_nodes, top_altitude_nodes + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the left + if branch_id > 0: + for parent_id, child_id in zip( + branches_ids["cruise"][branch_id][altitude_index], + branches_ids["cruise"][branch_id - 1][altitude_index], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the right + if branch_id + 1 < n_branches: + for parent_id, child_id in zip( + branches_ids["cruise"][branch_id][altitude_index], + branches_ids["cruise"][branch_id + 1][altitude_index], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + ## CRUISE CORRECTION PHASE ### + # connect to altitude on bottom + if altitude_index > 0: + for parent_id, child_id in zip( + branches_ids["cruise_correction"][branch_id][altitude_index], + branches_ids["cruise_correction"][branch_id][ + altitude_index - 1 + ][:-1], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to altitude on top + if altitude_index + 1 < n_steps_cruise_climb: + for parent_id, child_id in zip( + branches_ids["cruise_correction"][branch_id][altitude_index], + branches_ids["cruise_correction"][branch_id][ + altitude_index + 1 + ][:-1], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the left + if branch_id > 0: + for parent_id, child_id in zip( + branches_ids["cruise_correction"][branch_id][altitude_index], + branches_ids["cruise_correction"][branch_id - 1][ + altitude_index + ], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the right + if branch_id + 1 < n_branches: + for parent_id, child_id in zip( + branches_ids["cruise_correction"][branch_id][altitude_index], + branches_ids["cruise_correction"][branch_id + 1][ + altitude_index + ], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + ### DESCENT PHASE ### + # connect to to branch on the left + if branch_id > 0: + for parent_id, child_id in zip( + branches_ids["descent"][branch_id][altitude_index], + branches_ids["descent"][branch_id - 1][altitude_index][:-1], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + # connect to branch on the right + if branch_id + 1 < n_branches: + for parent_id, child_id in zip( + branches_ids["descent"][branch_id][altitude_index], + branches_ids["descent"][branch_id + 1][altitude_index][:-1], + ): + # print(f"{parent_id} -> {child_id+1}") + graph.add_edge(parent_id, child_id + 1) + + ######################### END OF NODE CONNECTION ####################################################### + ######################################################################################################## - return pt + return graph def get_network(self): return self.network def flying( - self, from_: pd.DataFrame, to_: tuple[float, float, int] + self, + from_: pd.DataFrame, + to_: Tuple[float, float, int], + phase: str, + current_speed: float, + current_speed_type: str, ) -> pd.DataFrame: """Compute the trajectory of a flying object from a given point to a given point # Parameters from_ (pd.DataFrame): the trajectory of the object so far - to_ (tuple[float, float]): the destination of the object + to_ (Tuple[float, float]): the destination of the object # Returns pd.DataFrame: the final trajectory of the object """ pos = from_.to_dict("records")[0] + self.aircraft_state.update_settings( + gw_kg=pos["mass"], + zp_ft=pos["alt"], + ) + + # check speed type (dependent if above or below Xover) + if current_speed_type == "CAS": + self.aircraft_state.mach = cas2mach(current_speed * kts, h=pos["alt"] * ft) + if pos["alt"] < self.alt_crossover: + # print(f"Current speed: {current_speed}, type: {current_speed_type}, mach: {self.aircraft_state.mach}") + self.aircraft_state.mach = min( + self.aircraft_state.mach, self.aircraft_state.mach_cruise + ) + + else: + self.aircraft_state.mach = min(current_speed, self.aircraft_state.MMO) lat_to, lon_to, alt_to = to_[0], to_[1], to_[2] dist_ = distance( - pos["lat"], pos["lon"], lat_to, lon_to, h=(alt_to - pos["alt"]) * ft + pos["lat"], + pos["lon"], + lat_to, + lon_to, + h=abs(alt_to - self.aircraft_state.zp_ft) * ft, ) data = [] @@ -1316,6 +1798,22 @@ def flying( loop = 0 while dist > epsilon: + if dist == 0: + angle = 0 + else: + angle = atan((alt_to - self.aircraft_state.zp_ft) * ft / dist) + + if phase == "climb": + self.aircraft_state.phase = PhaseEnum.CLIMB + self.aircraft_state.rating_level = RatingEnum.MCL + elif phase == "cruise": + self.aircraft_state.phase = PhaseEnum.CRUISE + self.aircraft_state.rating_level = RatingEnum.CR + else: + self.aircraft_state.phase = PhaseEnum.DESCENT + self.aircraft_state.rating_level = RatingEnum.CR + + self.aircraft_state.gamma_air_deg = math.degrees(angle) # bearing of the plane bearing_degrees = aero_bearing(pos["lat"], pos["lon"], lat_to, lon_to) @@ -1333,12 +1831,36 @@ def flying( # temperature computations temp = self.weather_interpolator.interpol_field( - [pos["ts"], pos["alt"], pos["lat"], pos["lon"]], field="T" + [pos["ts"], (pos["alt"] + alt_to) / 2, pos["lat"], pos["lon"]], + field="temperature", ) + dISA = temp - temperature((pos["alt"] + alt_to) / 2, disa=0) + + isa_atmosphere_settings = IsaAtmosphereSettings(d_isa=dISA) + + weather_state = self.atmosphere_service.retrieve_weather_state( + atmosphere_settings=isa_atmosphere_settings, + four_dimensions_state=self.aircraft_state, + ) + + self.aircraft_state.weather_state = weather_state + + delta = self.aircraft_state.weather_state.static_pressure_pa / 101325.0 + self.aircraft_state.cl = (2 * self.aircraft_state.gw_kg * 9.80665) / ( + delta + * 101325.0 + * 1.4 + * self.propulsion_settings.sref + * self.aircraft_state.mach**2 + * math.cos(angle) + ) + wspd = sqrt(wn * wn + we * we) - tas = mach2tas(self.mach, alt_to * ft) # alt ft -> meters + tas = mach2tas(self.aircraft_state.mach, alt_to * ft) # alt ft -> meters + + self.aircraft_state.tas_meters_per_sec = tas gs = compute_gspeed( tas=tas, @@ -1360,21 +1882,23 @@ def flying( h=alt_to * ft, ) - values_current = { - "mass": pos["mass"], - "alt": pos["alt"], - "speed": tas / kts, - "temp": temp, - } + self.aircraft_state.time_step = dt - pos["fuel"] = self.perf_model.compute_fuel_consumption( - values_current, - delta_time=dt, - vs=(alt_to - pos["alt"]) * 60 / dt, # ft/min - # approximation for small angles: tan(alpha) ~ alpha + if self.aircraft_state.phase.name == "DESCENT": + self.aircraft_state.tsp = 0.0 + else: + self.aircraft_state.tsp = self.propulsion_service.compute_max_rating( + propulsion_settings=self.propulsion_settings, + aircraft_state=self.aircraft_state, + ) + + ff = self.propulsion_service.compute_total_fuel_flow_kg_per_sec( + propulsion_settings=self.propulsion_settings, + aircraft_state=self.aircraft_state, ) - mass = pos["mass"] - pos["fuel"] + pos["fuel"] = ff * dt + mass_new = self.aircraft_state.gw_kg - pos["fuel"] # get new weather interpolators if pos["ts"] + dt >= (3_600.0 * 24.0): @@ -1387,42 +1911,65 @@ def flying( self.weather_date = self.weather_date.previous_day() self.weather_interpolator = self.get_weather_interpolator() + dist = distance( + ll[0], + ll[1], + lat_to, + lon_to, + h=abs(self.aircraft_state.zp_ft - alt_to) + * ft, # height difference in m + ) + new_row = { "ts": (pos["ts"] + dt), "lat": ll[0], "lon": ll[1], - "mass": mass, - "mach": self.mach, + "mass": mass_new, + "cas": current_speed + if current_speed_type == "CAS" + else mach2cas(current_speed, alt_to * ft) / kts, + "mach": current_speed + if current_speed_type == "MACH" + else min( + cas2mach(current_speed * kts, alt_to * ft), + self.aircraft_state.mach_cruise, + ), + "speed_type": current_speed_type, "fuel": pos["fuel"], "alt": alt_to, # to be modified + "phase": self.aircraft_state.phase, } - dist = distance( - ll[0], - ll[1], - lat_to, - lon_to, - h=(pos["alt"] - alt_to) * ft, # height difference in m - ) - - if dist < dist_: + if dist <= dist_: data.append(new_row) dist_ = dist pos = data[-1] else: + print(dist, dist_) dt = int(dt / 10) print("going in the wrong part.") assert dt > 0 + # update aircraft state + self.aircraft_state.update_settings( + gw_kg=mass_new, + zp_ft=alt_to, + ) + loop += 1 return pd.DataFrame(data) - def get_weather_interpolator(self) -> GenericWindInterpolator: + def get_weather_interpolator(self) -> WeatherForecastInterpolator: weather_interpolator = None if self.weather_date: + lat_min = min(self.lat1, self.lat2) - 1 + lat_max = max(self.lat1, self.lat2) + 1 + lon_min = min(self.lon1, self.lon2) - 2 + lon_max = max(self.lon1, self.lon2) + 2 + w_dict = self.weather_date.to_dict() mat = get_weather_matrix( @@ -1435,64 +1982,40 @@ def get_weather_interpolator(self) -> GenericWindInterpolator: ) # returns both wind and temperature interpolators - weather_interpolator = GenericWindInterpolator(file_npz=mat) + weather_interpolator = WeatherForecastInterpolator( + file_npz=mat, + lat_min=lat_min, + lat_max=lat_max, + lon_min=lon_min, + lon_max=lon_max, + ) return weather_interpolator - def custom_rollout(self, solver, max_steps=100, make_img=True): - observation = self.reset() + def custom_rollout( + self, solver: Solver, max_steps: int = 100, make_img: bool = True + ) -> None: - solver.reset() - clear_output(wait=True) + observation = self.reset() # loop until max_steps or goal is reached for i_step in range(1, max_steps + 1): # choose action according to solver action = solver.sample_action(observation) - - # get corresponding action outcome = self.step(action) observation = outcome.observation - # self.observation = observation - - print("step ", i_step) - print("policy = ", action[0], action[1]) - print("New state = ", observation.pos) - print("Alt = ", observation.alt) - print("Mach = ", observation.trajectory.iloc[-1]["mach"]) - print(observation) - - # if make_img: - # # update image - # plt.clf() # clear figure - # clear_output(wait=True) - # figure = self.render(observation) - # # plt.savefig(f'step_{i_step}') - # final state reached? if self.is_terminal(observation): break if make_img: print("Final state reached") - clear_output(wait=True) + # clear_output(wait=True) fig = plot_full(self, observation.trajectory) - # plt.savefig(f"full_plot") + plt.savefig(f"full_plot") plt.show() pass - # clear_output(wait=True) - # plt.title(f'Flight plan - {self.origin} -> {self.destination} \n Model: {self.perf_model_name}, Fuel: {np.round(observation.trajectory["fuel"].sum(), 2)} Kg') - # plt.savefig(f"terminal") - # plt.show() - - # figure = plot_altitude(observation.trajectory) - # plt.savefig("altitude") - # plt.show() - # figure = plot_mass(observation.trajectory) - # plt.savefig("mass") - # plt.show() - # plot_network(self) # goal reached? is_goal_reached = self.is_goal(observation) @@ -1501,7 +2024,7 @@ def custom_rollout(self, solver, max_steps=100, make_img=True): if self.constraints is not None: if self.constraints["time"] is not None: if ( - self.constraints["time"][1] + self.constraints["time"][1] # type: ignore >= terminal_state_constraints["time"] ): if ( @@ -1525,7 +2048,7 @@ def custom_rollout(self, solver, max_steps=100, make_img=True): f"Goal reached after {i_step} steps, but there is not enough fuel remaining!" ) else: - if self.ac["limits"]["MFC"] >= terminal_state_constraints["fuel"]: + if self.aircraft_state.MFC >= terminal_state_constraints["fuel"]: print(f"Goal reached after {i_step} steps!") else: print( @@ -1533,7 +2056,7 @@ def custom_rollout(self, solver, max_steps=100, make_img=True): ) else: print(f"Goal not reached after {i_step} steps!") - + self.observation = observation return terminal_state_constraints, self.constraints @@ -1571,11 +2094,13 @@ def compute_gspeed( def fuel_optimisation( origin: Union[str, tuple], destination: Union[str, tuple], - actype: str, + aircraft_state: AircraftState, + cruise_height_min: float, + cruise_height_max: float, constraints: dict, weather_date: WeatherDate, - solver_cls: type[Solver], - solver_kwargs: dict[str, Any], + solver_cls: Type[Solver], + solver_kwargs: Dict[str, Any], max_steps: int = 100, fuel_tol: float = 1e-3, ) -> float: @@ -1589,22 +2114,22 @@ def fuel_optimisation( destination (Union[str, tuple]): ICAO code of the arrival airport of th flight plan e.g LFBO for Toulouse-Blagnac airport, or a tuple (lat,lon) - actype (str): - Aircarft type describe in openap datas (https://github.com/junzis/openap/tree/master/openap/data/aircraft) + aircraft_state (AircraftState) + Initial aircraft state. - constraints (dict): - Constraints that will be defined for the flight plan + cruise_height_min (float) + Minimum cruise height in ft - wind_interpolator (GenericWindInterpolator): - Define the wind interpolator to use wind informations for the flight plan + cruise_height_max (float) + Maximum cruise height in ft - fuel_loaded (float): - Fuel loaded in the plane for the flight + constraints (dict): + Constraints that will be defined for the flight plan solver_cls (type[Solver]): Solver class used in the fuel loop. - solver_kwargs (dict[str, Any]): + solver_kwargs (Dict[str, Any]): Kwargs to initialize the solver used in the fuel loop. max_steps (int): @@ -1625,11 +2150,14 @@ def fuel_optimisation( domain_factory = lambda: FlightPlanningDomain( origin=origin, destination=destination, - actype=actype, - constraints=constraints, - weather_date=weather_date, + aircraft_state=aircraft_state, + cruise_height_min=cruise_height_min, + cruise_height_max=cruise_height_max, objective="distance", heuristic_name="distance", + constraints=constraints, + weather_date=weather_date, + nb_vertical_points=8, nb_forward_points=41, nb_lateral_points=11, fuel_loaded=new_fuel, diff --git a/skdecide/hub/domain/flight_planning/flightplanning_utils.py b/skdecide/hub/domain/flight_planning/flightplanning_utils.py index 28c9f2590f..86a51bb792 100644 --- a/skdecide/hub/domain/flight_planning/flightplanning_utils.py +++ b/skdecide/hub/domain/flight_planning/flightplanning_utils.py @@ -36,14 +36,15 @@ def __exit__(self, type, value, traceback): def plot_full(domain, trajectory: pd.DataFrame) -> Figure: network = domain.network - fig = plt.figure(figsize=(15, 10)) + fig = plt.figure(figsize=(10, 7)) # define the grid layout - gs = gridspec.GridSpec(2, 2, width_ratios=[1, 2]) + gs = gridspec.GridSpec(3, 2, width_ratios=[2, 4]) # add subplots for the line plots ax1 = fig.add_subplot(gs[0, 0]) ax2 = fig.add_subplot(gs[1, 0]) + ax3 = fig.add_subplot(gs[2, 0]) # values pos = [ @@ -68,36 +69,49 @@ def plot_full(domain, trajectory: pd.DataFrame) -> Figure: ax2.set_ylabel("Mass (Kg)") ax2.set_title("Mass profile") + # create twin axis for ax3 + ax3_twin = ax3.twinx() + # plot CAS / mach profile with altitude on y axis + ax3.plot(dist / nm, trajectory.cas, label="CAS", color="blue") + ax3_twin.plot(dist / nm, trajectory.mach, label="Mach", color="red") + ax3.set_xlabel("ESAD (nm)") + ax3.set_ylabel("CAS (kt)") + ax3_twin.set_ylabel("Mach") + ax3.set_title("CAS / Mach profile") + # add legend + ax3.legend(loc="upper left") + ax3_twin.legend(loc="upper right") + # plot the trajectory latmin, latmax = min(trajectory.lat), max(trajectory.lat) lonmin, lonmax = min(trajectory.lon), max(trajectory.lon) - ax3 = fig.add_subplot( + ax4 = fig.add_subplot( gs[:, 1], projection=ccrs.PlateCarree(central_longitude=trajectory.lon.mean()) ) - ax3.set_extent([lonmin - 4, lonmax + 4, latmin - 2, latmax + 2]) - ax3.add_feature(OCEAN, facecolor="#d1e0e0", zorder=-1, lw=0) - ax3.add_feature(LAND, facecolor="#f5f5f5", lw=0) - ax3.add_feature(BORDERS, lw=0.5, color="gray") - ax3.gridlines(draw_labels=True, color="gray", alpha=0.5, ls="--") - ax3.coastlines(resolution="50m", lw=0.5, color="gray") + ax4.set_extent([lonmin - 4, lonmax + 4, latmin - 2, latmax + 2]) + ax4.add_feature(OCEAN, facecolor="#d1e0e0", zorder=-1, lw=0) + ax4.add_feature(LAND, facecolor="#f5f5f5", lw=0) + ax4.add_feature(BORDERS, lw=0.5, color="gray") + ax4.gridlines(draw_labels=True, color="gray", alpha=0.5, ls="--") + ax4.coastlines(resolution="50m", lw=0.5, color="gray") # add great circle - ax3.scatter( + ax4.scatter( trajectory.lon.iloc[0], trajectory.lat.iloc[0], c="darkgreen", transform=ccrs.Geodetic(), ) - ax3.scatter( + ax4.scatter( trajectory.lon.iloc[-1], trajectory.lat.iloc[-1], c="red", transform=ccrs.Geodetic(), ) - ax3.plot( + ax4.plot( [trajectory.lon.iloc[0], trajectory.lon.iloc[-1]], [trajectory.lat.iloc[0], trajectory.lat.iloc[-1]], label="Great Circle", @@ -107,7 +121,7 @@ def plot_full(domain, trajectory: pd.DataFrame) -> Figure: ) # add trajectory - ax3.plot( + ax4.plot( trajectory.lon, trajectory.lat, color="green", @@ -116,30 +130,15 @@ def plot_full(domain, trajectory: pd.DataFrame) -> Figure: marker=".", label="skdecide", ) + ax4.legend() + total_fuel = np.round(trajectory["fuel"].sum(), 2) + total_time = trajectory["ts"].values[-1] - trajectory["ts"].values[0] - # add network - ax3.scatter( - [ - network[x][x1][x2].lon - for x in range(len(network)) - for x1 in range(len(network[x])) - for x2 in range(len(network[x][x1])) - ], - [ - network[x][x1][x2].lat - for x in range(len(network)) - for x1 in range(len(network[x])) - for x2 in range(len(network[x][x1])) - ], - transform=ccrs.Geodetic(), - s=0.1, - ) - - ax3.legend() + total_time = time.strftime("%H:%M:%S", time.gmtime(total_time)) # add title to figure fig.suptitle( - f'Leg: {domain.origin} -> {domain.destination} \n A/C perf. model: {domain.perf_model_name}; Fuel: {np.round(trajectory["fuel"].sum(), 2)} Kg', + f"Leg: {domain.origin} -> {domain.destination} \n A/C perf. model: {domain.aircraft_state.performance_model_type.name}; Fuel: {total_fuel} Kg; Time: {total_time}", fontsize=16, ) @@ -164,9 +163,6 @@ def plot_trajectory(lat1, lon1, lat2, lon2, trajectory: pd.DataFrame) -> Figure: fig.canvas.resizable = False fig.set_dpi(1) - # lon1, lat1 = trajectory.iloc[0]["lon"], trajectory.iloc[0]["lat"] - # lon2, lat2 = trajectory.iloc[-1]["lon"], trajectory.iloc[-1]["lat"] - latmin, latmax = min(lat1, lat2), max(lat1, lat2) lonmin, lonmax = min(lon1, lon2), max(lon1, lon2) @@ -307,81 +303,55 @@ def plot_altitude(trajectory: pd.DataFrame) -> Figure: def plot_network(domain, dir=None): network = domain.network - origin_coord = domain.lat1, domain.lon1, domain.alt1 - target_coord = domain.lat2, domain.lon2, domain.alt2 - # fig, ax = plt.subplots(1, subplot_kw={"projection": ccrs.PlateCarree()}) - fig = plt.figure(figsize=(15, 10)) + fig = plt.figure(figsize=(10, 7)) # define the grid layout - gs = gridspec.GridSpec(1, 2, width_ratios=[1, 1]) - ax1 = fig.add_subplot(gs[0], projection=ccrs.PlateCarree()) - ax2 = fig.add_subplot(gs[1]) - - ax1.set_extent( - [ - min(origin_coord[1], target_coord[1]) - 4, - max(origin_coord[1], target_coord[1]) + 4, - min(origin_coord[0], target_coord[0]) - 2, - max(origin_coord[0], target_coord[0]) + 2, - ] - ) - ax1.add_feature(OCEAN, facecolor="#d1e0e0", zorder=-1, lw=0) - ax1.add_feature(LAND, facecolor="#f5f5f5", lw=0) - ax1.add_feature(BORDERS, lw=0.5, color="gray") - ax1.gridlines(draw_labels=True, color="gray", alpha=0.5, ls="--") - ax1.coastlines(resolution="50m", lw=0.5, color="gray") - - lon_values = [ - network[x][x1][x2].lon - for x in range(len(network)) - for x1 in range(len(network[x])) - for x2 in range(len(network[x][x1])) - ] - lat_values = [ - network[x][x1][x2].lat - for x in range(len(network)) - for x1 in range(len(network[x])) - for x2 in range(len(network[x][x1])) - ] - height_values = [ - network[x][x1][x2].height / ft - for x in range(len(network)) - for x1 in range(len(network[x])) - for x2 in range(len(network[x][x1])) - ] - distance_to_origin = [ - LatLon(lat_values[i], lon_values[i], height_values[i]).distanceTo( - LatLon(origin_coord[0], origin_coord[1], origin_coord[2]) + gs = gridspec.GridSpec(1, 2) + + # add subplots for the line plots + ax1 = fig.add_subplot(gs[0]) + + # plot the altitude + for node in network.nodes: + ax1.scatter( + network.nodes[node]["ts"], + network.nodes[node]["height"] / ft, + color="k", + s=0.5, ) - / nm - for i in range(len(lon_values)) - ] - ax1.scatter( - lon_values, - lat_values, - # transform=ccrs.Geodetic(), - s=0.2, - ) + ax1.set_xlabel("Time (s)") + ax1.set_ylabel("Zp (ft)") + ax1.set_title("Altitude profile") - ax2.scatter( - distance_to_origin, - height_values, - s=0.2, - ) + # plot the trajectory + latmin, latmax = min(domain.lat1, domain.lat2), max(domain.lat1, domain.lat2) + lonmin, lonmax = min(domain.lon1, domain.lon2), max(domain.lon1, domain.lon2) - # scatter airports - ax1.scatter( - origin_coord[1], - origin_coord[0], - c="darkgreen", - transform=ccrs.Geodetic(), - alpha=0.3, - ) - ax1.scatter( - target_coord[1], target_coord[0], c="red", transform=ccrs.Geodetic(), alpha=0.3 - ) + ax3 = fig.add_subplot(gs[1], projection=ccrs.PlateCarree()) + + ax3.set_extent([lonmin - 3, lonmax + 3, latmin - 2, latmax + 2]) + + ax3.add_feature(BORDERS, lw=0.5, color="gray") + ax3.gridlines(draw_labels=True, color="gray", alpha=0.5, ls="--") + ax3.coastlines(resolution="50m", lw=0.5, color="gray") + + for node in network.nodes: + ax3.scatter( + network.nodes[node]["lon"], + network.nodes[node]["lat"], + transform=ccrs.Geodetic(), + color="blue", + s=1, + ) + + # plot airports + lat_start, lon_start = domain.lat1, domain.lon1 + lat_end, lon_end = domain.lat2, domain.lon2 + + ax3.scatter(lon_start, lat_start, transform=ccrs.Geodetic(), color="red", s=3) + ax3.scatter(lon_end, lat_end, transform=ccrs.Geodetic(), color="red", s=3) plt.tight_layout() plt.show() diff --git a/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/GenericInterpolator.py b/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/GenericInterpolator.py index d5ae9ce23a..93cba092b5 100644 --- a/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/GenericInterpolator.py +++ b/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/GenericInterpolator.py @@ -145,13 +145,6 @@ def __init__( else: fields = [f for f in fields if f in list(self.datas.keys())] - ### ??? ### - # if fields is None: - # fields = self.datas.keys() - # else: - # fields = [f for f in fields if f in list(self.datas.keys())] - - # self.datas.allow_pickle = True items = {var: self.datas[var] for var in fields} self.lat_dict = {var: items[var]["lats"] for var in fields} self.long_dict = { @@ -170,14 +163,7 @@ def __init__( for v in self.time_dict: self.time_dict[v] += time_shift_s self.values = {var: items[var]["values"] for var in fields} - # for var in self.lat_dict: - # print(self.lat_dict[var].shape, "lats") - # print(self.long_dict[var].shape, "long") - # print(self.levels_dict[var].shape, "levels") - # print(self.time_dict[var].shape, "time") - # print(self.values[var].shape, "values") - - # one_field = list(self.values.keys())[0] + for feat in self.lat_dict: if self.lat_dict[feat][-1] < self.lat_dict[feat][0]: self.lat_dict[feat] = self.lat_dict[feat][::-1] @@ -188,8 +174,6 @@ def __init__( self.interpol_dict = {} for var in self.values: - # print(f'Building interpolator for {var}') - # print(f'Levels dict: {self.levels_dict[var]}') self.levels_dict[var] = [111, 121] if (len(self.levels_dict[var]) == 0) or (len(self.levels_dict[var]) == 1): self.levels_dict[var] = np.array([30_000]) @@ -261,6 +245,8 @@ def interpol_field(self, X, field="CONVEXION"): :param field: field of weather data to interpolate (could be 'temperature' or 'humidity' :return: array of interpolated values """ + X[1] = std_atm.alt2press(X[1], alt_units="ft", press_units="hpa") + # with self._auto_lock: return self.interpol_dict[field](X) @@ -412,8 +398,7 @@ def plot_field_5d( alpha=0.9, zorder=2, ) - # cs = ax.imshow(Ut[:, :, i], - # extent=[down_long, up_long, down_lat, up_lat]) + plt.title("time " + str(times[i])) plt.draw() if save: @@ -424,8 +409,6 @@ def plot_field_5d( for i in range(1, n_time): for coll in cs.collections: plt.gca().collections.remove(coll) - ##cs.clear() - # cs.set_data(Ut[:, :, i]) cs = ax.contour( x, y, @@ -519,7 +502,6 @@ def transform_long(self, long): return long def interpol_wind_classic(self, lat, longi, alt=35000.0, t=0.0, index_forecast=0): - # with self._auto_lock: p = std_atm.alt2press(alt, alt_units="ft", press_units="hpa") if len(self.axes["U"][1]) == 5: @@ -545,7 +527,8 @@ def interpol_wind(self, X): :param X: array of points [time (in s), alt (in ft), lat, long] :return: wind vector. """ - # with self._auto_lock: + X[1] = std_atm.alt2press(X[1], alt_units="ft", press_units="hpa") + arg = self.interpol_dict["argument-wind"](X) return self.interpol_dict["norm-wind"](X) * np.array( [[np.cos(arg), np.sin(arg)]] @@ -607,7 +590,6 @@ def plot_wind( Ut = np.resize(res[0, 0, :], (n_lat, n_long, n_time)) Vt = np.resize(res[0, 1, :], (n_lat, n_long, n_time)) Nt = np.sqrt(np.square(Ut) + np.square(Vt)) - # Nt = np.reshape(self.interpol_field(values, field='norm-wind'), (n_lat, n_long, n_time)) i = 0 CS = ax.contourf(x, y, Nt[:, :, i], 100, alpha=0.5, zorder=2) diff --git a/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/WeatherInterpolator.py b/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/WeatherInterpolator.py index f40390f77a..88e21af2fa 100644 --- a/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/WeatherInterpolator.py +++ b/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/interpolator/WeatherInterpolator.py @@ -6,6 +6,7 @@ import skdecide.hub.domain.flight_planning.weather_interpolator.weather_tools.common_utils as Toolbox import skdecide.hub.domain.flight_planning.weather_interpolator.weather_tools.interpolator.intergrid as intergrid +import skdecide.hub.domain.flight_planning.weather_interpolator.weather_tools.std_atm as std_atm class WeatherInterpolator(ABC): @@ -52,45 +53,70 @@ class WeatherForecastInterpolator(WeatherInterpolator): Class used to store weather data, interpolate and plot weather forecast from .npz files """ - def __init__(self, file_npz, time_cut_index=None, order_interp=1): + def __init__( + self, + file_npz, + lat_min: float, + lat_max: float, + lon_min: float, + lon_max: float, + time_cut_index=None, + order_interp=1, + ): """ Stores the weather data and build the interpolators on grid. """ # Files Loading self.time_cut_index = time_cut_index if isinstance(file_npz, (str, np.lib.npyio.NpzFile)): - self.datas = np.load(file_npz) if isinstance(file_npz, str) else file_npz - - self.lat_dict = { - var: self.datas[var].item()["lats"] for var in self.datas.keys() - } - self.long_dict = { - var: self.datas[var].item()["longs"] for var in self.datas.keys() - } - self.alt_dict = { - var: self.datas[var].item()["levels"] for var in self.datas.keys() - } + datas = np.load(file_npz) if isinstance(file_npz, str) else file_npz + + # input values are the same for all keys, we pick U + lat_dict = datas["U"].item()["lats"] + long_dict = datas["U"].item()["longs"] + alt_dict = datas["U"].item()["levels"] + time_dict = datas["U"].item()["times"] + + # Data filtering + index_lat = np.where((lat_dict >= lat_min) & (lat_dict <= lat_max))[0] + index_long = np.where((long_dict >= lon_min) & (long_dict <= lon_max))[0] + index_level = np.where(alt_dict >= 150)[0] + + lat_dict_filtered = lat_dict[index_lat] + long_dict_filtered = long_dict[index_long] + alt_dict_filtered = alt_dict[index_level] + + self.lat_dict = {var: lat_dict_filtered for var in datas.keys()} + self.long_dict = {var: long_dict_filtered for var in datas.keys()} + self.alt_dict = {var: alt_dict_filtered for var in datas.keys()} self.time_dict = { - var: self.datas[var].item()["times"] + var: time_dict if self.time_cut_index is None - else self.datas[var].item()["times"][ - : min(self.time_cut_index, len(self.datas[var].item()["times"])) - ] - for var in self.datas.keys() + else time_dict[: min(self.time_cut_index, len(time_dict))] + for var in datas.keys() } + # Data Extraction - # self.u_wind = self.datas["U"].item()["values"] - # self.v_wind = self.datas["V"].item()["values"] - self.humidity = self.datas["R"].item()["values"] - self.temperature = self.datas["T"].item()["values"] + self.u_wind = datas["U"].item()["values"][:, :, index_lat, :][ + :, :, :, index_long + ][:, index_level, :, :] + self.v_wind = datas["V"].item()["values"][:, :, index_lat, :][ + :, :, :, index_long + ][:, index_level, :, :] + self.humidity = datas["R"].item()["values"][:, :, index_lat, :][ + :, :, :, index_long + ][:, index_level, :, :] + self.temperature = datas["T"].item()["values"][:, :, index_lat, :][ + :, :, :, index_long + ][:, index_level, :, :] if self.time_cut_index is not None: index_cut = min( self.time_cut_index, len(self.time_dict[list(self.time_dict.keys())[0]]), ) - # self.u_wind = self.u_wind[:index_cut, :, :, :] - # self.v_wind = self.v_wind[:index_cut, :, :, :] + self.u_wind = self.u_wind[:index_cut, :, :, :] + self.v_wind = self.v_wind[:index_cut, :, :, :] self.humidity = self.humidity[:index_cut, :, :, :] self.temperature = self.temperature[:index_cut, :, :, :] elif isinstance( @@ -109,76 +135,75 @@ def __init__(self, file_npz, time_cut_index=None, order_interp=1): var: self.datas[var]["times"] for var in self.datas.keys() } # Data Extraction - # self.u_wind = self.datas["U"]["values"] - # self.v_wind = self.datas["V"]["values"] + self.u_wind = self.datas["U"]["values"] + self.v_wind = self.datas["V"]["values"] self.humidity = self.datas["R"]["values"] self.temperature = self.datas["T"]["values"] for feat in self.lat_dict: if self.lat_dict[feat][-1] < self.lat_dict[feat][0]: self.lat_dict[feat] = self.lat_dict[feat][::-1] - # if feat == "U": - # self.u_wind = self.u_wind[:, :, ::-1, :] - # elif feat == "V": - # self.v_wind = self.v_wind[:, :, ::-1, :] + if feat == "U": + self.u_wind = self.u_wind[:, :, ::-1, :] + elif feat == "V": + self.v_wind = self.v_wind[:, :, ::-1, :] if feat == "R": self.humidity = self.humidity[:, :, ::-1, :] elif feat == "T": self.temperature = self.temperature[:, :, ::-1, :] - # self.norm_wind = np.sqrt(np.square(self.u_wind) + np.square(self.v_wind)) - # self.angle_wind = np.arctan2(self.v_wind, self.u_wind) + self.norm_wind = np.sqrt(np.square(self.u_wind) + np.square(self.v_wind)) + self.angle_wind = np.arctan2(self.v_wind, self.u_wind) self.interpol_dict = {} - # self.interpol_dict["wind"] = { - # "norm": intergrid.Intergrid( - # self.norm_wind, - # lo=[ - # min(self.time_dict["U"]), - # min(self.alt_dict["U"]), - # min(self.lat_dict["U"]), - # min(self.long_dict["U"]), - # ], - # hi=[ - # max(self.time_dict["U"]), - # max(self.alt_dict["U"]), - # max(self.lat_dict["U"]), - # max(self.long_dict["U"]), - # ], - # maps=[ - # self.time_dict["U"], - # self.alt_dict["U"], - # self.lat_dict["U"], - # self.long_dict["U"], - # ], - # verbose=False, - # order=order_interp, - # ), - - # "argument": intergrid.Intergrid( - # self.angle_wind, - # lo=[ - # min(self.time_dict["U"]), - # min(self.alt_dict["U"]), - # min(self.lat_dict["U"]), - # min(self.long_dict["U"]), - # ], - # hi=[ - # max(self.time_dict["U"]), - # max(self.alt_dict["U"]), - # max(self.lat_dict["U"]), - # max(self.long_dict["U"]), - # ], - # maps=[ - # self.time_dict["U"], - # self.alt_dict["U"], - # self.lat_dict["U"], - # self.long_dict["U"], - # ], - # verbose=False, - # order=order_interp, - # ), - # } + self.interpol_dict["wind"] = { + "norm": intergrid.Intergrid( + self.norm_wind, + lo=[ + min(self.time_dict["U"]), + min(self.alt_dict["U"]), + min(self.lat_dict["U"]), + min(self.long_dict["U"]), + ], + hi=[ + max(self.time_dict["U"]), + max(self.alt_dict["U"]), + max(self.lat_dict["U"]), + max(self.long_dict["U"]), + ], + maps=[ + self.time_dict["U"], + self.alt_dict["U"], + self.lat_dict["U"], + self.long_dict["U"], + ], + verbose=False, + order=order_interp, + ), + "argument": intergrid.Intergrid( + self.angle_wind, + lo=[ + min(self.time_dict["U"]), + min(self.alt_dict["U"]), + min(self.lat_dict["U"]), + min(self.long_dict["U"]), + ], + hi=[ + max(self.time_dict["U"]), + max(self.alt_dict["U"]), + max(self.lat_dict["U"]), + max(self.long_dict["U"]), + ], + maps=[ + self.time_dict["U"], + self.alt_dict["U"], + self.lat_dict["U"], + self.long_dict["U"], + ], + verbose=False, + order=order_interp, + ), + } self.interpol_dict["humidity"] = intergrid.Intergrid( self.humidity, lo=[ @@ -236,13 +261,16 @@ def interpol_wind_classic(self, lat, longi, alt=35000.0, t=0.0, **kwargs): :param t: time in second :return: [wind strength, direction, wind wector] """ - pass - # if longi < 0: - # longi += 360.0 - # norm = self.interpol_dict["wind"]["norm"]([t, alt, lat, longi]) - # arg = self.interpol_dict["wind"]["argument"]([t, alt, lat, longi]) - # result = norm * np.array([np.cos(arg), np.sin(arg)]) - # return [norm, arg, result] + + # convert altitude to Pa + alt = std_atm.alt2press(alt, alt_units="ft", press_units="hpa") + + if longi < 0: + longi += 360.0 + norm = self.interpol_dict["wind"]["norm"]([t, alt, lat, longi]) + arg = self.interpol_dict["wind"]["argument"]([t, alt, lat, longi]) + result = norm * np.array([np.cos(arg), np.sin(arg)]) + return [norm, arg, result] def interpol_wind(self, X): """ @@ -251,11 +279,14 @@ def interpol_wind(self, X): :param X: array of points [time (in s), alt (in ft), lat, long] :return: wind vector. """ - pass - # arg = self.interpol_dict["wind"]["argument"](X) - # return self.interpol_dict["wind"]["norm"](X) * np.array( - # [[np.cos(arg), np.sin(arg)]] - # ) + + # convert altitude to Pa + X[1] = std_atm.alt2press(X[1], alt_units="ft", press_units="hpa") + + arg = self.interpol_dict["wind"]["argument"](X) + return self.interpol_dict["wind"]["norm"](X) * np.array( + [[np.cos(arg), np.sin(arg)]] + ) def interpol_field(self, X, field="temperature"): """ @@ -265,6 +296,8 @@ def interpol_field(self, X, field="temperature"): :param field: field of weather data to interpolate (could be 'temperature' or 'humidity' :return: array of interpolated values """ + # convert altitude to Pa + X[1] = std_atm.alt2press(X[1], alt_units="ft", press_units="hpa") return self.interpol_dict[field](X) def transform_long(self, long): @@ -331,7 +364,6 @@ def plot_wind( Ut = np.resize(res[0, 0, :], (n_lat, n_long, n_time)) Vt = np.resize(res[0, 1, :], (n_lat, n_long, n_time)) Nt = np.sqrt(np.square(Ut) + np.square(Vt)) - # Nt = self.interpol_field(values, field="norw-wind") i = 0 CS = ax.contourf(x, y, Nt[:, :, i], 20, alpha=0.5, zorder=2) @@ -443,9 +475,7 @@ def plot_wind_noised( Nt_noised = np.sqrt(np.square(Ut_noised) + np.square(Vt_noised)) Ut = np.resize(res[0, 0, :], (n_lat, n_long, n_time)) Vt = np.resize(res[0, 1, :], (n_lat, n_long, n_time)) - Nt = np.sqrt(np.square(Ut - Ut_noised) + np.square(Vt - Vt_noised)) i = 0 - # CS = ax.contourf(x, y, Nt[:, :, i], 20, alpha=0.5, zorder=2) if plot_wind: if x.shape[0] > 100: q = ax.quiver( @@ -520,8 +550,6 @@ def plot_matrix_wind(self, index_alt=10, index_time=0, ax=None): extent=[-180.0, 180.0, -90.0, 90.0], alpha=0.5, ) - # plt.gca().invert_yaxis() - # ax.colorbar() def plot_matrix_wind_noised(self, index_alt=10, index_time=0, ax=None): """ @@ -636,4 +664,3 @@ def plot_field( def render(self, ax, **kwargs): pass - # self.plot_matrix_wind(index_alt=0, index_time=0, ax=ax) diff --git a/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/parser_pygrib.py b/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/parser_pygrib.py index 8a802d619f..c1be90622c 100644 --- a/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/parser_pygrib.py +++ b/skdecide/hub/domain/flight_planning/weather_interpolator/weather_tools/parser_pygrib.py @@ -36,8 +36,6 @@ def computeTimeStamps(dates, times, steps): ) for step in steps: forecast_datetime = date_object + datetime.timedelta(hours=int(step)) - # forecast_datetime = forecast_datetime.replace(tzinfo=pytz.utc) - # forecast_datetime.timestamp() timestamps.add(forecast_datetime.timestamp()) return list(timestamps) @@ -67,7 +65,6 @@ def computeTimeStamp(date, time, step): tzinfo=pytz.utc, ) forecast_datetime = date_object + datetime.timedelta(hours=int(step)) - # forecast_datetime.replace(tzinfo=pytz.utc) return datetime.datetime.timestamp(forecast_datetime) diff --git a/tests/flight_planning/aircraft_performance/test_aircraft_perf_model.py b/tests/flight_planning/aircraft_performance/test_aircraft_perf_model.py deleted file mode 100644 index 04d474425b..0000000000 --- a/tests/flight_planning/aircraft_performance/test_aircraft_perf_model.py +++ /dev/null @@ -1,65 +0,0 @@ -import inspect -import math -import sys - -import pytest - -if sys.version_info < (3, 9): - pytest.skip("cartopy requires python3.9 or higher", allow_module_level=True) -if sys.platform.startswith("win"): - pytest.skip("pygrib does not install on windows", allow_module_level=True) - - -@pytest.fixture(scope="function") -def ac_model(model): - from skdecide.hub.domain.flight_planning.aircraft_performance.base import ( - AircraftPerformanceModel, - ) - - out = AircraftPerformanceModel(actype="A320", perf_model=model) - yield out - - -@pytest.mark.parametrize( - "model, mass, alt, speed, delta_time, path_angle, temp, expected, expected_openap1", - [ - ("openap", 200_000, 10_000, 300, 10, 0.0, 273, 17.1, 9.5), - ("openap", 200_000, 10_000, 310, 50, 10.0, 273, 84.8, 46.6), - ("openap", 220_000, 10_000, 280, 60, -5.0, 273, 12.0, 17.3), - ("PS", 200_000, 10_000, 300, 10, 0.0, 273, 6.4, None), - ("PS", 200_000, 10_000, 310, 50, 10.0, 273, 86.7, None), - ("PS", 220_000, 10_000, 280, 60, -5.0, 273, 11.0, None), - ], -) -def test_perf_model( - ac_model, - model, - mass, - alt, - speed, - delta_time, - path_angle, - temp, - expected, - expected_openap1, -): - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.utils.aero import ( - ft, - kts, - ) - - if model == "openap": - from openap import FuelFlow - - if "path_angle" in inspect.signature(FuelFlow.enroute).parameters: - # openap <= 1.5 - expected = expected_openap1 - - fpm = ft / 60 - vs = math.tan(math.radians(path_angle)) * speed * kts / fpm - - assert ac_model.compute_fuel_consumption( - values_current={"mass": mass, "alt": alt, "speed": speed, "temp": temp}, - delta_time=delta_time, - vs=vs, - ) == pytest.approx(expected, abs=1e-1) diff --git a/tests/flight_planning/aircraft_performance/test_openap.py b/tests/flight_planning/aircraft_performance/test_openap.py new file mode 100644 index 0000000000..28d8b2fc03 --- /dev/null +++ b/tests/flight_planning/aircraft_performance/test_openap.py @@ -0,0 +1,173 @@ +import sys + +import pytest + + +@pytest.mark.skipif( + sys.version_info < (3, 9), reason="cartopy requires python3.9 or higher" +) +@pytest.mark.skipif( + sys.platform.startswith("win"), reason="pygrib does not install on windows" +) +def test_thrust(): + from itertools import product + + import numpy as np + from openap.extra.aero import ft, kts, mach2tas + from openap.thrust import Thrust + + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service.propulsion_service import ( + PropulsionService, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.isa_atmosphere_settings import ( + IsaAtmosphereSettings, + ) + + openap_propu = PropulsionService() + openap_settings = openap_propu.init_settings("A320", PerformanceModelEnum.OPENAP) + openap_thrust = Thrust(ac="A320") + + atmosphere_service = AtmosphereService() + + list_zp_ft = [10000, 20000, 30000, 40000] + list_gw_kg = [50_000, 60_000, 70_000, 80_000, 90_000, 100_000] + list_mach = [0.6, 0.7, 0.8, 0.9] + list_disa = [-10, 0, 10] + + list_test = list(product(list_zp_ft, list_gw_kg, list_mach, list_disa)) + + for zp_ft, gw_kg, mach, disa in list_test: + # initial state of the aircraft + acState = AircraftState( + model_type="A320", # only for OPENAP and POLL_SCHUMANN + performance_model_type=PerformanceModelEnum.OPENAP, # PerformanceModelEnum.OPENAP, PerformanceModelEnum.BADA + gw_kg=gw_kg, + zp_ft=zp_ft, + mach_cruise=mach, + cas_climb_kts=170, + cas_descent_kts=250, + phase=PhaseEnum.CRUISE, + rating_level=RatingEnum.MCL, + cg=0.3, + gamma_air_deg=0, + ) + + # current state + acState.weather_state = atmosphere_service.retrieve_weather_state( + atmosphere_settings=IsaAtmosphereSettings(d_isa=disa), + four_dimensions_state=acState, + ) + acState.mach = mach + + # compute + val_skdecide = openap_propu.compute_total_net_thrust_n( + propulsion_settings=openap_settings, aircraft_state=acState + ) + + val_true = openap_thrust.cruise( + tas=mach2tas(acState.mach, acState.zp_ft * ft) / kts, + alt=acState.zp_ft, + ) + + np.testing.assert_almost_equal(val_skdecide, val_true, decimal=1) + + +@pytest.mark.skipif( + sys.version_info < (3, 9), reason="cartopy requires python3.9 or higher" +) +@pytest.mark.skipif( + sys.platform.startswith("win"), reason="pygrib does not install on windows" +) +def test_fuelflow(): + from itertools import product + + import numpy as np + from openap.extra.aero import ft, kts, mach2tas + from openap.fuel import FuelFlow + + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service.propulsion_service import ( + PropulsionService, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.isa_atmosphere_settings import ( + IsaAtmosphereSettings, + ) + + openap_propu = PropulsionService() + openap_settings = openap_propu.init_settings("A320", PerformanceModelEnum.OPENAP) + openap_fuelflow = FuelFlow(ac="A320") + + atmosphere_service = AtmosphereService() + + list_zp_ft = [10000, 20000, 30000, 40000] + list_gw_kg = [50_000, 60_000, 70_000, 80_000, 90_000, 100_000] + list_mach = [0.6, 0.7, 0.8, 0.9] + list_disa = [-10, 0, 10] + + list_test = list(product(list_zp_ft, list_gw_kg, list_mach, list_disa)) + + for zp_ft, gw_kg, mach, disa in list_test: + # initial state of the aircraft + acState = AircraftState( + model_type="A320", # only for OPENAP and POLL_SCHUMANN + performance_model_type=PerformanceModelEnum.OPENAP, # PerformanceModelEnum.OPENAP, PerformanceModelEnum.BADA + gw_kg=gw_kg, + zp_ft=zp_ft, + mach_cruise=mach, + cas_climb_kts=170, + cas_descent_kts=250, + phase=PhaseEnum.CRUISE, + rating_level=RatingEnum.MCL, + cg=0.3, + gamma_air_deg=0, + ) + + # current state + acState.weather_state = atmosphere_service.retrieve_weather_state( + atmosphere_settings=IsaAtmosphereSettings(d_isa=disa), + four_dimensions_state=acState, + ) + acState.mach = mach + + # compute + val_skdecide = openap_propu.compute_total_fuel_flow_kg_per_sec( + propulsion_settings=openap_settings, aircraft_state=acState + ) + + val_true = openap_fuelflow.enroute( + mass=acState.gw_kg, + tas=mach2tas(acState.mach, acState.zp_ft * ft) / kts, + alt=acState.zp_ft, + vs=0, + ) + + np.testing.assert_almost_equal(val_skdecide, val_true, decimal=1) diff --git a/tests/flight_planning/aircraft_performance/test_poll_schumann.py b/tests/flight_planning/aircraft_performance/test_poll_schumann.py index 656e78a695..2db7cbd360 100644 --- a/tests/flight_planning/aircraft_performance/test_poll_schumann.py +++ b/tests/flight_planning/aircraft_performance/test_poll_schumann.py @@ -1,329 +1,203 @@ import sys -import numpy as np import pytest -if sys.version_info < (3, 9): - pytest.skip("cartopy requires python3.9 or higher", allow_module_level=True) -if sys.platform.startswith("win"): - pytest.skip("pygrib does not install on windows", allow_module_level=True) - - -def test_speed_of_sound(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - - T_15 = 288.15 - assert atm_params.local_speed_of_sound(T_15) == pytest.approx(340.2, rel=1e-3) - - -def test_dynamic_viscosity(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - - T_15 = 288.15 - assert atm_params.dynamic_viscosity(T_15) == pytest.approx(1.789e-5, rel=1e-2) - - -def test_air_density(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - - T_0 = 273.15 - pressure_0 = 100_000 - assert atm_params.air_density(pressure_0, T_0) == pytest.approx(1.2754, rel=1e-3) - - -def test_reynolds_number(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) - - T_15 = 288.15 - aircraft_parameters = load_aircraft_engine_params("A320") - wing_aspect_ratio = aircraft_parameters["wing_aspect_ratio"] - wing_span = aircraft_parameters["wing_span"] - mach_number = 0.78 - pressure_0 = 100_000 - assert atm_params.reynolds_number( - wing_span, wing_aspect_ratio, mach_number, T_15, pressure_0 - ) == pytest.approx(64_412_748, rel=1e-3) - - -def test_rocd(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.jet as jet - - altitude_current = 34_000 - altitude_next = 35_000 - delta_time = 30 - assert jet.rate_of_climb_descent( - altitude_current, altitude_next, delta_time - ) == pytest.approx((altitude_next - altitude_current) / (delta_time / 60), rel=1e-4) - - -def test_lift_coefficient(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) - - aircraft_parameters = load_aircraft_engine_params("A320") - wing_surface_area = aircraft_parameters["wing_surface_area"] - mtow = aircraft_parameters["amass_mtow"] - T_0 = 273.15 - mach_number = 0.78 - pressure_0 = 100_000 - climb_angle = 0 - assert atm_params.lift_coefficient( - wing_surface_area, mtow, pressure_0, T_0, mach_number, climb_angle - ) == pytest.approx(0.13828, rel=1e-3) - - -def test_skin_friction_coefficient(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) - - aircraft_parameters = load_aircraft_engine_params("A320") - wing_aspect_ratio = aircraft_parameters["wing_aspect_ratio"] - wing_span = aircraft_parameters["wing_span"] - T_15 = 288.15 - mach_number = 0.78 - pressure_0 = 100_000 - reynolds_number = atm_params.reynolds_number( - wing_span, wing_aspect_ratio, mach_number, T_15, pressure_0 - ) - assert atm_params.skin_friction_coefficient(reynolds_number) == pytest.approx( - 0.0269 / (reynolds_number**0.14), rel=1e-5 - ) - - -def test_zero_lift_drag(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) - - aircraft_parameters = load_aircraft_engine_params("A320") - psi_0 = aircraft_parameters["psi_0"] - reynolds_number = 64_412_748 - assert atm_params.zero_lift_drag_coefficient( - 0.0269 / (reynolds_number**0.14), psi_0 - ) == pytest.approx(0.0269 / (reynolds_number**0.14) * psi_0, rel=1e-5) +@pytest.mark.skipif( + sys.version_info < (3, 9), reason="cartopy requires python3.9 or higher" +) +@pytest.mark.skipif( + sys.platform.startswith("win"), reason="pygrib does not install on windows" +) +def test_drag(): + import numpy as np + from openap.extra.aero import ft, kts, mach2tas -def test_oswald_efficiency_factor2(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, ) - - aircraft_parameters = load_aircraft_engine_params("A320") - wing_aspect_ratio = aircraft_parameters["wing_aspect_ratio"] - wing_span = aircraft_parameters["wing_span"] - psi_0 = aircraft_parameters["psi_0"] - T_15 = 288.15 - mach_number = 0.78 - pressure_0 = 100_000 - reynolds_number = atm_params.reynolds_number( - wing_span, wing_aspect_ratio, mach_number, T_15, pressure_0 + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.atmos_isa import ( + temperature, ) - zero_lift_drag = 0.0269 / (reynolds_number**0.14) * psi_0 - assert atm_params.oswald_efficiency_factor( - zero_lift_drag, aircraft_parameters - ) == pytest.approx(0.85, rel=1e-2) - - -def test_k1(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.aero.service.aerodynamics_service import ( + AerodynamicsService, ) - - aircraft_parameters = load_aircraft_engine_params("A320") - psi_0 = aircraft_parameters["psi_0"] - reynolds_number = 64_412_748 - zero_lift_drag = 0.0269 / (reynolds_number**0.14) * psi_0 - cos_sweep = aircraft_parameters["cos_sweep"] - assert atm_params._non_vortex_lift_dependent_drag_factor( - zero_lift_drag, cos_sweep - ) == pytest.approx(0.80 * (1 - 0.53 * cos_sweep) * zero_lift_drag, rel=1e-2) - - -def test_wave_drag_coefficient(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, ) - - aircraft_parameters = load_aircraft_engine_params("A320") - c_lift = 0.13828 - mach_number = 0.78 - assert atm_params.wave_drag_coefficient( - mach_number, c_lift, aircraft_parameters - ) == pytest.approx(0.00049245, rel=1e-2) - - -def test_airframe_drag_coefficient(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, ) - - aircraft_parameters = load_aircraft_engine_params("A320") - c_lift = 0.13828 - psi_0 = aircraft_parameters["psi_0"] - reynolds_number = 64_412_748 - zero_lift_drag = atm_params.zero_lift_drag_coefficient( - 0.0269 / (reynolds_number**0.14), psi_0 + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, ) - wave_drag = 0.00049245 - oswald_efficiency = atm_params.oswald_efficiency_factor( - zero_lift_drag, aircraft_parameters + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, ) - wing_aspect_ratio = aircraft_parameters["wing_aspect_ratio"] - assert atm_params.airframe_drag_coefficient( - zero_lift_drag, wave_drag, c_lift, oswald_efficiency, wing_aspect_ratio - ) == pytest.approx(0.019465667160460293, rel=1e-2) - - -def test_thrust_force(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.isa_atmosphere_settings import ( + IsaAtmosphereSettings, ) - aircraft_parameters = load_aircraft_engine_params("A320") - c_lift = 0.13828 - c_drag = 0.019465667160460293 - mtow = aircraft_parameters["amass_mtow"] - climb_angle = 0 - assert atm_params.thrust_force( - mtow, c_lift, c_drag, 0, climb_angle - ) == pytest.approx(101470, rel=1e-2) - - -def test_engine_thrust_coefficient(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, + atmosphere_service = AtmosphereService() + poll_schumann_aero = AerodynamicsService() + poll_schumann_settings = poll_schumann_aero.init_settings( + "A320", PerformanceModelEnum.POLL_SCHUMANN ) - f_thrust = 101470 - aircraft_parameters = load_aircraft_engine_params("A320") - wing_surface_area = aircraft_parameters["wing_surface_area"] - mach_number = 0.78 - pressure_0 = 100_000 - assert atm_params.engine_thrust_coefficient( - f_thrust, mach_number, pressure_0, wing_surface_area - ) == pytest.approx(0.01946566716046029, rel=1e-1) + test_cases = [ + { + "zp_ft": 34000, + "expected_cl": 0.475, + "expected_cd": 0.0285, + "dISA": 220.79 - temperature(34000, disa=0), + }, + { + "zp_ft": 41450, + "expected_cl": 0.679, + "expected_cd": 0.0402, + "dISA": 216.65 - temperature(34000, disa=0), + }, + ] + for case in test_cases: + acState = AircraftState( + model_type="A320", + performance_model_type=PerformanceModelEnum.OPENAP, + gw_kg=58800.0, + zp_ft=case["zp_ft"], + mach_cruise=0.753, + cas_climb_kts=170, + cas_descent_kts=250, + phase=PhaseEnum.CRUISE, + rating_level=RatingEnum.MCL, + cg=0.3, + gamma_air_deg=0, + ) -def test_thrust_coefficient_at_max_efficiency(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) - - aircraft_parameters = load_aircraft_engine_params("A320") - mach_number = 0.78 - assert atm_params.thrust_coefficient_at_max_efficiency( - mach_number, aircraft_parameters["m_des"], aircraft_parameters["c_t_des"] - ) == pytest.approx(0.03267886563990706, rel=1e-1) - - -def test_max_available_thrust_coeff(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.operational_limits as op_lim - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) + isa_atmosphere_settings = IsaAtmosphereSettings(d_isa=case["dISA"]) - aircraft_parameters = load_aircraft_engine_params("A320") - c_t_eta_b = 0.03267886563990706 - T_15 = 288.15 - mach_number = 0.78 - assert op_lim.max_available_thrust_coefficient( - T_15, mach_number, c_t_eta_b, aircraft_parameters - ) == pytest.approx(0.019882296940110962, rel=1e-1) + weather_state = atmosphere_service.retrieve_weather_state( + atmosphere_settings=isa_atmosphere_settings, four_dimensions_state=acState + ) + acState.weather_state = weather_state + acState.mach = 0.753 -def test_overall_prop_efficiency(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) + delta = acState.weather_state.static_pressure_pa / 101325.0 - c_t_available = 0.019882296940110962 - c_t = 0.01946566716046029 - c_t = np.clip(c_t, 0, c_t_available) - c_t_eta_b = 0.03267886563990706 - eta_over_eta_b_min = 0.5 - aircraft_parameters = load_aircraft_engine_params("A320") - mach_number = 0.78 - assert atm_params.overall_propulsion_efficiency( - mach_number, c_t, c_t_eta_b, aircraft_parameters, eta_over_eta_b_min - ) == pytest.approx(0.28091506251406534, rel=1e-2) + acState.cl = (2 * acState.gw_kg * 9.80665) / ( + delta * 101325.0 * 1.4 * poll_schumann_settings.sref * acState.mach**2 + ) + np.testing.assert_almost_equal(acState.cl, case["expected_cl"], decimal=2) -def test_fuel_mass_flow_rate(): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) + val_skdecide = poll_schumann_aero.compute_drag_coefficient( + aerodynamics_settings=poll_schumann_settings, aircraft_state=acState + ) - c_t = 0.01946566716046029 - engine_efficiency = 0.28091506251406534 - q_fuel = 43.13e6 - aircraft_parameters = load_aircraft_engine_params("A320") - wing_surface_area = aircraft_parameters["wing_surface_area"] - T_15 = 288.15 - mach_number = 0.78 - pressure_0 = 100_000 - assert atm_params.fuel_mass_flow_rate( - pressure_0, T_15, mach_number, c_t, engine_efficiency, wing_surface_area, q_fuel - ) == pytest.approx(702.9593810712935, rel=1e-1) + np.testing.assert_almost_equal(val_skdecide, case["expected_cd"], decimal=4) -@pytest.mark.parametrize( - "rocd, expected", - [ - (0, 1.8787841814021262), - (250, 1.8787841814021262), - (-250, 0.6449999999999999), - (251, 1.8787841814021262), - (-251, 0.6449999999999999), - ], +@pytest.mark.skipif( + sys.version_info < (3, 9), reason="cartopy requires python3.9 or higher" ) -def test_fuel_flow_correction(rocd, expected): - import skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.parameters.atmospheric_parameters as atm_params - from skdecide.hub.domain.flight_planning.aircraft_performance.poll_schumann_utils.engine_loader import ( - load_aircraft_engine_params, - ) - - MIN_CRUISE_ALTITUDE = 20_000.0 - rocd_threshold = 250.0 - fuel_flow = 702.9593810712935 - altitude_current = 34_000 - cruise = ( - (rocd < rocd_threshold) - & (rocd > -rocd_threshold) - & (altitude_current > MIN_CRUISE_ALTITUDE) - ) - climb = ~cruise & (rocd > 0.0) - descent = ~cruise & (rocd < 0.0) - - # convert to string - flight_phase = np.where(cruise, "cruise", np.where(climb, "climb", "descent")) - aircraft_parameters = load_aircraft_engine_params("A320") - T_15 = 288.15 - mach_number = 0.78 - pressure_0 = 100_000 - assert atm_params.fuel_flow_correction( - fuel_flow, - altitude_current, - T_15, - pressure_0, - mach_number, - aircraft_parameters["ff_idle_sls"], - aircraft_parameters["ff_max_sls"], - flight_phase, - ) == pytest.approx(expected, rel=1e-1) +@pytest.mark.skipif( + sys.platform.startswith("win"), reason="pygrib does not install on windows" +) +def test_thrust(): + import numpy as np + from openap.extra.aero import ft, kts, mach2tas + + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.atmos_isa import ( + temperature, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.propulsion.service.propulsion_service import ( + PropulsionService, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.service.atmosphere_service import ( + AtmosphereService, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.weather.settings.isa_atmosphere_settings import ( + IsaAtmosphereSettings, + ) + + atmosphere_service = AtmosphereService() + poll_schumann_propu = PropulsionService() + poll_schumann_settings = poll_schumann_propu.init_settings( + "A320", PerformanceModelEnum.POLL_SCHUMANN + ) + + test_cases = [ + { + "zp_ft": 34000, + "expected_cl": 0.475, + "expected_fn": 3.4638, + "expected_ff": 0.593, + "dISA": 220.79 - temperature(34000, disa=0), + }, + { + "zp_ft": 41450, + "expected_cl": 0.679, + "expected_fn": 3.4156, + "expected_ff": 0.5710, + "dISA": 216.65 - temperature(34000, disa=0), + }, + ] + + for case in test_cases: + acState = AircraftState( + model_type="A320", + performance_model_type=PerformanceModelEnum.OPENAP, + gw_kg=58800.0, + zp_ft=case["zp_ft"], + mach_cruise=0.753, + cas_climb_kts=170, + cas_descent_kts=250, + phase=PhaseEnum.CRUISE, + rating_level=RatingEnum.MCL, + cg=0.3, + gamma_air_deg=0, + ) + + isa_atmosphere_settings = IsaAtmosphereSettings(d_isa=case["dISA"]) + + weather_state = atmosphere_service.retrieve_weather_state( + atmosphere_settings=isa_atmosphere_settings, four_dimensions_state=acState + ) + + acState.weather_state = weather_state + acState.mach = 0.753 + + delta = acState.weather_state.static_pressure_pa / 101325.0 + + acState.cl = (2 * acState.gw_kg * 9.80665) / ( + delta * 101325.0 * 1.4 * poll_schumann_settings.sref * acState.mach**2 + ) + + np.testing.assert_almost_equal(acState.cl, case["expected_cl"], decimal=2) + + val_skdecide = poll_schumann_propu.compute_total_net_thrust_n( + propulsion_settings=poll_schumann_settings, aircraft_state=acState + ) + + np.testing.assert_almost_equal( + val_skdecide / 1e4, case["expected_fn"], decimal=2 + ) + + val_skdecide = poll_schumann_propu.compute_total_fuel_flow_kg_per_sec( + propulsion_settings=poll_schumann_settings, aircraft_state=acState + ) + + np.testing.assert_almost_equal(val_skdecide, case["expected_ff"], decimal=3) diff --git a/tests/flight_planning/test_flight_planning.py b/tests/flight_planning/test_flight_planning.py index 5fbd519839..604d3bcb6c 100644 --- a/tests/flight_planning/test_flight_planning.py +++ b/tests/flight_planning/test_flight_planning.py @@ -11,30 +11,68 @@ @pytest.mark.skipif( sys.platform.startswith("win"), reason="pygrib does not install on windows" ) -def test_flight_planning(): - from skdecide.hub.domain.flight_planning.domain import FlightPlanningDomain +def test_aircraft_state(): + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, + ) - origin = "LFPG" - destination = "LFBO" - actype = "A320" - heuristic = "lazy_fuel" - cost_function = "fuel" - domain_factory = lambda: FlightPlanningDomain( - origin=origin, - destination=destination, - actype=actype, - heuristic_name=heuristic, - objective=cost_function, - fuel_loop=False, - graph_width="normal", + acState_openap = AircraftState( + model_type="A320", # only for OPENAP and POLL_SCHUMANN + performance_model_type=PerformanceModelEnum.OPENAP, # PerformanceModelEnum.OPENAP, PerformanceModelEnum.BADA + gw_kg=80_000, + zp_ft=10_000, + mach_cruise=0.78, + cas_climb_kts=170, + cas_descent_kts=250, + phase=PhaseEnum.CLIMB, + rating_level=RatingEnum.MCL, + cg=0.3, + gamma_air_deg=0, ) - domain = domain_factory() - solver = LazyAstar( - domain_factory=domain_factory, heuristic=lambda d, s: d.heuristic(s) + + # check that the aircraft state is correctly initialized + assert acState_openap.model_type == "A320" + assert acState_openap.performance_model_type == PerformanceModelEnum.OPENAP + assert acState_openap.gw_kg == 80_000 + assert acState_openap.zp_ft == 10_000 + assert acState_openap.mach_cruise == 0.78 + assert acState_openap.cas_climb_kts == 170 + assert acState_openap.cas_descent_kts == 250 + assert acState_openap.phase == PhaseEnum.CLIMB + assert acState_openap.rating_level == RatingEnum.MCL + assert acState_openap.cg == 0.3 + assert acState_openap.gamma_air_deg == 0 + + acState_poll_schumann = AircraftState( + # model_type="BADA/A320-271N", # only for BADA + model_type="A320", # only for OPENAP and POLL_SCHUMANN + performance_model_type=PerformanceModelEnum.POLL_SCHUMANN, # PerformanceModelEnum.OPENAP + gw_kg=80_000, + zp_ft=10_000, + mach_cruise=0.78, + cas_climb_kts=170, + cas_descent_kts=250, + phase=PhaseEnum.CLIMB, + rating_level=RatingEnum.MCL, + cg=0.3, + gamma_air_deg=0, ) - solver.solve() - assert solver.check_domain(domain) + # check that the aircraft state is correctly initialized + assert acState_poll_schumann.model_type == "A320" + assert ( + acState_poll_schumann.performance_model_type + == PerformanceModelEnum.POLL_SCHUMANN + ) @pytest.mark.skipif( @@ -43,29 +81,57 @@ def test_flight_planning(): @pytest.mark.skipif( sys.platform.startswith("win"), reason="pygrib does not install on windows" ) -def test_flight_planning_fuel_loop(): - from openap.prop import aircraft +def test_flight_planning(): + from skdecide.hub.domain.flight_planning.aircraft_performance.bean.aircraft_state import ( + AircraftState, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.performance_model_enum import ( + PerformanceModelEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.phase_enum import ( + PhaseEnum, + ) + from skdecide.hub.domain.flight_planning.aircraft_performance.performance.rating_enum import ( + RatingEnum, + ) + from skdecide.hub.domain.flight_planning.domain import ( + FlightPlanningDomain, + WeatherDate, + ) + + acState_poll_schumann = AircraftState( + model_type="A320", # only for OPENAP and POLL_SCHUMANN + performance_model_type=PerformanceModelEnum.POLL_SCHUMANN, # PerformanceModelEnum.OPENAP + gw_kg=80_000, + zp_ft=10_000, + mach_cruise=0.78, + cas_climb_kts=170, + cas_descent_kts=250, + phase=PhaseEnum.CLIMB, + rating_level=RatingEnum.MCL, + cg=0.3, + gamma_air_deg=0, + ) - from skdecide.hub.domain.flight_planning.domain import FlightPlanningDomain + weather_date = WeatherDate(day=1, month=12, year=2024) - origin = "LFPG" - destination = "LFBO" - actype = "A320" - heuristic = "lazy_fuel" - cost_function = "fuel" - constraints = {"fuel": aircraft(actype)["limits"]["MFC"]} domain_factory = lambda: FlightPlanningDomain( - origin=origin, - destination=destination, - actype=actype, - constraints=constraints, - heuristic_name=heuristic, - objective=cost_function, - fuel_loop=True, - graph_width="normal", - fuel_loop_tol=1.0, + origin="LFBO", + destination="LFPG", + aircraft_state=acState_poll_schumann, + objective="fuel", + heuristic_name="lazy_fuel", + weather_date=weather_date, + cruise_height_min=32_000, + cruise_height_max=38_000, + graph_width="medium", + nb_vertical_points=3, + nb_forward_points=5, + nb_lateral_points=11, ) + domain = domain_factory() + solver = LazyAstar( domain_factory=domain_factory, heuristic=lambda d, s: d.heuristic(s) )