setuav-pythrust 0.1.0__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- pythrust/__init__.py +4 -0
- pythrust/motors/__init__.py +6 -0
- pythrust/motors/database.py +130 -0
- pythrust/openmdao/__init__.py +3 -0
- pythrust/openmdao/components.py +103 -0
- pythrust/propellers/__init__.py +8 -0
- pythrust/propellers/database.py +316 -0
- pythrust/propulsion/__init__.py +15 -0
- pythrust/propulsion/autotune.py +279 -0
- pythrust/propulsion/models.py +121 -0
- pythrust/propulsion/solver.py +260 -0
- setuav_pythrust-0.1.0.dist-info/METADATA +56 -0
- setuav_pythrust-0.1.0.dist-info/RECORD +16 -0
- setuav_pythrust-0.1.0.dist-info/WHEEL +5 -0
- setuav_pythrust-0.1.0.dist-info/licenses/LICENSE +176 -0
- setuav_pythrust-0.1.0.dist-info/top_level.txt +1 -0
pythrust/__init__.py
ADDED
|
@@ -0,0 +1,130 @@
|
|
|
1
|
+
"""Brushless motor database loader and query interface."""
|
|
2
|
+
|
|
3
|
+
from __future__ import annotations
|
|
4
|
+
|
|
5
|
+
from dataclasses import dataclass
|
|
6
|
+
from pathlib import Path
|
|
7
|
+
import json
|
|
8
|
+
from typing import Dict, List, Optional
|
|
9
|
+
from pythrust.propulsion.models import MotorSpec
|
|
10
|
+
|
|
11
|
+
|
|
12
|
+
@dataclass(frozen=True)
|
|
13
|
+
class MotorEntry:
|
|
14
|
+
"""A database entry for a single brushless motor."""
|
|
15
|
+
id: str
|
|
16
|
+
name: str
|
|
17
|
+
manufacturer: str
|
|
18
|
+
kv: float
|
|
19
|
+
resistance: float
|
|
20
|
+
io: float
|
|
21
|
+
max_current: float
|
|
22
|
+
weight_g: float
|
|
23
|
+
max_power: float
|
|
24
|
+
io_voltage: float
|
|
25
|
+
|
|
26
|
+
def to_spec(self) -> MotorSpec:
|
|
27
|
+
"""Convert the database entry to a PyThrust MotorSpec object."""
|
|
28
|
+
return MotorSpec(
|
|
29
|
+
kv_rpm_per_v=self.kv,
|
|
30
|
+
resistance_ohm=self.resistance,
|
|
31
|
+
no_load_current_a=self.io,
|
|
32
|
+
current_max_a=self.max_current,
|
|
33
|
+
no_load_voltage_v=self.io_voltage,
|
|
34
|
+
)
|
|
35
|
+
|
|
36
|
+
|
|
37
|
+
class MotorDatabase:
|
|
38
|
+
"""Load and query brushless motor database from JSON files."""
|
|
39
|
+
|
|
40
|
+
def __init__(self) -> None:
|
|
41
|
+
"""Create an empty motor database."""
|
|
42
|
+
self._entries: Dict[str, MotorEntry] = {}
|
|
43
|
+
self._loaded = False
|
|
44
|
+
|
|
45
|
+
@property
|
|
46
|
+
def is_loaded(self) -> bool:
|
|
47
|
+
"""Return True if a database has been successfully loaded."""
|
|
48
|
+
return self._loaded
|
|
49
|
+
|
|
50
|
+
@property
|
|
51
|
+
def motor_count(self) -> int:
|
|
52
|
+
"""Return the number of motors in the database."""
|
|
53
|
+
return len(self._entries)
|
|
54
|
+
|
|
55
|
+
def list_motors(self) -> List[str]:
|
|
56
|
+
"""Return sorted unique motor IDs in the database."""
|
|
57
|
+
return sorted(self._entries.keys())
|
|
58
|
+
|
|
59
|
+
def get(self, motor_id: str) -> Optional[MotorEntry]:
|
|
60
|
+
"""Get a motor entry by its unique ID."""
|
|
61
|
+
return self._entries.get(motor_id)
|
|
62
|
+
|
|
63
|
+
def load(self, data_dir: Path) -> bool:
|
|
64
|
+
"""Load all motor JSON entries from a dataset directory."""
|
|
65
|
+
data_dir = Path(data_dir)
|
|
66
|
+
if not data_dir.exists():
|
|
67
|
+
self._loaded = False
|
|
68
|
+
return False
|
|
69
|
+
|
|
70
|
+
self._entries.clear()
|
|
71
|
+
|
|
72
|
+
# Recursively search for and load all .json files under the directory
|
|
73
|
+
for json_path in sorted(data_dir.glob("**/*.json")):
|
|
74
|
+
self.load_entry(json_path)
|
|
75
|
+
|
|
76
|
+
self._loaded = bool(self._entries)
|
|
77
|
+
return self._loaded
|
|
78
|
+
|
|
79
|
+
def load_entry(self, json_path: Path) -> Optional[MotorEntry]:
|
|
80
|
+
"""Load a single motor JSON file and store its entry."""
|
|
81
|
+
json_path = Path(json_path)
|
|
82
|
+
if not json_path.exists():
|
|
83
|
+
return None
|
|
84
|
+
try:
|
|
85
|
+
with open(json_path, "r", encoding="utf-8") as f:
|
|
86
|
+
m = json.load(f)
|
|
87
|
+
|
|
88
|
+
entry = MotorEntry(
|
|
89
|
+
id=m.get("id", ""),
|
|
90
|
+
name=m.get("name", "Unknown"),
|
|
91
|
+
manufacturer=m.get("manufacturer", "Unknown"),
|
|
92
|
+
kv=float(m.get("kv", 0.0)),
|
|
93
|
+
resistance=float(m.get("resistance", 0.0)),
|
|
94
|
+
io=float(m.get("io", 0.0)),
|
|
95
|
+
max_current=float(m.get("max_current", 0.0)),
|
|
96
|
+
weight_g=float(m.get("weight_g", 0.0)),
|
|
97
|
+
max_power=float(m.get("max_power", 0.0)),
|
|
98
|
+
io_voltage=float(m.get("io_voltage", 10.0)),
|
|
99
|
+
)
|
|
100
|
+
if entry.id:
|
|
101
|
+
self._entries[entry.id] = entry
|
|
102
|
+
self._loaded = True
|
|
103
|
+
return entry
|
|
104
|
+
except Exception:
|
|
105
|
+
pass
|
|
106
|
+
return None
|
|
107
|
+
|
|
108
|
+
def search(
|
|
109
|
+
self,
|
|
110
|
+
min_kv: Optional[float] = None,
|
|
111
|
+
max_kv: Optional[float] = None,
|
|
112
|
+
min_max_current: Optional[float] = None,
|
|
113
|
+
min_weight: Optional[float] = None,
|
|
114
|
+
max_weight: Optional[float] = None,
|
|
115
|
+
) -> List[MotorEntry]:
|
|
116
|
+
"""Search and filter motors in the database matching specified criteria."""
|
|
117
|
+
results = []
|
|
118
|
+
for entry in self._entries.values():
|
|
119
|
+
if min_kv is not None and entry.kv < min_kv:
|
|
120
|
+
continue
|
|
121
|
+
if max_kv is not None and entry.kv > max_kv:
|
|
122
|
+
continue
|
|
123
|
+
if min_max_current is not None and entry.max_current < min_max_current:
|
|
124
|
+
continue
|
|
125
|
+
if min_weight is not None and entry.weight_g < min_weight:
|
|
126
|
+
continue
|
|
127
|
+
if max_weight is not None and entry.weight_g > max_weight:
|
|
128
|
+
continue
|
|
129
|
+
results.append(entry)
|
|
130
|
+
return results
|
|
@@ -0,0 +1,103 @@
|
|
|
1
|
+
"""OpenMDAO wrapper component for PyThrust propulsion solver."""
|
|
2
|
+
|
|
3
|
+
from __future__ import annotations
|
|
4
|
+
|
|
5
|
+
import math
|
|
6
|
+
import openmdao.api as om
|
|
7
|
+
|
|
8
|
+
from pythrust.propellers.database import PropellerEntry
|
|
9
|
+
from pythrust.propulsion import (
|
|
10
|
+
BatterySpec,
|
|
11
|
+
MotorSpec,
|
|
12
|
+
PropellerSpec,
|
|
13
|
+
PropulsionSolver,
|
|
14
|
+
SystemSpec,
|
|
15
|
+
)
|
|
16
|
+
|
|
17
|
+
|
|
18
|
+
class PropulsionComponent(om.ExplicitComponent):
|
|
19
|
+
"""OpenMDAO ExplicitComponent wrapping the PyThrust propulsion solver."""
|
|
20
|
+
|
|
21
|
+
def initialize(self) -> None:
|
|
22
|
+
self.options.declare(
|
|
23
|
+
'prop_entry',
|
|
24
|
+
types=PropellerEntry,
|
|
25
|
+
desc='PropellerEntry database object',
|
|
26
|
+
)
|
|
27
|
+
|
|
28
|
+
def setup(self) -> None:
|
|
29
|
+
# Inputs
|
|
30
|
+
self.add_input('kv_rpm_per_v', val=860.0, desc='Motor Kv [RPM/V]')
|
|
31
|
+
self.add_input('resistance_ohm', val=0.0258, desc='Motor winding resistance [ohm]')
|
|
32
|
+
self.add_input('no_load_current_a', val=1.3, desc='Motor no-load current [A]')
|
|
33
|
+
self.add_input('current_max_a', val=65.0, desc='Motor maximum current [A]')
|
|
34
|
+
|
|
35
|
+
self.add_input('voltage_v', val=14.8, desc='Battery pack voltage [V]')
|
|
36
|
+
self.add_input('discharge_efficiency', val=1.0, desc='Battery discharge efficiency')
|
|
37
|
+
|
|
38
|
+
self.add_input('resistance_system_ohm', val=0.095, desc='Lumped system transmission resistance [ohm]')
|
|
39
|
+
self.add_input('diameter_m', val=0.3302, desc='Propeller diameter [m]')
|
|
40
|
+
self.add_input('throttle', val=0.7, desc='Throttle fraction [0, 1]')
|
|
41
|
+
|
|
42
|
+
self.add_input('rho', val=1.225, desc='Air density [kg/m^3]')
|
|
43
|
+
self.add_input('airspeed_mps', val=0.0, desc='Flight airspeed [m/s]')
|
|
44
|
+
|
|
45
|
+
# Outputs
|
|
46
|
+
self.add_output('rpm', val=5000.0, desc='Equilibrium shaft speed [RPM]')
|
|
47
|
+
self.add_output('thrust_n', val=10.0, desc='Generated static/dynamic thrust [N]')
|
|
48
|
+
self.add_output('torque_nm', val=0.2, desc='Propeller shaft torque [N-m]')
|
|
49
|
+
self.add_output('battery_current_a', val=15.0, desc='Battery DC current draw [A]')
|
|
50
|
+
self.add_output('battery_power_w', val=220.0, desc='Battery power consumption [W]')
|
|
51
|
+
self.add_output('motor_current_a', val=15.0, desc='Motor winding current [A]')
|
|
52
|
+
self.add_output('motor_voltage_v', val=12.0, desc='Motor terminal voltage [V]')
|
|
53
|
+
self.add_output('is_feasible', val=1.0, desc='1.0 if feasible, 0.0 otherwise')
|
|
54
|
+
|
|
55
|
+
# Declare derivatives using finite-difference
|
|
56
|
+
self.declare_partials(of='*', wrt='*', method='fd')
|
|
57
|
+
|
|
58
|
+
def _get_specs(self, inputs: om.Vector) -> tuple[MotorSpec, BatterySpec, SystemSpec, PropellerSpec]:
|
|
59
|
+
motor = MotorSpec(
|
|
60
|
+
kv_rpm_per_v=float(inputs['kv_rpm_per_v'][0]),
|
|
61
|
+
resistance_ohm=float(inputs['resistance_ohm'][0]),
|
|
62
|
+
no_load_current_a=float(inputs['no_load_current_a'][0]),
|
|
63
|
+
current_max_a=float(inputs['current_max_a'][0]),
|
|
64
|
+
)
|
|
65
|
+
battery = BatterySpec(
|
|
66
|
+
voltage_v=float(inputs['voltage_v'][0]),
|
|
67
|
+
discharge_efficiency=float(inputs['discharge_efficiency'][0]),
|
|
68
|
+
)
|
|
69
|
+
system = SystemSpec(
|
|
70
|
+
resistance_ohm=float(inputs['resistance_system_ohm'][0]),
|
|
71
|
+
)
|
|
72
|
+
propeller = PropellerSpec(
|
|
73
|
+
diameter_m=float(inputs['diameter_m'][0]),
|
|
74
|
+
)
|
|
75
|
+
return motor, battery, system, propeller
|
|
76
|
+
|
|
77
|
+
def compute(self, inputs: om.Vector, outputs: om.Vector) -> None:
|
|
78
|
+
motor, battery, system, propeller = self._get_specs(inputs)
|
|
79
|
+
prop_entry = self.options['prop_entry']
|
|
80
|
+
throttle = float(inputs['throttle'][0])
|
|
81
|
+
rho = float(inputs['rho'][0])
|
|
82
|
+
airspeed_mps = float(inputs['airspeed_mps'][0])
|
|
83
|
+
|
|
84
|
+
solver = PropulsionSolver()
|
|
85
|
+
op = solver.solve_operating_point(
|
|
86
|
+
motor=motor,
|
|
87
|
+
battery=battery,
|
|
88
|
+
system=system,
|
|
89
|
+
propeller=propeller,
|
|
90
|
+
prop_entry=prop_entry,
|
|
91
|
+
rho=rho,
|
|
92
|
+
airspeed_mps=airspeed_mps,
|
|
93
|
+
throttle=throttle,
|
|
94
|
+
)
|
|
95
|
+
|
|
96
|
+
outputs['rpm'] = op.rpm
|
|
97
|
+
outputs['thrust_n'] = op.thrust_n
|
|
98
|
+
outputs['torque_nm'] = op.torque_nm
|
|
99
|
+
outputs['battery_current_a'] = op.battery_power_w / max(1e-6, battery.voltage_v)
|
|
100
|
+
outputs['battery_power_w'] = op.battery_power_w
|
|
101
|
+
outputs['motor_current_a'] = op.motor_current_a
|
|
102
|
+
outputs['motor_voltage_v'] = op.motor_voltage_v
|
|
103
|
+
outputs['is_feasible'] = 1.0 if op.is_feasible else 0.0
|
|
@@ -0,0 +1,316 @@
|
|
|
1
|
+
"""Propeller database loader for JSON metadata + CSV data files."""
|
|
2
|
+
|
|
3
|
+
from __future__ import annotations
|
|
4
|
+
|
|
5
|
+
from dataclasses import dataclass
|
|
6
|
+
from pathlib import Path
|
|
7
|
+
from typing import Dict, Iterable, List, Optional, Tuple
|
|
8
|
+
import csv
|
|
9
|
+
import json
|
|
10
|
+
import math
|
|
11
|
+
|
|
12
|
+
|
|
13
|
+
@dataclass(frozen=True)
|
|
14
|
+
class PropellerMetadata:
|
|
15
|
+
"""Metadata for a propeller dataset entry."""
|
|
16
|
+
id: str
|
|
17
|
+
manufacturer: str
|
|
18
|
+
model: str
|
|
19
|
+
diameter_in: float
|
|
20
|
+
pitch_in: float
|
|
21
|
+
blade_count: int
|
|
22
|
+
data_csv: str
|
|
23
|
+
|
|
24
|
+
|
|
25
|
+
@dataclass(frozen=True)
|
|
26
|
+
class PropellerDataPoint:
|
|
27
|
+
"""Single data point in J space for one RPM band."""
|
|
28
|
+
j: float
|
|
29
|
+
ct: float
|
|
30
|
+
cp: float
|
|
31
|
+
|
|
32
|
+
|
|
33
|
+
@dataclass
|
|
34
|
+
class PropellerEntry:
|
|
35
|
+
"""Propeller performance data grouped by RPM bands."""
|
|
36
|
+
metadata: PropellerMetadata
|
|
37
|
+
data_by_rpm: Dict[float, List[PropellerDataPoint]]
|
|
38
|
+
|
|
39
|
+
@property
|
|
40
|
+
def diameter_m(self) -> float:
|
|
41
|
+
return self.metadata.diameter_in * 0.0254
|
|
42
|
+
|
|
43
|
+
@property
|
|
44
|
+
def pitch_m(self) -> float:
|
|
45
|
+
return self.metadata.pitch_in * 0.0254
|
|
46
|
+
|
|
47
|
+
@property
|
|
48
|
+
def rpm_levels(self) -> List[float]:
|
|
49
|
+
return sorted(self.data_by_rpm.keys())
|
|
50
|
+
|
|
51
|
+
def get_coefficients(self, rpm: float, advance_ratio: float) -> Tuple[float, float]:
|
|
52
|
+
"""Return Ct/Cp for a given RPM and advance ratio."""
|
|
53
|
+
if not self.data_by_rpm:
|
|
54
|
+
return 0.0, 0.0
|
|
55
|
+
|
|
56
|
+
rpm_levels = self.rpm_levels
|
|
57
|
+
rpm_clamped = max(min(rpm, rpm_levels[-1]), rpm_levels[0])
|
|
58
|
+
|
|
59
|
+
low_idx, high_idx = _find_bracketing_indices(rpm_levels, rpm_clamped)
|
|
60
|
+
rpm_low = rpm_levels[low_idx]
|
|
61
|
+
rpm_high = rpm_levels[high_idx]
|
|
62
|
+
|
|
63
|
+
# First interpolate on J at each RPM band, then blend between RPM bands.
|
|
64
|
+
ct_low, cp_low = self._interp_at_rpm(rpm_low, advance_ratio)
|
|
65
|
+
ct_high, cp_high = self._interp_at_rpm(rpm_high, advance_ratio)
|
|
66
|
+
|
|
67
|
+
if rpm_high == rpm_low:
|
|
68
|
+
return ct_low, cp_low
|
|
69
|
+
|
|
70
|
+
frac = (rpm_clamped - rpm_low) / (rpm_high - rpm_low)
|
|
71
|
+
ct = ct_low + frac * (ct_high - ct_low)
|
|
72
|
+
cp = cp_low + frac * (cp_high - cp_low)
|
|
73
|
+
return float(ct), float(cp)
|
|
74
|
+
|
|
75
|
+
def _interp_at_rpm(self, rpm: float, advance_ratio: float) -> Tuple[float, float]:
|
|
76
|
+
"""Interpolate Ct/Cp at a fixed RPM band."""
|
|
77
|
+
points = self.data_by_rpm.get(rpm)
|
|
78
|
+
if not points:
|
|
79
|
+
return 0.0, 0.0
|
|
80
|
+
|
|
81
|
+
j_values = [p.j for p in points]
|
|
82
|
+
ct_values = [p.ct for p in points]
|
|
83
|
+
cp_values = [p.cp for p in points]
|
|
84
|
+
|
|
85
|
+
# Clamp to the lowest J in the dataset.
|
|
86
|
+
if advance_ratio <= j_values[0]:
|
|
87
|
+
return ct_values[0], cp_values[0]
|
|
88
|
+
|
|
89
|
+
# Do not extrapolate past J_max.
|
|
90
|
+
if advance_ratio > j_values[-1]:
|
|
91
|
+
return 0.0, 0.0
|
|
92
|
+
|
|
93
|
+
# Linear interpolation between the two nearest J points.
|
|
94
|
+
idx = _find_insert_index(j_values, advance_ratio)
|
|
95
|
+
j_low = j_values[idx - 1]
|
|
96
|
+
j_high = j_values[idx]
|
|
97
|
+
ct_low = ct_values[idx - 1]
|
|
98
|
+
ct_high = ct_values[idx]
|
|
99
|
+
cp_low = cp_values[idx - 1]
|
|
100
|
+
cp_high = cp_values[idx]
|
|
101
|
+
|
|
102
|
+
frac = (advance_ratio - j_low) / (j_high - j_low)
|
|
103
|
+
ct = ct_low + frac * (ct_high - ct_low)
|
|
104
|
+
cp = cp_low + frac * (cp_high - cp_low)
|
|
105
|
+
return float(ct), float(cp)
|
|
106
|
+
|
|
107
|
+
|
|
108
|
+
class PropellerDatabase:
|
|
109
|
+
"""Load and query propeller data from JSON + CSV files."""
|
|
110
|
+
def __init__(self) -> None:
|
|
111
|
+
"""Create an empty propeller database."""
|
|
112
|
+
self._entries: Dict[str, PropellerEntry] = {}
|
|
113
|
+
self._loaded = False
|
|
114
|
+
|
|
115
|
+
@property
|
|
116
|
+
def is_loaded(self) -> bool:
|
|
117
|
+
return self._loaded
|
|
118
|
+
|
|
119
|
+
@property
|
|
120
|
+
def propeller_count(self) -> int:
|
|
121
|
+
return len(self._entries)
|
|
122
|
+
|
|
123
|
+
def list_propellers(self) -> List[str]:
|
|
124
|
+
"""Return sorted propeller IDs in the database."""
|
|
125
|
+
return sorted(self._entries.keys())
|
|
126
|
+
|
|
127
|
+
def get(self, prop_id: str) -> Optional[PropellerEntry]:
|
|
128
|
+
"""Get a propeller entry by its ID."""
|
|
129
|
+
return self._entries.get(prop_id)
|
|
130
|
+
|
|
131
|
+
def load(self, data_dir: Path, strict: bool = False) -> bool:
|
|
132
|
+
"""Load all JSON/CSV entries from a dataset directory."""
|
|
133
|
+
data_dir = Path(data_dir)
|
|
134
|
+
if not data_dir.exists():
|
|
135
|
+
self._loaded = False
|
|
136
|
+
return False
|
|
137
|
+
|
|
138
|
+
self._entries.clear()
|
|
139
|
+
# Each JSON file points to a CSV with the RPM/J/Ct/Cp data.
|
|
140
|
+
for json_path in sorted(data_dir.glob("*.json")):
|
|
141
|
+
entry = _load_entry(json_path, data_dir, strict=strict)
|
|
142
|
+
if entry is not None:
|
|
143
|
+
self._entries[entry.metadata.id] = entry
|
|
144
|
+
|
|
145
|
+
self._loaded = bool(self._entries)
|
|
146
|
+
return self._loaded
|
|
147
|
+
|
|
148
|
+
def load_entry(
|
|
149
|
+
self,
|
|
150
|
+
json_path: Path,
|
|
151
|
+
data_dir: Optional[Path] = None,
|
|
152
|
+
strict: bool = False,
|
|
153
|
+
) -> Optional[PropellerEntry]:
|
|
154
|
+
"""Load a single JSON metadata file and store its entry."""
|
|
155
|
+
json_path = Path(json_path)
|
|
156
|
+
base_dir = Path(data_dir) if data_dir is not None else json_path.parent
|
|
157
|
+
entry = _load_entry(json_path, base_dir, strict=strict)
|
|
158
|
+
if entry is None:
|
|
159
|
+
return None
|
|
160
|
+
|
|
161
|
+
self._entries[entry.metadata.id] = entry
|
|
162
|
+
self._loaded = bool(self._entries)
|
|
163
|
+
return entry
|
|
164
|
+
|
|
165
|
+
def find_by_size(
|
|
166
|
+
self,
|
|
167
|
+
diameter_in: float,
|
|
168
|
+
pitch_in: float,
|
|
169
|
+
blade_count: int = 2,
|
|
170
|
+
tolerance: float = 0.5,
|
|
171
|
+
) -> Optional[PropellerEntry]:
|
|
172
|
+
"""Find the closest propeller by (diameter, pitch) within tolerance."""
|
|
173
|
+
candidates: List[Tuple[float, PropellerEntry]] = []
|
|
174
|
+
|
|
175
|
+
for entry in self._entries.values():
|
|
176
|
+
if entry.metadata.blade_count != blade_count:
|
|
177
|
+
continue
|
|
178
|
+
|
|
179
|
+
dist = ((entry.metadata.diameter_in - diameter_in) ** 2 +
|
|
180
|
+
(entry.metadata.pitch_in - pitch_in) ** 2) ** 0.5
|
|
181
|
+
if dist <= tolerance:
|
|
182
|
+
candidates.append((dist, entry))
|
|
183
|
+
|
|
184
|
+
if not candidates:
|
|
185
|
+
return None
|
|
186
|
+
|
|
187
|
+
candidates.sort(key=lambda item: item[0])
|
|
188
|
+
return candidates[0][1]
|
|
189
|
+
|
|
190
|
+
def get_interpolated_coefficients(
|
|
191
|
+
self,
|
|
192
|
+
diameter_in: float,
|
|
193
|
+
pitch_in: float,
|
|
194
|
+
blade_count: int,
|
|
195
|
+
rpm: float,
|
|
196
|
+
advance_ratio: float,
|
|
197
|
+
tolerance: float = 0.5,
|
|
198
|
+
) -> Tuple[float, float, bool]:
|
|
199
|
+
"""Convenience helper to fetch Ct/Cp by prop size."""
|
|
200
|
+
entry = self.find_by_size(diameter_in, pitch_in, blade_count, tolerance)
|
|
201
|
+
if entry is None:
|
|
202
|
+
return 0.0, 0.0, False
|
|
203
|
+
|
|
204
|
+
ct, cp = entry.get_coefficients(rpm, advance_ratio)
|
|
205
|
+
return ct, cp, True
|
|
206
|
+
|
|
207
|
+
|
|
208
|
+
def _normalize_rpm(value: float) -> float:
|
|
209
|
+
"""Round RPM values when they are effectively integers."""
|
|
210
|
+
# Keep clean integer RPM levels when possible.
|
|
211
|
+
rounded = round(value)
|
|
212
|
+
if abs(value - rounded) < 1e-3:
|
|
213
|
+
return float(rounded)
|
|
214
|
+
return float(value)
|
|
215
|
+
|
|
216
|
+
|
|
217
|
+
def _find_bracketing_indices(values: List[float], target: float) -> Tuple[int, int]:
|
|
218
|
+
"""Return indices of the two values that bracket the target."""
|
|
219
|
+
if target <= values[0]:
|
|
220
|
+
return 0, 0
|
|
221
|
+
if target >= values[-1]:
|
|
222
|
+
return len(values) - 1, len(values) - 1
|
|
223
|
+
|
|
224
|
+
idx = _find_insert_index(values, target)
|
|
225
|
+
return idx - 1, idx
|
|
226
|
+
|
|
227
|
+
|
|
228
|
+
def _find_insert_index(values: List[float], target: float) -> int:
|
|
229
|
+
"""Find the insertion index for a sorted list."""
|
|
230
|
+
lo = 0
|
|
231
|
+
hi = len(values)
|
|
232
|
+
while lo < hi:
|
|
233
|
+
mid = (lo + hi) // 2
|
|
234
|
+
if values[mid] < target:
|
|
235
|
+
lo = mid + 1
|
|
236
|
+
else:
|
|
237
|
+
hi = mid
|
|
238
|
+
return min(max(lo, 1), len(values) - 1)
|
|
239
|
+
|
|
240
|
+
|
|
241
|
+
def _load_entry(json_path: Path, data_dir: Path, strict: bool = False) -> Optional[PropellerEntry]:
|
|
242
|
+
"""Load a JSON metadata file plus its CSV into a PropellerEntry."""
|
|
243
|
+
try:
|
|
244
|
+
metadata_raw = json.loads(json_path.read_text())
|
|
245
|
+
except json.JSONDecodeError:
|
|
246
|
+
return None
|
|
247
|
+
|
|
248
|
+
required = ["id", "manufacturer", "model", "diameter_in", "pitch_in", "blade_count", "data_csv"]
|
|
249
|
+
if not all(key in metadata_raw for key in required):
|
|
250
|
+
return None
|
|
251
|
+
|
|
252
|
+
metadata = PropellerMetadata(
|
|
253
|
+
id=str(metadata_raw["id"]),
|
|
254
|
+
manufacturer=str(metadata_raw["manufacturer"]),
|
|
255
|
+
model=str(metadata_raw["model"]),
|
|
256
|
+
diameter_in=float(metadata_raw["diameter_in"]),
|
|
257
|
+
pitch_in=float(metadata_raw["pitch_in"]),
|
|
258
|
+
blade_count=int(metadata_raw["blade_count"]),
|
|
259
|
+
data_csv=str(metadata_raw["data_csv"]),
|
|
260
|
+
)
|
|
261
|
+
|
|
262
|
+
csv_path = data_dir / metadata.data_csv
|
|
263
|
+
if not csv_path.exists():
|
|
264
|
+
return None
|
|
265
|
+
|
|
266
|
+
data_by_rpm: Dict[float, List[PropellerDataPoint]] = {}
|
|
267
|
+
seen_keys: Dict[float, set[float]] = {}
|
|
268
|
+
required_cols = {"rpm", "advance_ratio", "thrust_coeff", "power_coeff"}
|
|
269
|
+
with csv_path.open("r", newline="") as handle:
|
|
270
|
+
reader = csv.DictReader(handle)
|
|
271
|
+
if reader.fieldnames is None or not required_cols.issubset(set(reader.fieldnames)):
|
|
272
|
+
if strict:
|
|
273
|
+
raise ValueError(f"Missing required columns in {csv_path.name}")
|
|
274
|
+
return None
|
|
275
|
+
for row in reader:
|
|
276
|
+
try:
|
|
277
|
+
rpm = _normalize_rpm(float(row["rpm"]))
|
|
278
|
+
j_value = float(row["advance_ratio"])
|
|
279
|
+
ct = float(row["thrust_coeff"])
|
|
280
|
+
cp = float(row["power_coeff"])
|
|
281
|
+
except (KeyError, ValueError):
|
|
282
|
+
if strict:
|
|
283
|
+
raise ValueError(f"Invalid numeric values in {csv_path.name}")
|
|
284
|
+
continue
|
|
285
|
+
|
|
286
|
+
if not (math.isfinite(rpm) and math.isfinite(j_value) and math.isfinite(ct) and math.isfinite(cp)):
|
|
287
|
+
if strict:
|
|
288
|
+
raise ValueError(f"Non-finite values in {csv_path.name}")
|
|
289
|
+
continue
|
|
290
|
+
if rpm <= 0 or j_value < 0 or ct < 0 or cp < 0:
|
|
291
|
+
if strict:
|
|
292
|
+
raise ValueError(f"Out-of-range values in {csv_path.name}")
|
|
293
|
+
continue
|
|
294
|
+
|
|
295
|
+
seen = seen_keys.setdefault(rpm, set())
|
|
296
|
+
if j_value in seen:
|
|
297
|
+
if strict:
|
|
298
|
+
raise ValueError(f"Duplicate (rpm,J) pair in {csv_path.name}")
|
|
299
|
+
continue
|
|
300
|
+
seen.add(j_value)
|
|
301
|
+
|
|
302
|
+
data_by_rpm.setdefault(rpm, []).append(
|
|
303
|
+
PropellerDataPoint(j=j_value, ct=ct, cp=cp)
|
|
304
|
+
)
|
|
305
|
+
|
|
306
|
+
for rpm_key, points in data_by_rpm.items():
|
|
307
|
+
data_by_rpm[rpm_key] = sorted(points, key=lambda p: p.j)
|
|
308
|
+
|
|
309
|
+
if strict:
|
|
310
|
+
for rpm_key, points in data_by_rpm.items():
|
|
311
|
+
if len(points) < 2:
|
|
312
|
+
raise ValueError(f"Insufficient points for RPM {rpm_key} in {csv_path.name}")
|
|
313
|
+
if not data_by_rpm:
|
|
314
|
+
raise ValueError(f"No valid data rows in {csv_path.name}")
|
|
315
|
+
|
|
316
|
+
return PropellerEntry(metadata=metadata, data_by_rpm=data_by_rpm)
|
|
@@ -0,0 +1,15 @@
|
|
|
1
|
+
"""Propulsion solver models and utilities."""
|
|
2
|
+
|
|
3
|
+
from .models import ( # noqa: F401
|
|
4
|
+
MotorSpec,
|
|
5
|
+
BatterySpec,
|
|
6
|
+
SystemSpec,
|
|
7
|
+
PropellerSpec,
|
|
8
|
+
OperatingPoint,
|
|
9
|
+
)
|
|
10
|
+
from .solver import PropulsionSolver, SolverConfig # noqa: F401
|
|
11
|
+
from .autotune import ( # noqa: F401
|
|
12
|
+
ManufacturerTestPoint,
|
|
13
|
+
CalibrationResult,
|
|
14
|
+
PropulsionCalibrator,
|
|
15
|
+
)
|