From afbdaca99bab6a901895e431ddee07491ac5f33b Mon Sep 17 00:00:00 2001 From: Bart Date: Tue, 5 May 2026 13:22:06 +0200 Subject: [PATCH 1/3] Add forwarddiff compat --- Project.toml | 2 + examples/Project.toml | 1 + examples/linearize_check.jl | 216 ++++++++++++ examples/menu.jl | 1 + src/VortexStepMethod.jl | 3 +- src/body_aerodynamics.jl | 107 +++--- src/filament.jl | 24 +- src/obj_geometry.jl | 20 +- src/panel.jl | 99 +++--- src/solver.jl | 346 ++++++++++++------- src/wing_geometry.jl | 206 ++++------- test/Project.toml | 2 + test/body_aerodynamics/test_results.jl | 3 +- test/filament/test_bound_filament.jl | 6 +- test/filament/test_semi_infinite_filament.jl | 2 +- test/panel/test_panel.jl | 2 +- test/runtests.jl | 1 + test/solver/test_forwarddiff.jl | 54 +++ 18 files changed, 710 insertions(+), 385 deletions(-) create mode 100644 examples/linearize_check.jl create mode 100644 test/solver/test_forwarddiff.jl diff --git a/Project.toml b/Project.toml index 1ff03cb9..3e95fd71 100644 --- a/Project.toml +++ b/Project.toml @@ -12,6 +12,7 @@ DefaultApplication = "3f0dd361-4fe0-5fc6-8523-80b14ec94d85" DelimitedFiles = "8bb1440f-4735-579b-a4ab-409b98df4dab" DifferentiationInterface = "a0c0ee7d-e4b9-4e03-894e-1c5f64a51d63" FiniteDiff = "6a86dc24-6348-571c-b903-95158fe2bd41" +ForwardDiff = "f6369f11-7733-5829-9624-2563aa707210" Interpolations = "a98d9a8b-a2ab-59e6-89dd-64a1c18fca59" LaTeXStrings = "b964fa9f-0449-5b57-a5c2-d3ea65f4040f" LinearAlgebra = "37e2e46d-f89d-539d-b4ee-838fcccc9c8e" @@ -47,6 +48,7 @@ DefaultApplication = "1" DelimitedFiles = "1" DifferentiationInterface = "0.7.4" FiniteDiff = "2.27.0" +ForwardDiff = "0.10, 1" Interpolations = "0.15, 0.16" LaTeXStrings = "1" LinearAlgebra = "1" diff --git a/examples/Project.toml b/examples/Project.toml index 5b5059b5..e4e6ad0f 100644 --- a/examples/Project.toml +++ b/examples/Project.toml @@ -3,6 +3,7 @@ CSV = "336ed68f-0bac-5ca0-87d4-7b16caf5d00b" CairoMakie = "13f3f980-e62b-5c42-98c6-ff1f3baf88f0" DataFrames = "a93c6f00-e57d-5684-b7b6-d8193f3e46c0" DelimitedFiles = "8bb1440f-4735-579b-a4ab-409b98df4dab" +DifferentiationInterface = "a0c0ee7d-e4b9-4e03-894e-1c5f64a51d63" GLMakie = "e9467ef8-e4e7-5192-8a1a-b1aee30e663a" LinearAlgebra = "37e2e46d-f89d-539d-b4ee-838fcccc9c8e" REPL = "3fa0cd96-eef1-5676-8a61-b3b8758bbffb" diff --git a/examples/linearize_check.jl b/examples/linearize_check.jl new file mode 100644 index 00000000..d3c49590 --- /dev/null +++ b/examples/linearize_check.jl @@ -0,0 +1,216 @@ +using Pkg +if Base.active_project() != joinpath(@__DIR__, "Project.toml") + Pkg.activate(@__DIR__) +end + +using GLMakie +using DifferentiationInterface +using LinearAlgebra +using VortexStepMethod +using VortexStepMethod: linearize, unrefined_deform!, reinit! + +# Sweep each linearize input around the operating point and +# overlay the linear prediction from the local `linearize` +# Jacobian. If the tangent (red dashed line) matches the sweep +# slope at δ=0, the FD Jacobian column is correct. + +n_unrefined = 4 + +wing = ObjWing( + joinpath("data", "ram_air_kite", "ram_air_kite_body.obj"), + joinpath("data", "ram_air_kite", "ram_air_kite_foil.dat"); + n_unrefined_sections=n_unrefined, + prn=false, +) +body_aero = BodyAerodynamics([wing]) + +solver = Solver(body_aero; + aerodynamic_model_type=VSM, + is_with_artificial_damping=false, + rtol=1e-7, + solver_type=NONLIN, +) + +v_a = 15.0 +aoa_deg = 10.0 +aoa_rad = deg2rad(aoa_deg) +side_slip = 0.0 +va_b_0 = [ + cos(aoa_rad) * cos(side_slip), + sin(side_slip), + sin(aoa_rad), +] * v_a +omega_b_0 = zeros(3) +theta_0 = zeros(n_unrefined) + +theta_idxs = 1:n_unrefined +va_idxs = (n_unrefined + 1):(n_unrefined + 3) +omega_idxs = (n_unrefined + 4):(n_unrefined + 6) +y0 = [theta_0; va_b_0; omega_b_0] + +@info "Computing linearize Jacobian (NONLIN, AutoFiniteDiff) …" +jac, x0, converged = linearize( + solver, body_aero, y0; + theta_idxs, va_idxs, omega_idxs, + aero_coeffs=true, + backend=AutoFiniteDiff(absstep=1e-4, relstep=1e-4), +) +converged || @warn "linearize did not converge at operating point" + +@info "Operating point" CFx=x0[1] CFy=x0[2] CFz=x0[3] CM=x0[4:6] + +input_labels = [ + ["θ_$i" for i in 1:n_unrefined]..., + "va_x", "va_y", "va_z", + "ω_x", "ω_y", "ω_z", +] +output_labels = [ + "CFx", "CFy", "CFz", + "CMx", "CMy", "CMz", + ["cm_$i" for i in 1:n_unrefined]..., +] +n_inputs = length(input_labels) +n_outputs = length(output_labels) + +@assert size(jac) == (n_outputs, n_inputs) + +input_scales = [ + fill(0.05, n_unrefined)..., # θ [rad] : ±0.05 rad ≈ ±2.9° + fill(1.0, 3)..., # va: ±1 m/s + fill(0.05, 3)..., # ω : ±0.05 rad/s +] +n_sweep = 11 +sweep_frac = range(-1.0, 1.0; length=n_sweep) + +# results[col][si, ri] +results_sw = [zeros(n_sweep, n_outputs) for _ in 1:n_inputs] + +last_theta = fill(NaN, n_unrefined) + +function solve_at!(y) + theta = y[theta_idxs] + va = y[va_idxs] + omega = y[omega_idxs] + if !all(theta .== last_theta) + unrefined_deform!(wing, theta, nothing; smooth=false) + reinit!(body_aero; init_aero=false) + last_theta .= theta + end + set_va!(body_aero, va, omega) + solve!(solver, body_aero; log=false) + return [ + solver.sol.force_coeffs..., + solver.sol.moment_coeffs..., + solver.sol.cm_unrefined_dist..., + ] +end + +@info "Sweeping each input …" +for ci in 1:n_inputs + @info " $(input_labels[ci])" + for (si, frac) in enumerate(sweep_frac) + y = copy(y0) + y[ci] += frac * input_scales[ci] + results_sw[ci][si, :] .= solve_at!(y) + end +end + +# Restore baseline +solve_at!(y0) + +fig = Figure(size=(180 * n_inputs + 80, 90 * n_outputs + 80)) +Label(fig[0, 1:n_inputs], + "linearize check: sweeps (blue) vs Jacobian tangent (red dashed)"; + fontsize=18, font=:bold, tellwidth=false) + +for ri in 1:n_outputs + for ci in 1:n_inputs + ax = Axis(fig[ri, ci]; + xlabel = ri == n_outputs ? input_labels[ci] : "", + ylabel = ci == 1 ? output_labels[ri] : "", + xticklabelsvisible = ri == n_outputs, + yticklabelsvisible = ci == 1, + xticksvisible = ri == n_outputs, + yticksvisible = ci == 1, + ) + delta_input = sweep_frac .* input_scales[ci] + ys_sweep = results_sw[ci][:, ri] + ys_linear = x0[ri] .+ jac[ri, ci] .* delta_input + + lines!(ax, delta_input, ys_sweep; + color=:steelblue, linewidth=1.5) + lines!(ax, delta_input, ys_linear; + color=:crimson, linestyle=:dash, linewidth=1.2) + scatter!(ax, [0.0], [x0[ri]]; + color=:crimson, markersize=6) + end +end + +colgap!(fig.layout, 6) +rowgap!(fig.layout, 4) + +display(fig) + +# Worst-case mismatch between sweep slope at δ=0 and Jacobian +# column (central FD on the sweep). Useful as a numerical check +# in addition to the visual one. +# Skip near-zero Jacobian entries — relative error is dominated by +# FD rounding there and not informative. +sig_threshold = 1e-3 * maximum(abs, jac) +global max_rel_err = 0.0 +global worst = (0, 0, 0.0, 0.0) +for ri in 1:n_outputs, ci in 1:n_inputs + delta = sweep_frac .* input_scales[ci] + mid = div(n_sweep, 2) + 1 + fd = (results_sw[ci][mid + 1, ri] - + results_sw[ci][mid - 1, ri]) / + (delta[mid + 1] - delta[mid - 1]) + jc = jac[ri, ci] + max(abs(jc), abs(fd)) < sig_threshold && continue + rel = abs(fd - jc) / max(abs(jc), abs(fd)) + if rel > max_rel_err + global max_rel_err = rel + global worst = (ri, ci, fd, jc) + end +end +@info "Worst Jacobian/sweep mismatch (significant entries)" rel=max_rel_err output=output_labels[worst[1]] input=input_labels[worst[2]] sweep_slope=worst[3] jac_entry=worst[4] sig_threshold + +# ── ForwardDiff vs FiniteDiff agreement (LOOP solver) ───────────────────── +# NONLIN doesn't support Duals (LAPACK on Float64), so use LOOP here. +solver_loop = Solver(body_aero; + aerodynamic_model_type = VSM, + is_with_artificial_damping = false, + rtol = 1e-7, + solver_type = LOOP, + use_gamma_prev = false, # required for fair FD comparison +) + +@info "Computing ForwardDiff Jacobian (LOOP) …" +t_fwd = @elapsed begin + jac_fwd, x0_fwd, conv_fwd = linearize( + solver_loop, body_aero, y0; + theta_idxs, va_idxs, omega_idxs, + aero_coeffs = true, + backend = AutoForwardDiff(), + ) +end + +@info "Computing FiniteDiff Jacobian (LOOP) …" +t_fd = @elapsed begin + jac_fd, x0_fd, conv_fd = linearize( + solver_loop, body_aero, y0; + theta_idxs, va_idxs, omega_idxs, + aero_coeffs = true, + backend = AutoFiniteDiff(absstep = 1e-5, relstep = 1e-5), + ) +end + +@assert conv_fwd && conv_fd "linearize did not converge at operating point" + +denom = max(maximum(abs, jac_fwd), eps()) +rel_err_fwd_fd = maximum(abs.(jac_fwd .- jac_fd)) / denom +@info "AutoForwardDiff vs AutoFiniteDiff (LOOP)" rel_err = rel_err_fwd_fd +@info "Speed" t_fwd_s = t_fwd t_fd_s = t_fd speedup = t_fd / t_fwd +@assert rel_err_fwd_fd < 1e-4 "ForwardDiff and FiniteDiff Jacobians differ by $rel_err_fwd_fd (>1e-4)" + +nothing diff --git a/examples/menu.jl b/examples/menu.jl index 50a948a7..3117c7c0 100644 --- a/examples/menu.jl +++ b/examples/menu.jl @@ -16,6 +16,7 @@ example_files = [ "ram_air_kite.jl", "stall_model.jl", "bench.jl", + "linearize_check.jl", "cleanup.jl", ] diff --git a/src/VortexStepMethod.jl b/src/VortexStepMethod.jl index 74430045..5c5e3f4d 100644 --- a/src/VortexStepMethod.jl +++ b/src/VortexStepMethod.jl @@ -20,6 +20,7 @@ using PreallocationTools using PrecompileTools using Pkg using DifferentiationInterface +using ForwardDiff import YAML using StructMapping using Xfoil @@ -175,7 +176,7 @@ Enumeration specifying the method used to solve for circulation distribution. """ @enum SolverType LOOP NONLIN -abstract type AbstractWing end +abstract type AbstractWing{T} end """ AeroData= Union{ diff --git a/src/body_aerodynamics.jl b/src/body_aerodynamics.jl index 1596b85f..8ca7c003 100644 --- a/src/body_aerodynamics.jl +++ b/src/body_aerodynamics.jl @@ -4,7 +4,7 @@ Main structure for calculating aerodynamic properties of bodies. Use the constructor to initialize. # Fields -- panels::Vector{Panel}: Vector of refined [Panel](@ref) structs +- panels::Vector{<:Panel}: Vector of refined [Panel](@ref) structs - wings::Vector{W}: A vector of wings of type `W <: AbstractWing`; a body can have multiple wings - `va::MVec3` = zeros(MVec3): A vector of the apparent wind speed, see: [MVec3](@ref) - `omega`::MVec3 = zeros(MVec3): A vector of the turn rates around the kite body axes @@ -22,23 +22,23 @@ Main structure for calculating aerodynamic properties of bodies. Use the constru - `y::MVector{P, Float64}` = MVector{P,Float64}(zeros(P)) - `cache::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}}` = [LazyBufferCache() for _ in 1:15] """ -@with_kw mutable struct BodyAerodynamics{P,W<:AbstractWing} - panels::Vector{Panel} +@with_kw mutable struct BodyAerodynamics{P, W<:AbstractWing, T} + panels::Vector{Panel{T}} wings::Vector{W} - _va::MVec3 = zeros(MVec3) + _va::MVector{3, T} = zeros(MVector{3, T}) has_distributed_va::Bool = false - omega::MVec3 = zeros(MVec3) - gamma_distribution::MVector{P, Float64} = zeros(P) - alpha_uncorrected::MVector{P, Float64} = zeros(P) - alpha_corrected::MVector{P, Float64} = zeros(P) - stall_angle_list::MVector{P, Float64} = zeros(P) - alpha_dist::MVector{P, Float64} = zeros(P) - v_a_dist::MVector{P, Float64} = zeros(P) - work_vectors::NTuple{10,MVec3} = ntuple(_ -> zeros(MVec3), 10) - AIC::Array{Float64, 3} = zeros(3, P, P) - projected_area::Float64 = one(Float64) - c_ref::Float64 = one(Float64) - y::MVector{P, Float64} = zeros(P) + omega::MVector{3, T} = zeros(MVector{3, T}) + gamma_distribution::MVector{P, T} = zeros(MVector{P, T}) + alpha_uncorrected::MVector{P, T} = zeros(MVector{P, T}) + alpha_corrected::MVector{P, T} = zeros(MVector{P, T}) + stall_angle_list::MVector{P, T} = zeros(MVector{P, T}) + alpha_dist::MVector{P, T} = zeros(MVector{P, T}) + v_a_dist::MVector{P, T} = zeros(MVector{P, T}) + work_vectors::NTuple{10, MVector{3, T}} = ntuple(_ -> zeros(MVector{3, T}), 10) + AIC::Array{T, 3} = zeros(T, 3, P, P) + projected_area::T = one(T) + c_ref::T = one(T) + y::MVector{P, T} = zeros(MVector{P, T}) cache::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}} = [LazyBufferCache() for _ in 1:15] end @@ -69,11 +69,11 @@ body_aero = BodyAerodynamics([wing], va=[15.0, 0.0, 0.0], omega=zeros(3)) ``` """ function BodyAerodynamics( - wings::Vector{T}; + wings::Vector{W}; kite_body_origin=zeros(MVec3), va=[15.0, 0.0, 0.0], omega=zeros(MVec3) -) where T <: AbstractWing +) where {T, W <: AbstractWing{T}} # Validate all wings are refined for (i, wing) in enumerate(wings) if isempty(wing.refined_sections) || @@ -96,7 +96,7 @@ function BodyAerodynamics( end # Initialize panels - panels = Panel[] + panels = Panel{T}[] for wing in wings for section in wing.unrefined_sections section.LE_point .-= kite_body_origin @@ -105,12 +105,12 @@ function BodyAerodynamics( # Create panels for _ in 1:wing.n_panels - panel = Panel() + panel = Panel{T}() push!(panels, panel) end end - body_aero = BodyAerodynamics{length(panels),T}(; panels, wings) + body_aero = BodyAerodynamics{length(panels), W, T}(; panels, wings) reinit!(body_aero; va, omega) return body_aero end @@ -162,7 +162,7 @@ end end """ - calculate_stall_angle_list(panels::Vector{Panel}; + calculate_stall_angle_list(panels::Vector{<:Panel}; begin_aoa=9.0, end_aoa=22.0, step_aoa=1.0, @@ -174,7 +174,7 @@ Calculate stall angles for each panel. Returns: Vector{Float64}: Stall angles in radians """ -function calculate_stall_angle_list(panels::Vector{Panel}; +function calculate_stall_angle_list(panels::Vector{<:Panel}; begin_aoa=9.0, end_aoa=22.0, step_aoa=1.0, @@ -187,8 +187,8 @@ function calculate_stall_angle_list(panels::Vector{Panel}; return stall_angles end -function calculate_stall_angle_list!(stall_angles::AbstractVector{Float64}, - panels::Vector{Panel}; +function calculate_stall_angle_list!(stall_angles::AbstractVector, + panels::Vector{<:Panel}; begin_aoa=9.0, end_aoa=22.0, step_aoa=1.0, @@ -238,13 +238,13 @@ Initialize a BodyAerodynamics struct in-place by setting up panels and coefficie # Returns nothing """ -function reinit!(body_aero::BodyAerodynamics; +function reinit!(body_aero::BodyAerodynamics{P, W, T}; init_aero=true, va=[15.0, 0.0, 0.0], - omega=zeros(MVec3) -) + omega=zeros(MVector{3, T}) +) where {P, W, T} idx = 1 - vec = @MVector zeros(3) + vec = zeros(MVector{3, T}) for wing in body_aero.wings reinit!(wing) panel_props = wing.panel_props @@ -256,7 +256,7 @@ function reinit!(body_aero::BodyAerodynamics; # Panel i gets its delta directly from delta_dist[i] delta = wing.delta_dist[i] else - delta = 0.0 + delta = zero(T) end @views reinit!( body_aero.panels[idx], @@ -304,7 +304,8 @@ the area-weighted mean direction. ) length(va_input) == 3 || throw(ArgumentError("'va' must be shape (3,) or ($(n_panels), 3); got length $(length(va_input))")) - return MVec3(Float64(va_input[1]), Float64(va_input[2]), Float64(va_input[3])) + T = eltype(va_input) + return MVector{3, T}(va_input[1], va_input[2], va_input[3]) end @inline function _compute_reference_velocity_from_distribution( @@ -315,19 +316,21 @@ end size(va_input) == (n_panels, 3) || throw(ArgumentError("'va' must be shape (3,) or ($(n_panels), 3); got $(size(va_input))")) + T = promote_type(eltype(va_input), + isnothing(panel_areas) ? Float64 : eltype(panel_areas)) areas = if isnothing(panel_areas) - ones(Float64, n_panels) + ones(T, n_panels) else length(panel_areas) == n_panels || throw(ArgumentError("panel_areas must be shape ($(n_panels),), got length $(length(panel_areas))")) - Float64.(panel_areas) + T.(panel_areas) end total_area = sum(areas) total_area > 0.0 || throw(ArgumentError("Total panel area must be positive.")) - weighted_speed_sq = 0.0 - direction = zeros(MVec3) + weighted_speed_sq = zero(T) + direction = zeros(MVector{3, T}) @inbounds for i in 1:n_panels @views va_i = va_input[i, :] speed_i = norm(va_i) @@ -338,8 +341,8 @@ end reference_speed = sqrt(weighted_speed_sq / total_area) direction_norm = norm(direction) if direction_norm <= 0.0 - direction .= (1.0, 0.0, 0.0) - direction_norm = 1.0 + direction .= (one(T), zero(T), zero(T)) + direction_norm = one(T) end return direction ./ direction_norm .* reference_speed @@ -357,23 +360,23 @@ See also: [BodyAerodynamics](@ref), [Model](@ref) Returns: nothing """ -@inline function calculate_AIC_matrices!(body_aero::BodyAerodynamics, model::Model, +@inline function calculate_AIC_matrices!(body_aero::BodyAerodynamics{P, W, T}, model::Model, core_radius_fraction, - va_norm_array, - va_unit_array) + va_norm_array::AbstractVector{T}, + va_unit_array::AbstractMatrix{T}) where {P, W, T} # Determine evaluation point based on model evaluation_point = model == VSM ? :control_point : :aero_center evaluation_point_on_bound = model == LLT # Allocate work vectors for this function (separate from those used by child functions) - velocity_induced = @MVector zeros(3) - tempvel = @MVector zeros(3) - va_unit = @MVector zeros(3) - U_2D = @MVector zeros(3) + velocity_induced = zeros(MVector{3, T}) + tempvel = zeros(MVector{3, T}) + va_unit = zeros(MVector{3, T}) + U_2D = zeros(MVector{3, T}) # Python parity: one shared area-weighted wake vector for all panels. panel_areas = [panel.chord * panel.width for panel in body_aero.panels] - va_distribution = zeros(length(body_aero.panels), 3) + va_distribution = zeros(T, length(body_aero.panels), 3) @inbounds for i in 1:length(body_aero.panels), k in 1:3 va_distribution[i, k] = va_unit_array[i, k] * va_norm_array[i] end @@ -402,7 +405,7 @@ Returns: nothing evaluation_point_on_bound, va_norm, va_unit, - 1.0, + one(T), core_radius_fraction, body_aero.work_vectors ) @@ -712,7 +715,7 @@ end chord_array, x_airf_array, z_airf_array, va_array, va_norm_array, - va_unit_array, panels::Vector{Panel}, + va_unit_array, panels::Vector{<:Panel}, is_only_f_and_gamma_output::Bool) Calculate final aerodynamic results. Reference point is in the kite body (KB) frame. @@ -735,7 +738,7 @@ function calculate_results( va_array, va_norm_array, va_unit_array, - panels::Vector{Panel}, + panels::Vector{<:Panel}, is_only_f_and_gamma_output::Bool; correct_aoa::Bool=false, ) @@ -1050,9 +1053,9 @@ Set velocity array and update wake filaments. - `va::VelVector`: Velocity vector of the apparent wind speed [m/s] - `omega::VelVector`: Turn rate vector around x y and z axis [rad/s] """ -function set_va!(body_aero::BodyAerodynamics, va::AbstractVector, omega=zeros(MVec3)) +function set_va!(body_aero::BodyAerodynamics{P, W, T}, va::AbstractVector, omega=zeros(MVector{3, T})) where {P, W, T} n_panels = length(body_aero.panels) - va_distribution = zeros(n_panels, 3) + va_distribution = zeros(T, n_panels, 3) body_aero.omega .= omega if all(iszero, omega) @@ -1070,12 +1073,12 @@ function set_va!(body_aero::BodyAerodynamics, va::AbstractVector, omega=zeros(MV idx = panel_end + 1 end end - + # Update panel velocities for (i, panel) in enumerate(body_aero.panels) panel.va .= va_distribution[i,:] end - + # Update wake elements frozen_wake!(body_aero, va_distribution) body_aero._va .= va diff --git a/src/filament.jl b/src/filament.jl index e3b91b88..e2c5a772 100644 --- a/src/filament.jl +++ b/src/filament.jl @@ -20,15 +20,15 @@ Represents a bound vortex filament defined by two points. - r0::MVec3=zeros(MVec3): Vector from x1 to x2 - initialized::Bool = false """ -@with_kw mutable struct BoundFilament <: Filament - x1::MVec3 = zeros(MVec3) - x2::MVec3 = zeros(MVec3) - length::Float64 = zero(Float64) - r0::MVec3 = zeros(MVec3) - initialized::Bool = false +@with_kw mutable struct BoundFilament{T} <: Filament + x1::MVector{3, T} = zeros(MVector{3, T}) + x2::MVector{3, T} = zeros(MVector{3, T}) + length::T = zero(T) + r0::MVector{3, T} = zeros(MVector{3, T}) + initialized::Bool = false end -function reinit!(filament::BoundFilament, x1, x2, vec=zeros(MVec3)) +function reinit!(filament::BoundFilament{T}, x1, x2, vec=zeros(MVector{3, T})) where {T} filament.x1 .= x1 filament.x2 .= x2 vec .= x2 .- x1 @@ -229,15 +229,15 @@ Represents a semi-infinite vortex filament. - `filament_direction`::Int64=0 : Direction indicator (-1 or 1) - initialized::Bool=false """ -@with_kw mutable struct SemiInfiniteFilament <: Filament - x1::MVec3 = zeros(MVec3) - direction::MVec3 = zeros(MVec3) - vel_mag::Float64 = zero(Float64) +@with_kw mutable struct SemiInfiniteFilament{T} <: Filament + x1::MVector{3, T} = zeros(MVector{3, T}) + direction::MVector{3, T} = zeros(MVector{3, T}) + vel_mag::T = zero(T) filament_direction::Int64 = zero(Int64) initialized::Bool = false end -function reinit!(filament::SemiInfiniteFilament, x1::PosVector, direction::PosVector, vel_mag::Real, filament_direction::Real) +function reinit!(filament::SemiInfiniteFilament{T}, x1::AbstractVector, direction::AbstractVector, vel_mag::Real, filament_direction::Real) where T filament.x1 .= x1 filament.direction .= direction filament.vel_mag = vel_mag diff --git a/src/obj_geometry.jl b/src/obj_geometry.jl index eddd60be..fdaefd2c 100644 --- a/src/obj_geometry.jl +++ b/src/obj_geometry.jl @@ -246,7 +246,7 @@ This method enables deformation support for OBJ wings by: # Effects Updates wing.refined_sections and wing.non_deformed_sections in-place. """ -function refine_obj_wing!(wing::AbstractWing; recompute_mapping=true) +function refine_obj_wing!(wing::AbstractWing{T}; recompute_mapping=true) where {T} n_unrefined = wing.n_unrefined_sections n_refined = wing.n_panels + 1 @@ -274,7 +274,7 @@ function refine_obj_wing!(wing::AbstractWing; recompute_mapping=true) # 4. Create refined sections with interpolated deltas refined_gammas = range(-wing.gamma_tip, wing.gamma_tip, n_refined) if isempty(wing.refined_sections) - wing.refined_sections = [Section() for _ in 1:n_refined] + wing.refined_sections = [Section{T}() for _ in 1:n_refined] end for (idx, gamma) in enumerate(refined_gammas) @@ -568,7 +568,7 @@ function ObjWing( end # Create unrefined sections (evenly spaced including both tips) - sections = Section[] + sections = Section{Float64}[] aero_data = (collect(alpha_range), collect(delta_range), cl_matrix, cd_matrix, cm_matrix) for gamma in range(-gamma_tip, gamma_tip, n_unrefined_sections) LE_point = [le_interp[i](gamma) for i in 1:3] @@ -576,14 +576,18 @@ function ObjWing( push!(sections, Section(LE_point, TE_point, POLAR_MATRICES, aero_data)) end - panel_props = PanelProperties{n_panels}() + panel_props = PanelProperties{n_panels, Float64}() cache = [PreallocationTools.LazyBufferCache()] - wing = Wing(Int16(n_panels), Int16(n_unrefined_sections), spanwise_distribution, panel_props, MVec3(spanwise_direction), - sections, Section[], remove_nan, use_prior_polar, 0.0, # billowing_percentage + wing = Wing{n_panels, Float64}( + Int16(n_panels), Int16(n_unrefined_sections), spanwise_distribution, panel_props, + MVector{3, Float64}(spanwise_direction), + sections, Section{Float64}[], remove_nan, use_prior_polar, 0.0, # billowing_percentage Int16[], # refined_panel_mapping empty - Section[], zeros(n_panels), zeros(n_panels), # non_deformed, theta, delta - mass, gamma_tip, inertia_tensor, MVec3(T_cad_body), MMat3(R_cad_body), radius, + Section{Float64}[], zeros(Float64, n_panels), zeros(Float64, n_panels), + Float64(mass), Float64(gamma_tip), Matrix{Float64}(inertia_tensor), + MVector{3, Float64}(T_cad_body), MMatrix{3, 3, Float64, 9}(R_cad_body), + Float64(radius), le_interp, te_interp, area_interp, cache) # Auto-refine for backward compatibility diff --git a/src/panel.jl b/src/panel.jl index ffd2e378..3d58db3e 100644 --- a/src/panel.jl +++ b/src/panel.jl @@ -43,41 +43,42 @@ Represents a panel in a vortex step method simulation. All points and vectors ar SemiInfiniteFilament() ): Panel filaments, see: [BoundFilament](@ref) """ -@with_kw mutable struct Panel - TE_point_1::MVec3 = zeros(MVec3) - LE_point_1::MVec3 = zeros(MVec3) - TE_point_2::MVec3 = zeros(MVec3) - LE_point_2::MVec3 = zeros(MVec3) - chord::Float64 = zero(Float64) - va::MVec3 = zeros(MVec3) - corner_points::MMatrix{3, 4, Float64, 12} = zeros(MMatrix{3, 4, Float64, 12}) +@with_kw mutable struct Panel{T} + TE_point_1::MVector{3, T} = zeros(MVector{3, T}) + LE_point_1::MVector{3, T} = zeros(MVector{3, T}) + TE_point_2::MVector{3, T} = zeros(MVector{3, T}) + LE_point_2::MVector{3, T} = zeros(MVector{3, T}) + chord::T = zero(T) + va::MVector{3, T} = zeros(MVector{3, T}) + corner_points::MMatrix{3, 4, T, 12} = zeros(MMatrix{3, 4, T, 12}) aero_model::AeroModel = INVISCID + # Polar / Breukels coefficients are static lookup-table data — kept Float64 cl_coeffs::Vector{Float64} = zeros(Float64, 3) cd_coeffs::Vector{Float64} = zeros(Float64, 3) cm_coeffs::Vector{Float64} = zeros(Float64, 3) cl_interp::Union{Nothing, I1, I2, I3, I4} = nothing cd_interp::Union{Nothing, I1, I2, I3, I4, I5, I6} = nothing cm_interp::Union{Nothing, I1, I2, I3, I4} = nothing - aero_center::MVec3 = zeros(MVec3) - control_point::MVec3 = zeros(MVec3) - bound_point_1::MVec3 = zeros(MVec3) - bound_point_2::MVec3 = zeros(MVec3) - x_airf::MVec3 = zeros(MVec3) - y_airf::MVec3 = zeros(MVec3) - z_airf::MVec3 = zeros(MVec3) - width::Float64 = zero(Float64) - filaments::Tuple{BoundFilament,BoundFilament,BoundFilament,SemiInfiniteFilament,SemiInfiniteFilament} = ( - BoundFilament(), - BoundFilament(), - BoundFilament(), - SemiInfiniteFilament(), - SemiInfiniteFilament() + aero_center::MVector{3, T} = zeros(MVector{3, T}) + control_point::MVector{3, T} = zeros(MVector{3, T}) + bound_point_1::MVector{3, T} = zeros(MVector{3, T}) + bound_point_2::MVector{3, T} = zeros(MVector{3, T}) + x_airf::MVector{3, T} = zeros(MVector{3, T}) + y_airf::MVector{3, T} = zeros(MVector{3, T}) + z_airf::MVector{3, T} = zeros(MVector{3, T}) + width::T = zero(T) + filaments::Tuple{BoundFilament{T},BoundFilament{T},BoundFilament{T},SemiInfiniteFilament{T},SemiInfiniteFilament{T}} = ( + BoundFilament{T}(), + BoundFilament{T}(), + BoundFilament{T}(), + SemiInfiniteFilament{T}(), + SemiInfiniteFilament{T}() ) - delta::Float64 = 0.0 + delta::T = zero(T) end function init_pos!( - panel::Panel, + panel::Panel{T}, section_1::Section, section_2::Section, aero_center, @@ -88,8 +89,8 @@ function init_pos!( y_airf, z_airf, delta, - vec::MVec3 -) + vec::AbstractVector{T} +) where T # Initialize basic geometry panel.TE_point_1 .= section_1.TE_point panel.LE_point_1 .= section_1.LE_point @@ -262,9 +263,9 @@ Calculate the relative angle of attack and relative velocity of the panel. - relative_velocity: Relative velocity vector of the panel """ function calculate_relative_alpha_and_relative_velocity( - panel::Panel, - induced_velocity::Vector{Float64} -) + panel::Panel{T}, + induced_velocity::AbstractVector{T} +) where T # Calculate relative velocity and angle of attack # Constants throughout iterations: panel.va, panel.x_airf, panel.y_airf relative_velocity = panel.va .+ induced_velocity @@ -370,8 +371,8 @@ Calculate lift coefficient for given angle of attack. # Returns - `Float64`: Lift coefficient (Cl) """ -function calculate_cl(panel::Panel, alpha::Float64)::Float64 - isnan(alpha) && return NaN +function calculate_cl(panel::Panel, alpha::T)::T where T + isnan(alpha) && return T(NaN) if panel.aero_model == LEI_AIRFOIL_BREUKELS cl = evalpoly(rad2deg(alpha), reverse(panel.cl_coeffs)) if abs(alpha) > (π/9) @@ -383,11 +384,11 @@ function calculate_cl(panel::Panel, alpha::Float64)::Float64 elseif panel.aero_model == POLAR_VECTORS interp = panel.cl_interp interp isa Union{I1, I2} || throw(ArgumentError("cl_interp is not initialized for POLAR_VECTORS.")) - return (interp::Union{I1, I2})(alpha)::Float64 + return (interp::Union{I1, I2})(alpha)::T elseif panel.aero_model == POLAR_MATRICES interp = panel.cl_interp interp isa Union{I3, I4} || throw(ArgumentError("cl_interp is not initialized for POLAR_MATRICES.")) - return (interp::Union{I3, I4})(alpha, panel.delta)::Float64 + return (interp::Union{I3, I4})(alpha, panel.delta)::T else throw(ArgumentError("Unsupported aero model: $(panel.aero_model)")) end @@ -399,8 +400,8 @@ end Calculate drag and moment coefficients for given angle of attack. """ -function calculate_cd_cm(panel::Panel, alpha::Float64) - isnan(alpha) && return NaN, NaN +function calculate_cd_cm(panel::Panel, alpha::T)::Tuple{T, T} where T + isnan(alpha) && return T(NaN), T(NaN) if panel.aero_model == LEI_AIRFOIL_BREUKELS cd = evalpoly(rad2deg(alpha), reverse(panel.cd_coeffs)) cm = evalpoly(rad2deg(alpha), reverse(panel.cm_coeffs)) @@ -413,19 +414,19 @@ function calculate_cd_cm(panel::Panel, alpha::Float64) cm_interp = panel.cm_interp cd_interp isa Union{I1, I2, I5} || throw(ArgumentError("cd_interp is not initialized for POLAR_VECTORS.")) cm_interp isa Union{I1, I2} || throw(ArgumentError("cm_interp is not initialized for POLAR_VECTORS.")) - return (cd_interp::Union{I1, I2, I5})(alpha)::Float64, - (cm_interp::Union{I1, I2})(alpha)::Float64 + return (cd_interp::Union{I1, I2, I5})(alpha)::T, + (cm_interp::Union{I1, I2})(alpha)::T elseif panel.aero_model == POLAR_MATRICES cd_interp = panel.cd_interp cm_interp = panel.cm_interp cd_interp isa Union{I3, I4, I6} || throw(ArgumentError("cd_interp is not initialized for POLAR_MATRICES.")) cm_interp isa Union{I3, I4} || throw(ArgumentError("cm_interp is not initialized for POLAR_MATRICES.")) - return (cd_interp::Union{I3, I4, I6})(alpha, panel.delta)::Float64, - (cm_interp::Union{I3, I4})(alpha, panel.delta)::Float64 + return (cd_interp::Union{I3, I4, I6})(alpha, panel.delta)::T, + (cm_interp::Union{I3, I4})(alpha, panel.delta)::T elseif !(panel.aero_model == INVISCID) throw(ArgumentError("Unsupported aero model: $(panel.aero_model)")) end - return 0.0, 0.0 + return zero(T), zero(T) end """ @@ -498,17 +499,17 @@ Calculate the velocity induced by a vortex ring at a control point. - nothing """ @inline function calculate_velocity_induced_single_ring_semiinfinite!( - velind::MVec3, - tempvel::MVec3, + velind::AbstractVector{T}, + tempvel::AbstractVector{T}, filaments, - evaluation_point::MVec3, + evaluation_point::AbstractVector{T}, evaluation_point_on_bound::Bool, - va_norm::Float64, - va_unit::MVec3, - gamma::Float64, - core_radius_fraction::Float64, - work_vectors::NTuple{10, MVec3} -) + va_norm::T, + va_unit::AbstractVector{T}, + gamma::T, + core_radius_fraction::Real, + work_vectors +) where T velind .= 0.0 # Filament 1: bound filament (BoundFilament — compiler knows type) diff --git a/src/solver.jl b/src/solver.jl index dc062db8..5ad135b1 100644 --- a/src/solver.jl +++ b/src/solver.jl @@ -33,68 +33,68 @@ Struct for storing the solution of the [solve!](@ref) function. Must contain all - `alpha_unrefined_dist`::MVector{U, Float64}: Averaged angles of attack for unrefined sections [rad] - `solver_status`::SolverStatus: enum, see [SolverStatus](@ref) """ -@with_kw mutable struct VSMSolution{P,U} +@with_kw mutable struct VSMSolution{P, U, T} ### private vectors of solve_base! - _x_airf_dist::Matrix{Float64} = zeros(P, 3) - _y_airf_dist::Matrix{Float64} = zeros(P, 3) - _z_airf_dist::Matrix{Float64} = zeros(P, 3) - _va_dist::Matrix{Float64} = zeros(P, 3) - _chord_dist::Vector{Float64} = zeros(P) + _x_airf_dist::Matrix{T} = zeros(T, P, 3) + _y_airf_dist::Matrix{T} = zeros(T, P, 3) + _z_airf_dist::Matrix{T} = zeros(T, P, 3) + _va_dist::Matrix{T} = zeros(T, P, 3) + _chord_dist::Vector{T} = zeros(T, P) ### end of private vectors - width_dist::Vector{Float64} = zeros(P) - alpha_dist::Vector{Float64} = zeros(P) - alpha_geometric_dist::Vector{Float64} = zeros(P) - cl_dist::Vector{Float64} = zeros(P) - cd_dist::Vector{Float64} = zeros(P) - cm_dist::Vector{Float64} = zeros(P) - lift_dist::Vector{Float64} = zeros(P) - drag_dist::Vector{Float64} = zeros(P) - panel_moment_dist::Vector{Float64} = zeros(P) - f_body_3D::Matrix{Float64} = zeros(3, P) - m_body_3D::Matrix{Float64} = zeros(3, P) - gamma_distribution::Union{Nothing, Vector{Float64}} = nothing - force::MVec3 = zeros(MVec3) - moment::MVec3 = zeros(MVec3) - force_coeffs::MVec3 = zeros(MVec3) - moment_coeffs::MVec3 = zeros(MVec3) - center_of_pressure::Union{Nothing, MVec3} = nothing - panel_cp_locations::Vector{MVec3} = MVec3[] - moment_dist::MVector{P, Float64} = zeros(P) - moment_coeff_dist::MVector{P, Float64} = zeros(P) - moment_unrefined_dist::MVector{U, Float64} = zeros(U) - cl_unrefined_dist::MVector{U, Float64} = zeros(U) - cd_unrefined_dist::MVector{U, Float64} = zeros(U) - cm_unrefined_dist::MVector{U, Float64} = zeros(U) - alpha_unrefined_dist::MVector{U, Float64} = zeros(U) - x_airf_unrefined_dist::Vector{MVec3} = [MVec3(0,0,0) for _ in 1:U] - y_airf_unrefined_dist::Vector{MVec3} = [MVec3(0,0,0) for _ in 1:U] - z_airf_unrefined_dist::Vector{MVec3} = [MVec3(0,0,0) for _ in 1:U] - va_unrefined_dist::Vector{MVec3} = [MVec3(0,0,0) for _ in 1:U] - chord_unrefined_dist::MVector{U, Float64} = zeros(U) - width_unrefined_dist::MVector{U, Float64} = zeros(U) + width_dist::Vector{T} = zeros(T, P) + alpha_dist::Vector{T} = zeros(T, P) + alpha_geometric_dist::Vector{T} = zeros(T, P) + cl_dist::Vector{T} = zeros(T, P) + cd_dist::Vector{T} = zeros(T, P) + cm_dist::Vector{T} = zeros(T, P) + lift_dist::Vector{T} = zeros(T, P) + drag_dist::Vector{T} = zeros(T, P) + panel_moment_dist::Vector{T} = zeros(T, P) + f_body_3D::Matrix{T} = zeros(T, 3, P) + m_body_3D::Matrix{T} = zeros(T, 3, P) + gamma_distribution::Union{Nothing, Vector{T}} = nothing + force::MVector{3, T} = zeros(MVector{3, T}) + moment::MVector{3, T} = zeros(MVector{3, T}) + force_coeffs::MVector{3, T} = zeros(MVector{3, T}) + moment_coeffs::MVector{3, T} = zeros(MVector{3, T}) + center_of_pressure::Union{Nothing, MVector{3, T}} = nothing + panel_cp_locations::Vector{MVector{3, T}} = MVector{3, T}[] + moment_dist::MVector{P, T} = zeros(MVector{P, T}) + moment_coeff_dist::MVector{P, T} = zeros(MVector{P, T}) + moment_unrefined_dist::MVector{U, T} = zeros(MVector{U, T}) + cl_unrefined_dist::MVector{U, T} = zeros(MVector{U, T}) + cd_unrefined_dist::MVector{U, T} = zeros(MVector{U, T}) + cm_unrefined_dist::MVector{U, T} = zeros(MVector{U, T}) + alpha_unrefined_dist::MVector{U, T} = zeros(MVector{U, T}) + x_airf_unrefined_dist::Vector{MVector{3, T}} = [zeros(MVector{3, T}) for _ in 1:U] + y_airf_unrefined_dist::Vector{MVector{3, T}} = [zeros(MVector{3, T}) for _ in 1:U] + z_airf_unrefined_dist::Vector{MVector{3, T}} = [zeros(MVector{3, T}) for _ in 1:U] + va_unrefined_dist::Vector{MVector{3, T}} = [zeros(MVector{3, T}) for _ in 1:U] + chord_unrefined_dist::MVector{U, T} = zeros(MVector{U, T}) + width_unrefined_dist::MVector{U, T} = zeros(MVector{U, T}) solver_status::SolverStatus = FAILURE end # Output of the function gamma_loop! -@with_kw mutable struct LoopResult{P} - converged::Bool = false - gamma_new::MVector{P, Float64} = zeros(P) - alpha_dist::MVector{P, Float64} = zeros(P) # TODO: Is this different from BodyAerodynamics.alpha_dist ? - v_a_dist::MVector{P, Float64} = zeros(P) +@with_kw mutable struct LoopResult{P, T} + converged::Bool = false + gamma_new::MVector{P, T} = zeros(MVector{P, T}) + alpha_dist::MVector{P, T} = zeros(MVector{P, T}) + v_a_dist::MVector{P, T} = zeros(MVector{P, T}) end -@with_kw struct BaseResult{P} - va_norm_dist::MVector{P, Float64} = zeros(P) - va_unit_dist::Matrix{Float64} = zeros(P, 3) +@with_kw struct BaseResult{P, T} + va_norm_dist::MVector{P, T} = zeros(MVector{P, T}) + va_unit_dist::Matrix{T} = zeros(T, P, 3) end -@inline function check_reference_point(reference_point) +@inline function check_reference_point(reference_point, ::Type{T}=Float64) where {T} msg = "reference_point must be a list/array with 3 numbers." reference_point isa AbstractVector || throw(ArgumentError(msg)) length(reference_point) == 3 || throw(ArgumentError(msg)) all(x -> x isa Number, reference_point) || throw(ArgumentError(msg)) try - return MVec3(Float64(reference_point[1]), Float64(reference_point[2]), Float64(reference_point[3])) + return MVector{3, T}(reference_point[1], reference_point[2], reference_point[3]) catch throw(ArgumentError(msg)) end @@ -130,53 +130,52 @@ Main solver structure for the Vortex Step Method.See also: [solve](@ref) ## Solution sol::VSMSolution = VSMSolution(): The result of calling [solve!](@ref) """ -@with_kw mutable struct Solver{P,U} +@with_kw mutable struct Solver{P, U, T} # General settings solver_type::SolverType = LOOP aerodynamic_model_type::Model = VSM - density::Float64 = 1.225 + density::T = T(1.225) max_iterations::Int64 = 1500 - rtol::Float64 = 1e-5 - tol_reference_error::Float64 = 0.001 - relaxation_factor::Float64 = 0.03 + rtol::T = T(1e-5) + tol_reference_error::T = T(0.001) + relaxation_factor::T = T(0.03) # Nonlin solver fields - atol::Float64 = 1e-5 - nonlin_jac::Matrix{Float64} = zeros(P, P) - nonlin_residual::MVector{P, Float64} = zeros(P) - nonlin_residual_perturbed::MVector{P, Float64} = zeros(P) - nonlin_gamma_perturbed::MVector{P, Float64} = zeros(P) + atol::T = T(1e-5) + nonlin_jac::Matrix{T} = zeros(T, P, P) + nonlin_residual::MVector{P, T} = zeros(MVector{P, T}) + nonlin_residual_perturbed::MVector{P, T} = zeros(MVector{P, T}) + nonlin_gamma_perturbed::MVector{P, T} = zeros(MVector{P, T}) nonlin_ipiv::Vector{LinearAlgebra.BlasInt} = zeros(LinearAlgebra.BlasInt, P) - + # Damping settings is_with_artificial_damping::Bool = false artificial_damping::NamedTuple{(:k2, :k4), Tuple{Float64, Float64}} =(k2=0.1, k4=0.0) - + # Additional settings type_initial_gamma_distribution::InitialGammaDistribution = ZEROS use_gamma_prev::Bool = true - core_radius_fraction::Float64 = 0.05 - mu::Float64 = 1.81e-5 + core_radius_fraction::T = T(0.05) + mu::T = T(1.81e-5) is_only_f_and_gamma_output::Bool = false correct_aoa::Bool = false - reference_point::MVec3 = zeros(MVec3) + reference_point::MVector{3, T} = zeros(MVector{3, T}) # Intermediate results - lr::LoopResult{P} = LoopResult{P}() - br::BaseResult{P} = BaseResult{P}() + lr::LoopResult{P, T} = LoopResult{P, T}() + br::BaseResult{P, T} = BaseResult{P, T}() cache::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}} = [LazyBufferCache() for _ in 1:11] cache_base::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}} = [LazyBufferCache()] cache_lin::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}} = [LazyBufferCache() for _ in 1:4] - + # Solution - sol::VSMSolution{P,U} = VSMSolution{P,U}() + sol::VSMSolution{P, U, T} = VSMSolution{P, U, T}() end -function Solver(body_aero; reference_point=[0.0, 0.0, 0.0], kwargs...) - P = length(body_aero.panels) +function Solver(body_aero::BodyAerodynamics{P, W, T}; reference_point=[0.0, 0.0, 0.0], kwargs...) where {P, W, T} U = sum([wing.n_unrefined_sections for wing in body_aero.wings]) - reference_point_checked = check_reference_point(reference_point) - return Solver{P,U}(; reference_point=reference_point_checked, kwargs...) + reference_point_checked = check_reference_point(reference_point, T) + return Solver{P, U, T}(; reference_point=reference_point_checked, kwargs...) end function Solver(body_aero, settings::VSMSettings) @@ -224,8 +223,8 @@ a dictionary. # Returns The solution of type [VSMSolution](@ref) """ -function solve!(solver::Solver, body_aero::BodyAerodynamics, gamma_distribution=solver.sol.gamma_distribution; - log=false, reference_point=solver.reference_point, moment_frac=0.1) +function solve!(solver::Solver{P, U, T}, body_aero::BodyAerodynamics, gamma_distribution=solver.sol.gamma_distribution; + log=false, reference_point=solver.reference_point, moment_frac=0.1) where {P, U, T} # calculate intermediate result solve_base!(solver, body_aero, gamma_distribution; log) @@ -320,8 +319,8 @@ function solve!(solver::Solver, body_aero::BodyAerodynamics, gamma_distribution= end # Initialize result arrays - area_all_panels = 0.0 - panel_areas = zeros(length(panels)) + area_all_panels = zero(T) + panel_areas = zeros(T, length(panels)) # Get wing properties spanwise_direction = body_aero.wings[1].spanwise_direction @@ -583,8 +582,8 @@ end end end -function solve_base!(solver::Solver, body_aero::BodyAerodynamics, gamma_distribution=nothing; - log=false) +function solve_base!(solver::Solver{P, U, T}, body_aero::BodyAerodynamics, gamma_distribution=nothing; + log=false) where {P, U, T} # check arguments isnothing(body_aero.panels[1].va) && throw(ArgumentError("Inflow conditions are not set, use set_va!(body_aero, va)")) @@ -661,7 +660,7 @@ end gamma_out, gamma_in, solver::Solver, - panels::Vector{Panel}, + panels::AbstractVector{<:Panel}, n_panels::Int, AIC_x, AIC_y, @@ -739,17 +738,17 @@ end """ gamma_loop!(solver::Solver, AIC_x::Matrix{Float64}, AIC_y::Matrix{Float64}, AIC_z::Matrix{Float64}, - panels::Vector{Panel}, relaxation_factor::Float64; log=true) + panels::AbstractVector{<:Panel}, relaxation_factor::Float64; log=true) Main iteration loop for calculating circulation distribution. """ function gamma_loop!( - solver::Solver, + solver::Solver{P, U, T}, body_aero::BodyAerodynamics, - panels::Vector{Panel}, - relaxation_factor::Float64; + panels::AbstractVector{<:Panel}, + relaxation_factor; log::Bool = true -) +) where {P, U, T} va_array = solver.sol._va_dist chord_array = solver.sol._chord_dist x_airf_array = solver.sol._x_airf_dist @@ -781,6 +780,9 @@ function gamma_loop!( velocity_view_z = @view induced_velocity_all[:, 3] if solver.solver_type == NONLIN + T <: ForwardDiff.Dual && error( + "NONLIN solver does not support ForwardDiff in this release. " * + "Use `solver_type=LOOP` for differentiable solves.") gamma_iter = solver.lr.gamma_new residual = solver.nonlin_residual residual_perturbed = solver.nonlin_residual_perturbed @@ -1056,12 +1058,93 @@ jac, results, converged = linearize(solver, body_aero, y_op; # jac is (10×10): [6 force/moment coeffs + 4 unrefined moment coeffs] × [4 theta + 3 va + 3 omega] ``` """ +function _section_with_eltype(section::Section, ::Type{TD}) where TD + return Section{TD}( + MVector{3, TD}(section.LE_point), + MVector{3, TD}(section.TE_point), + section.aero_model, + section.aero_data, + ) +end + +function _wing_with_eltype(wing::Wing{P, Float64}, ::Type{TD}) where {P, TD} + return Wing{P, TD}( + wing.n_panels, + wing.n_unrefined_sections, + wing.spanwise_distribution, + PanelProperties{P, TD}(), + MVector{3, TD}(wing.spanwise_direction), + Section{TD}[_section_with_eltype(s, TD) for s in wing.unrefined_sections], + Section{TD}[_section_with_eltype(s, TD) for s in wing.refined_sections], + wing.remove_nan, + wing.use_prior_polar, + wing.billowing_percentage, + copy(wing.refined_panel_mapping), + Section{TD}[_section_with_eltype(s, TD) for s in wing.non_deformed_sections], + Vector{TD}(wing.theta_dist), + Vector{TD}(wing.delta_dist), + TD(wing.mass), + TD(wing.gamma_tip), + Matrix{TD}(wing.inertia_tensor), + MVector{3, TD}(wing.T_cad_body), + MMatrix{3, 3, TD, 9}(wing.R_cad_body), + TD(wing.radius), + wing.le_interp, + wing.te_interp, + wing.area_interp, + [PreallocationTools.LazyBufferCache()], + ) +end + +""" + make_dual_shadow(solver, body_aero, ::Type{TD}) where TD + +Build a `BodyAerodynamics`/`Solver` pair whose mutating buffers carry element type +`TD` (typically a `ForwardDiff.Dual`). Wing geometry, polar coefficients and +interpolators are reused from the Float64 originals; circulation/AIC/scratch +buffers are freshly allocated as `TD`-typed. +""" +function make_dual_shadow(solver::Solver{P, U, Float64}, + body_aero::BodyAerodynamics{P, W, Float64}, + ::Type{TD}) where {P, U, W, TD} + length(body_aero.wings) == 1 || throw(ArgumentError( + "make_dual_shadow currently supports body_aero with one wing")) + wing_d = _wing_with_eltype(body_aero.wings[1], TD) + body_aero_d = BodyAerodynamics([wing_d]; + va = MVector{3, TD}(body_aero._va), + omega = MVector{3, TD}(body_aero.omega), + ) + solver_d = Solver(body_aero_d; + solver_type = solver.solver_type, + aerodynamic_model_type = solver.aerodynamic_model_type, + density = TD(solver.density), + max_iterations = solver.max_iterations, + rtol = TD(solver.rtol), + tol_reference_error = TD(solver.tol_reference_error), + relaxation_factor = TD(solver.relaxation_factor), + atol = TD(solver.atol), + is_with_artificial_damping = solver.is_with_artificial_damping, + artificial_damping = solver.artificial_damping, + type_initial_gamma_distribution = solver.type_initial_gamma_distribution, + # Forced off: warm-starting with Duals from a prior chunk would leak + # stale gradient information into the next column of the Jacobian. + use_gamma_prev = false, + core_radius_fraction = TD(solver.core_radius_fraction), + mu = TD(solver.mu), + is_only_f_and_gamma_output = solver.is_only_f_and_gamma_output, + correct_aoa = solver.correct_aoa, + reference_point = MVector{3, TD}(solver.reference_point), + ) + return body_aero_d, solver_d +end + function linearize(solver::Solver, body_aero::BodyAerodynamics, y::Vector{T}; theta_idxs=1:4, delta_idxs=nothing, va_idxs=nothing, omega_idxs=nothing, aero_coeffs=false, + backend = AutoForwardDiff(), fd_absstep::Float64=1e-3, fd_relstep::Float64=1e-3, kwargs...) where T @@ -1082,75 +1165,90 @@ function linearize(solver::Solver, body_aero::BodyAerodynamics, y::Vector{T}; throw(ArgumentError("Cannot use theta_idxs or delta_idxs when wing has no unrefined sections")) end - init_va = body_aero.cache[1][body_aero._va] - init_va .= body_aero._va - init_omega = copy(body_aero.omega) - last_theta_ref = Ref{Vector{T}}(Vector{T}(undef, 0)) - if !isnothing(theta_idxs) - @views last_theta_ref[] = body_aero.cache[2][y[theta_idxs]] - last_theta_ref[] .= NaN - end - last_delta_ref = Ref{Vector{T}}(Vector{T}(undef, 0)) - if !isnothing(delta_idxs) - @views last_delta_ref[] = body_aero.cache[3][y[delta_idxs]] - last_delta_ref[] .= NaN - end - n_failed = Ref(0) + # Lazily-built Dual shadow keyed by element type; rebuilt only when + # eltype changes (e.g. across DI/ForwardDiff tag transitions). + shadow_ref = Ref{Any}(nothing) + last_theta_ref = Ref{Any}(nothing) + last_delta_ref = Ref{Any}(nothing) + + function calc_results!(results, y_in) + TI = eltype(y_in) + if TI === Float64 + body_aero_c = body_aero + solver_c = solver + wing_c = wing + else + shadow = shadow_ref[] + need_new = shadow === nothing || + eltype(shadow[1]._va) !== TI + if need_new + shadow_ref[] = make_dual_shadow(solver, body_aero, TI) + end + body_aero_c, solver_c = shadow_ref[] + wing_c = body_aero_c.wings[1] + end - # Function to compute forces for given control inputs - function calc_results!(results, y) - @views theta_angles = isnothing(theta_idxs) ? nothing : y[theta_idxs] - @views delta_angles = isnothing(delta_idxs) ? nothing : y[delta_idxs] + if !isnothing(theta_idxs) && + (last_theta_ref[] === nothing || eltype(last_theta_ref[]) !== TI) + last_theta_ref[] = fill(TI(NaN), length(theta_idxs)) + end + if !isnothing(delta_idxs) && + (last_delta_ref[] === nothing || eltype(last_delta_ref[]) !== TI) + last_delta_ref[] = fill(TI(NaN), length(delta_idxs)) + end + + @views theta_angles = isnothing(theta_idxs) ? nothing : y_in[theta_idxs] + @views delta_angles = isnothing(delta_idxs) ? nothing : y_in[delta_idxs] last_theta = last_theta_ref[] last_delta = last_delta_ref[] if !isnothing(theta_angles) && isnothing(delta_angles) if !all(theta_angles .== last_theta) - VortexStepMethod.unrefined_deform!(wing, theta_angles, nothing; smooth=false) - VortexStepMethod.reinit!(body_aero; init_aero=false) + VortexStepMethod.unrefined_deform!(wing_c, theta_angles, nothing; smooth=false) + VortexStepMethod.reinit!(body_aero_c; init_aero=false) last_theta .= theta_angles end elseif !isnothing(theta_angles) && !isnothing(delta_angles) if !all(delta_angles .== last_delta) || !all(theta_angles .== last_theta) - VortexStepMethod.unrefined_deform!(wing, theta_angles, delta_angles; smooth=false) - VortexStepMethod.reinit!(body_aero; init_aero=false) + VortexStepMethod.unrefined_deform!(wing_c, theta_angles, delta_angles; smooth=false) + VortexStepMethod.reinit!(body_aero_c; init_aero=false) last_theta .= theta_angles last_delta .= delta_angles end elseif isnothing(theta_angles) && !isnothing(delta_angles) if !all(delta_angles .== last_delta) - VortexStepMethod.unrefined_deform!(wing, nothing, delta_angles; smooth=false) - VortexStepMethod.reinit!(body_aero; init_aero=false) + VortexStepMethod.unrefined_deform!(wing_c, nothing, delta_angles; smooth=false) + VortexStepMethod.reinit!(body_aero_c; init_aero=false) last_delta .= delta_angles end end - va = isnothing(va_idxs) ? init_va : y[va_idxs] - om = isnothing(omega_idxs) ? init_omega : - y[omega_idxs] - set_va!(body_aero, va, om) + va = isnothing(va_idxs) ? MVector{3, TI}(body_aero_c._va) : y_in[va_idxs] + om = isnothing(omega_idxs) ? MVector{3, TI}(body_aero_c.omega) : y_in[omega_idxs] + set_va!(body_aero_c, va, om) - solve!(solver, body_aero; kwargs...) - solver.lr.converged || (n_failed[] += 1) + solve!(solver_c, body_aero_c; kwargs...) + solver_c.lr.converged || (n_failed[] += 1) if !aero_coeffs - results[1:3] .= solver.sol.force - results[4:6] .= solver.sol.moment - results[7:end] .= solver.sol.moment_unrefined_dist + results[1:3] .= solver_c.sol.force + results[4:6] .= solver_c.sol.moment + results[7:end] .= solver_c.sol.moment_unrefined_dist else - results[1:3] .= solver.sol.force_coeffs - results[4:6] .= solver.sol.moment_coeffs - results[7:end] .= solver.sol.cm_unrefined_dist + results[1:3] .= solver_c.sol.force_coeffs + results[4:6] .= solver_c.sol.moment_coeffs + results[7:end] .= solver_c.sol.cm_unrefined_dist end return nothing end - results = zeros(3+3+length(solver.sol.moment_unrefined_dist)) - jac = zeros(length(results), length(y)) - backend = AutoFiniteDiff(absstep=fd_absstep, relstep=fd_relstep) - prep = prepare_jacobian(calc_results!, results, backend, y) - jacobian!(calc_results!, results, jac, prep, backend, y) - + n_results = 3 + 3 + length(solver.sol.moment_unrefined_dist) + jac = zeros(n_results, length(y)) + results = zeros(n_results) + be = backend === nothing ? + AutoFiniteDiff(absstep=fd_absstep, relstep=fd_relstep) : backend + prep = prepare_jacobian(calc_results!, results, be, y) + jacobian!(calc_results!, results, jac, prep, be, y) calc_results!(results, y) converged = n_failed[] == 0 if !converged diff --git a/src/wing_geometry.jl b/src/wing_geometry.jl index 5dae50ed..3fe45e0c 100644 --- a/src/wing_geometry.jl +++ b/src/wing_geometry.jl @@ -9,9 +9,9 @@ Represents a wing section with leading edge, trailing edge, and aerodynamic prop - `aero_model`::AeroModel = INVISCID: [AeroModel](@ref) - `aero_data`::AeroData = nothing: See: [AeroData](@ref) """ -@with_kw mutable struct Section - LE_point::MVec3 = zeros(MVec3) - TE_point::MVec3 = zeros(MVec3) +@with_kw mutable struct Section{T} + LE_point::MVector{3, T} = zeros(MVector{3, T}) + TE_point::MVector{3, T} = zeros(MVector{3, T}) aero_model::AeroModel = INVISCID aero_data::AeroData = nothing end @@ -19,19 +19,23 @@ end """ Section(LE_point::PosVector, TE_point::PosVector, aero_model) -Create a new wing section with the specified leading edge point, trailing edge point, +Create a new wing section with the specified leading edge point, trailing edge point, and aerodynamic model. # Arguments - `LE_point::PosVector`: Leading edge point coordinates -- `TE_point::PosVector`: Trailing edge point coordinates +- `TE_point::PosVector`: Trailing edge point coordinates - `aero_model::AeroModel`: Aerodynamic model type (e.g., INVISCID, POLAR_VECTORS) # Returns - `Section`: A new section with the specified parameters and no aerodynamic data """ function Section(LE_point, TE_point, aero_model) - return Section(LE_point, TE_point, aero_model, nothing) + return Section{Float64}(MVector{3,Float64}(LE_point), MVector{3,Float64}(TE_point), aero_model, nothing) +end + +function Section(LE_point, TE_point, aero_model, aero_data) + return Section{Float64}(MVector{3,Float64}(LE_point), MVector{3,Float64}(TE_point), aero_model, aero_data) end """ @@ -57,7 +61,7 @@ function reinit!(section::Section, LE_point, TE_point, aero_model=nothing, aero_ nothing end -function reinit!(refined_section::Section, section::Section) +function reinit!(refined_section::Section{Tr}, section::Section) where {Tr} reinit!( refined_section, section.LE_point, @@ -81,15 +85,15 @@ Structure to hold calculated panel properties. - `y_airf`::Matrix{Float64}: Vector of unit vectors in spanwise direction - `z_airf`::Matrix{Float64}: Vector of unit vectors pointing up (cross of x_airf and y_airf) """ -@with_kw mutable struct PanelProperties{P} - aero_centers::Matrix{Float64} = zeros(P, 3) - control_points::Matrix{Float64} = zeros(P, 3) - bound_points_1::Matrix{Float64} = zeros(P, 3) - bound_points_2::Matrix{Float64} = zeros(P, 3) - x_airf::Matrix{Float64} = zeros(P, 3) - y_airf::Matrix{Float64} = zeros(P, 3) - z_airf::Matrix{Float64} = zeros(P, 3) - coords::Matrix{Float64} = zeros(2(P+1), 3) +@with_kw mutable struct PanelProperties{P, T} + aero_centers::Matrix{T} = zeros(T, P, 3) + control_points::Matrix{T} = zeros(T, P, 3) + bound_points_1::Matrix{T} = zeros(T, P, 3) + bound_points_2::Matrix{T} = zeros(T, P, 3) + x_airf::Matrix{T} = zeros(T, P, 3) + y_airf::Matrix{T} = zeros(T, P, 3) + z_airf::Matrix{T} = zeros(T, P, 3) + coords::Matrix{T} = zeros(T, 2(P+1), 3) end """ @@ -104,7 +108,7 @@ Update geometric properties for each panel. # Returns: `nothing`, updates the [PanelProperties](@ref) in-place """ -function update_panel_properties!(panel_props::PanelProperties, section_list::Vector{Section}, n_panels) +function update_panel_properties!(panel_props::PanelProperties{P,T}, section_list::AbstractVector{<:Section}, n_panels) where {P,T} coords = panel_props.coords aero_centers = panel_props.aero_centers control_points = panel_props.control_points @@ -113,8 +117,8 @@ function update_panel_properties!(panel_props::PanelProperties, section_list::Ve x_airf = panel_props.x_airf y_airf = panel_props.y_airf z_airf = panel_props.z_airf - vec = zeros(MVec3) - vec2 = zeros(MVec3) + vec = zeros(MVector{3, T}) + vec2 = zeros(MVector{3, T}) @debug "Shape of coordinates: $(size(coords))" for i in 1:n_panels @@ -198,13 +202,13 @@ Represents a wing composed of multiple sections with aerodynamic properties. - `n_unrefined_sections::Int16`: Number of unrefined sections (sections before mesh refinement) - `spanwise_distribution`::PanelDistribution: [PanelDistribution](@ref) - `spanwise_direction::MVec3`: Wing span direction vector -- `sections::Vector{Section}`: Vector of wing sections, see: [Section](@ref) -- `refined_sections::Vector{Section}`: Vector of refined wing sections, see: [Section](@ref) +- `sections::AbstractVector{<:Section}`: Vector of wing sections, see: [Section](@ref) +- `refined_sections::AbstractVector{<:Section}`: Vector of refined wing sections, see: [Section](@ref) - `remove_nan::Bool`: Wether to remove the NaNs from interpolations or not - `use_prior_polar::Bool`: Keep previously-initialized section/panel polar data when refining geometry updates # Deformation Fields (optional, for deformable wings) -- `non_deformed_sections::Vector{Section}`: Original undeformed sections +- `non_deformed_sections::AbstractVector{<:Section}`: Original undeformed sections - `theta_dist::Vector{Float64}`: Panel twist angle distribution - `delta_dist::Vector{Float64}`: Trailing edge deflection distribution @@ -221,14 +225,14 @@ Represents a wing composed of multiple sections with aerodynamic properties. - `cache::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}}`: Preallocated buffers """ -mutable struct Wing{P} <: AbstractWing +mutable struct Wing{P, T} <: AbstractWing{T} n_panels::Int16 n_unrefined_sections::Int16 spanwise_distribution::PanelDistribution - panel_props::PanelProperties{P} - spanwise_direction::MVec3 - unrefined_sections::Vector{Section} - refined_sections::Vector{Section} + panel_props::PanelProperties{P, T} + spanwise_direction::MVector{3, T} + unrefined_sections::Vector{Section{T}} + refined_sections::Vector{Section{T}} remove_nan::Bool use_prior_polar::Bool billowing_percentage::Float64 # TE billow as percentage of arc length (0=flat) @@ -237,87 +241,23 @@ mutable struct Wing{P} <: AbstractWing refined_panel_mapping::Vector{Int16} # Maps each refined panel index to unrefined section index (1 to n_unrefined_sections) # Deformation fields - non_deformed_sections::Vector{Section} - theta_dist::Vector{Float64} # Length: n_panels (panel twist angles) - delta_dist::Vector{Float64} # Length: n_panels (panel TE deflection angles) + non_deformed_sections::Vector{Section{T}} + theta_dist::Vector{T} # Length: n_panels (panel twist angles) + delta_dist::Vector{T} # Length: n_panels (panel TE deflection angles) # Physical properties (OBJ-based wings) - mass::Float64 - gamma_tip::Float64 - inertia_tensor::Matrix{Float64} - T_cad_body::MVec3 - R_cad_body::MMat3 - radius::Float64 + mass::T + gamma_tip::T + inertia_tensor::Matrix{T} + T_cad_body::MVector{3, T} + R_cad_body::MMatrix{3, 3, T, 9} + radius::T le_interp::Union{Nothing, NTuple{3, Interpolations.Extrapolation}} te_interp::Union{Nothing, NTuple{3, Interpolations.Extrapolation}} area_interp::Union{Nothing, Interpolations.Extrapolation} cache::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}} end -# Compatibility constructor for full positional initialization with integer panel counts. -# This keeps call sites that pass Int values working after n_panels/n_unrefined_sections -# were tightened to Int16 fields. -function Wing( - n_panels::Integer, - n_unrefined_sections::Integer, - spanwise_distribution::PanelDistribution, - panel_props::PanelProperties{P}, - spanwise_direction::MVec3, - unrefined_sections::Vector{Section}, - refined_sections::Vector{Section}, - remove_nan::Bool, - use_prior_polar::Bool, - billowing_percentage::Float64, - refined_panel_mapping::Vector{Int16}, - non_deformed_sections::Vector{Section}, - theta_dist::Vector{Float64}, - delta_dist::Vector{Float64}, - mass::Float64, - gamma_tip::Float64, - inertia_tensor::Matrix{Float64}, - T_cad_body::MVec3, - R_cad_body::MMat3, - radius::Float64, - le_interp::Union{Nothing, NTuple{3, Interpolations.Extrapolation}}, - te_interp::Union{Nothing, NTuple{3, Interpolations.Extrapolation}}, - area_interp::Union{Nothing, Interpolations.Extrapolation}, - cache::Vector{PreallocationTools.LazyBufferCache{typeof(identity), typeof(identity)}} - ) where {P} - - n_panels_i16 = Int16(n_panels) - n_unrefined_sections_i16 = Int16(n_unrefined_sections) - - Int(n_panels_i16) == P || throw(ArgumentError( - "n_panels ($n_panels) must match PanelProperties{$P}" - )) - - return Wing{P}( - n_panels_i16, - n_unrefined_sections_i16, - spanwise_distribution, - panel_props, - spanwise_direction, - unrefined_sections, - refined_sections, - remove_nan, - use_prior_polar, - billowing_percentage, - refined_panel_mapping, - non_deformed_sections, - theta_dist, - delta_dist, - mass, - gamma_tip, - inertia_tensor, - T_cad_body, - R_cad_body, - radius, - le_interp, - te_interp, - area_interp, - cache - ) -end """ Wing(n_panels::Int; @@ -353,17 +293,17 @@ function Wing(n_panels::Int; n_unrefined_sections_value::Int16 = isnothing(n_unrefined_sections) ? Int16(0) : Int16(n_unrefined_sections) - panel_props::PanelProperties{n_panels} = PanelProperties{n_panels}() - spanwise_direction_m::MVec3 = MVec3(spanwise_direction) + panel_props::PanelProperties{n_panels, Float64} = PanelProperties{n_panels, Float64}() + spanwise_direction_m::MVector{3, Float64} = MVector{3, Float64}(spanwise_direction) # Initialize with default/empty values for optional fields - Wing{n_panels}( + Wing{n_panels, Float64}( Int16(n_panels), n_unrefined_sections_value, spanwise_distribution, panel_props, spanwise_direction_m, - Section[], Section[], remove_nan, use_prior_polar, Float64(billowing_percentage), + Section{Float64}[], Section{Float64}[], remove_nan, use_prior_polar, Float64(billowing_percentage), # Grouping Int16[], # Deformation fields - Section[], zeros(max(0, n_panels)), zeros(max(0, n_panels)), + Section{Float64}[], zeros(max(0, n_panels)), zeros(max(0, n_panels)), # Physical properties (defaults for non-OBJ wings) 0.0, 0.0, zeros(0, 0), zeros(MVec3), MMat3(I), 0.0, nothing, nothing, nothing, @@ -553,7 +493,7 @@ Converts panel angles (n_panels) to section angles (n_panels+1) by averaging adj # Effects Updates wing.refined_sections based on wing.non_deformed_sections and stored distributions """ -function deform!(wing::Wing; smooth=false, smooth_window=nothing) +function deform!(wing::Wing{P, T}; smooth=false, smooth_window=nothing) where {P, T} !isempty(wing.non_deformed_sections) || return nothing # Apply smoothing if requested @@ -573,9 +513,9 @@ function deform!(wing::Wing; smooth=false, smooth_window=nothing) smooth_distribution!(wing.delta_dist, smooth_window) end - local_y = zeros(MVec3) - chord = zeros(MVec3) - normal = zeros(MVec3) + local_y = zeros(MVector{3, T}) + chord = zeros(MVector{3, T}) + normal = zeros(MVector{3, T}) # Process all refined sections (n_panels + 1) # Convert panel angles to section angles by averaging @@ -674,14 +614,14 @@ Add a new section to the wing. - `aero_model`::AeroModel: [AeroModel](@ref) - `aero_data`::AeroData: See [AeroData](@ref) """ -function add_section!(wing::Wing, LE_point, - TE_point, aero_model::AeroModel, aero_data::AeroData=nothing) +function add_section!(wing::Wing{P, T}, LE_point, + TE_point, aero_model::AeroModel, aero_data::AeroData=nothing) where {P, T} if aero_model == POLAR_VECTORS && wing.remove_nan aero_data = remove_vector_nans(aero_data) elseif aero_model == POLAR_MATRICES && wing.remove_nan interpolate_polar_matrix_nans!(aero_data) end - push!(wing.unrefined_sections, Section(LE_point, TE_point, aero_model, aero_data)) + push!(wing.unrefined_sections, Section{T}(MVector{3,T}(LE_point), MVector{3,T}(TE_point), aero_model, aero_data)) wing.n_unrefined_sections = Int16(length(wing.unrefined_sections)) return nothing end @@ -713,13 +653,13 @@ This enables deformation support for all wings (YAML and OBJ). Should be called after refined_sections are populated. Once populated, non_deformed_sections serves as the undeformed reference geometry. """ -function update_non_deformed_sections!(wing::AbstractWing) +function update_non_deformed_sections!(wing::AbstractWing{T}) where {T} n_sections = wing.n_panels + 1 # Populate or update non_deformed_sections if isempty(wing.non_deformed_sections) # Initial setup - wing.non_deformed_sections = [Section() for _ in 1:n_sections] + wing.non_deformed_sections = [Section{T}() for _ in 1:n_sections] for i in 1:n_sections reinit!(wing.non_deformed_sections[i], wing.refined_sections[i]) end @@ -829,7 +769,7 @@ body_aero = BodyAerodynamics([wing]) unrefined_deform!(wing, theta_angles, delta_angles) ``` """ -function refine!(wing::AbstractWing; recompute_mapping=true, sort_sections=true) +function refine!(wing::AbstractWing{T}; recompute_mapping=true, sort_sections=true) where {T} # Validate unrefined_sections exist if isempty(wing.unrefined_sections) throw(ArgumentError( @@ -863,7 +803,7 @@ function refine!(wing::AbstractWing; recompute_mapping=true, sort_sections=true) update_non_deformed_sections!(wing) return nothing else - wing.refined_sections = Section[Section() for _ in 1:wing.n_panels+1] + wing.refined_sections = Section{T}[Section{T}() for _ in 1:wing.n_panels+1] end end @@ -997,7 +937,7 @@ end Interpolate aerodynamic input between two adjacent sections (zero-copy variant). """ function calculate_new_aero_data( - sections::Vector{Section}, + sections::AbstractVector{<:Section}, section_index::Int, left_weight::Float64, right_weight::Float64 @@ -1122,7 +1062,7 @@ function refine_mesh_for_linear_cosine_distribution!( idx, spanwise_distribution::PanelDistribution, n_sections::Int, - sections::Vector{Section}; + sections::AbstractVector{<:Section}; endpoints::Bool=true, reuse_aero_data::Bool=false) @@ -1248,16 +1188,16 @@ When `billowing_percentage > 0`, rotates chord vectors around the leading edge with a sinusoidal profile to simulate fabric billowing between ribs. """ function refine_mesh_by_splitting_provided_sections!( - wing::AbstractWing; + wing::AbstractWing{T}; reuse_aero_data::Bool=false, billowing_percentage::Float64=0.0 -) +) where {T} n_sections_provided = length(wing.unrefined_sections) n_panels_provided = n_sections_provided - 1 n_panels_desired = wing.n_panels - + @debug "Panel counts" n_panels_provided n_panels_desired n_sections_provided - + # Check if refinement is needed if n_panels_provided == n_panels_desired copy_sections_to_refined!(wing; reuse_aero_data) @@ -1271,16 +1211,16 @@ function refine_mesh_by_splitting_provided_sections!( "($n_panels_provided). Choose: $(n_panels_provided*2), $(n_panels_provided*3), ..." )) end - + # Calculate distribution n_new_sections = wing.n_panels + 1 - n_sections_provided n_section_pairs = n_sections_provided - 1 new_sections_per_pair, remaining = divrem(n_new_sections, n_section_pairs) - + sections = wing.unrefined_sections # Pre-allocate a 2-element section buffer for pair refinement - section_pair = Section[Section(), Section()] + section_pair = Section{T}[Section{T}(), Section{T}()] # Process each section pair idx = 1 @@ -1526,19 +1466,19 @@ Calculate projected wing area onto plane defined by normal vector. Returns: Float64: Projected area """ -function calculate_projected_area(wing::AbstractWing, - z_plane_vector=[0.0, 0.0, 1.0]) +function calculate_projected_area(wing::AbstractWing{T}, + z_plane_vector=[0.0, 0.0, 1.0]) where T # Normalize plane normal vector z_plane_vector = z_plane_vector ./ norm(z_plane_vector) - LE_current_proj = zeros(MVec3) - TE_current_proj = zeros(MVec3) - LE_next_proj = zeros(MVec3) - TE_next_proj = zeros(MVec3) - + LE_current_proj = zeros(MVector{3, T}) + TE_current_proj = zeros(MVector{3, T}) + LE_next_proj = zeros(MVector{3, T}) + TE_next_proj = zeros(MVector{3, T}) + # Calculate area by decomposing each projected panel quadrilateral # into two triangles: (A, B, C) and (A, C, D). - projected_area = 0.0 + projected_area = zero(T) for i in 1:(length(wing.unrefined_sections)-1) # Get section points LE_current = wing.unrefined_sections[i].LE_point diff --git a/test/Project.toml b/test/Project.toml index 029c7e73..229362d1 100644 --- a/test/Project.toml +++ b/test/Project.toml @@ -6,7 +6,9 @@ CairoMakie = "13f3f980-e62b-5c42-98c6-ff1f3baf88f0" ControlPlots = "23c2ee80-7a9e-4350-b264-8e670f12517c" DataFrames = "a93c6f00-e57d-5684-b7b6-d8193f3e46c0" DelimitedFiles = "8bb1440f-4735-579b-a4ab-409b98df4dab" +DifferentiationInterface = "a0c0ee7d-e4b9-4e03-894e-1c5f64a51d63" Documenter = "e30172f5-a6a5-5a46-863b-614d45cd2de4" +ForwardDiff = "f6369f11-7733-5829-9624-2563aa707210" Interpolations = "a98d9a8b-a2ab-59e6-89dd-64a1c18fca59" LinearAlgebra = "37e2e46d-f89d-539d-b4ee-838fcccc9c8e" Logging = "56ddb016-857b-54e1-b83d-db4d58db5568" diff --git a/test/body_aerodynamics/test_results.jl b/test/body_aerodynamics/test_results.jl index 81de23fd..f26ecaa0 100644 --- a/test/body_aerodynamics/test_results.jl +++ b/test/body_aerodynamics/test_results.jl @@ -1,5 +1,6 @@ using VortexStepMethod using VortexStepMethod: calculate_cl, calculate_cd_cm, calculate_projected_area, calculate_AIC_matrices!, reinit! +using DifferentiationInterface using LinearAlgebra using Test using Logging @@ -74,7 +75,7 @@ end solver, body_aero, base_inputs; theta_idxs=1:4, va_idxs=5:7, omega_idxs=8:10, delta_idxs=11:14, moment_frac=0.1, - fd_absstep=fd_step, fd_relstep=fd_step, + backend=AutoFiniteDiff(absstep=fd_step, relstep=fd_step), ) @test lin_converged diff --git a/test/filament/test_bound_filament.jl b/test/filament/test_bound_filament.jl index d8faadcb..511af4c3 100644 --- a/test/filament/test_bound_filament.jl +++ b/test/filament/test_bound_filament.jl @@ -4,7 +4,7 @@ using Test # Test helper functions function create_test_filament() - fil = BoundFilament() + fil = BoundFilament{Float64}() reinit!(fil, [0.0, 0.0, 0.0], [1.0, 0.0, 0.0]) return fil end @@ -71,7 +71,7 @@ end end @testset "Long Filament" begin - filament = BoundFilament() + filament = BoundFilament{Float64}() reinit!(filament, [0.0, 0.0, 0.0], [1e6, 0.0, 0.0]) control_point = [5e5, 1.0, 0.0] @@ -121,7 +121,7 @@ end end @testset "Symmetry" begin - filament = BoundFilament() + filament = BoundFilament{Float64}() reinit!(filament, [-1.0, 0.0, 0.0], [1.0, 0.0, 0.0]) velocity_3D_bound_vortex!(v1, filament, [0.0, 1.0, 0.0], gamma, core_radius_fraction, work_vectors) diff --git a/test/filament/test_semi_infinite_filament.jl b/test/filament/test_semi_infinite_filament.jl index 9105b51e..ab870fb5 100644 --- a/test/filament/test_semi_infinite_filament.jl +++ b/test/filament/test_semi_infinite_filament.jl @@ -8,7 +8,7 @@ function create_test_filament2() direction = [1.0, 0.0, 0.0] filament_direction = 1 vel_mag = 1.0 - filament = SemiInfiniteFilament() + filament = SemiInfiniteFilament{Float64}() reinit!(filament, x1, direction, vel_mag, filament_direction) return filament end diff --git a/test/panel/test_panel.jl b/test/panel/test_panel.jl index 92ec27e4..9567555d 100644 --- a/test/panel/test_panel.jl +++ b/test/panel/test_panel.jl @@ -34,7 +34,7 @@ function create_panel(section1::Section, section2::Section) y_airf = bound_2 .- bound_1 y_airf = y_airf ./ norm(y_airf) - panel = Panel() + panel = Panel{Float64}() reinit!( panel, section1, diff --git a/test/runtests.jl b/test/runtests.jl index 0397925b..2a844f69 100644 --- a/test/runtests.jl +++ b/test/runtests.jl @@ -51,6 +51,7 @@ function include_selected_tests() should_run_test("ram_geometry/test_kite_geometry.jl") && include("ram_geometry/test_kite_geometry.jl") should_run_test("settings/test_settings.jl") && include("settings/test_settings.jl") should_run_test("solver/test_solver.jl") && include("solver/test_solver.jl") + should_run_test("solver/test_forwarddiff.jl") && include("solver/test_forwarddiff.jl") should_run_test("solver/test_unrefined_dist.jl") && include("solver/test_unrefined_dist.jl") should_run_test("VortexStepMethod/test_VortexStepMethod.jl") && include("VortexStepMethod/test_VortexStepMethod.jl") should_run_test("wake/test_wake.jl") && include("wake/test_wake.jl") diff --git a/test/solver/test_forwarddiff.jl b/test/solver/test_forwarddiff.jl new file mode 100644 index 00000000..c351fe5c --- /dev/null +++ b/test/solver/test_forwarddiff.jl @@ -0,0 +1,54 @@ +using VortexStepMethod +using DifferentiationInterface +using LinearAlgebra +using Test + +@testset "ForwardDiff linearize" begin + # Build a small rectangular wing with INVISCID polars so the test runs + # quickly and the comparison is dominated by the LOOP iteration itself. + n_panels = 10 + span = 20.0 + chord = 1.0 + wing = Wing(n_panels, spanwise_distribution=LINEAR) + add_section!(wing, + [0.0, span/2, 0.0], [chord, span/2, 0.0], INVISCID) + add_section!(wing, + [0.0, -span/2, 0.0], [chord, -span/2, 0.0], INVISCID) + refine!(wing) + body_aero = BodyAerodynamics([wing]) + + va = [15.0, 1.0, 2.0] + omega = [0.0, 0.0, 0.0] + y0 = [va; omega] + + @testset "AutoForwardDiff matches AutoFiniteDiff (LOOP, INVISCID)" begin + # `use_gamma_prev=false` is required so that the FD path does not + # warm-start from the previous perturbed state — otherwise the FD + # Jacobian carries a small bias unrelated to the AD result. + solver = Solver(body_aero; use_gamma_prev=false) + + jac_fwd, _, fwd_converged = VortexStepMethod.linearize( + solver, body_aero, y0; + theta_idxs=nothing, va_idxs=1:3, omega_idxs=4:6, + aero_coeffs=true, backend=AutoForwardDiff()) + @test fwd_converged + + jac_fd, _, fd_converged = VortexStepMethod.linearize( + solver, body_aero, y0; + theta_idxs=nothing, va_idxs=1:3, omega_idxs=4:6, + aero_coeffs=true, + backend=AutoFiniteDiff(absstep=1e-5, relstep=1e-5)) + @test fd_converged + + rel_err = maximum(abs.(jac_fwd .- jac_fd)) / maximum(abs, jac_fwd) + @test rel_err < 1e-4 + end + + @testset "NONLIN+ForwardDiff is rejected" begin + solver_nl = Solver(body_aero; solver_type=NONLIN) + @test_throws ErrorException VortexStepMethod.linearize( + solver_nl, body_aero, y0; + theta_idxs=nothing, va_idxs=1:3, omega_idxs=4:6, + aero_coeffs=true, backend=AutoForwardDiff()) + end +end From fd47f8f12172f8b68270e6b7bd2e2c0a65b97254 Mon Sep 17 00:00:00 2001 From: Bart Date: Tue, 5 May 2026 13:31:15 +0200 Subject: [PATCH 2/3] Working example --- examples/linearize_check.jl | 158 ++++++++++++++++---------------- src/panel.jl | 30 +++--- test/solver/test_forwarddiff.jl | 52 +++++++++++ 3 files changed, 146 insertions(+), 94 deletions(-) diff --git a/examples/linearize_check.jl b/examples/linearize_check.jl index d3c49590..7d67862c 100644 --- a/examples/linearize_check.jl +++ b/examples/linearize_check.jl @@ -9,10 +9,10 @@ using LinearAlgebra using VortexStepMethod using VortexStepMethod: linearize, unrefined_deform!, reinit! -# Sweep each linearize input around the operating point and -# overlay the linear prediction from the local `linearize` -# Jacobian. If the tangent (red dashed line) matches the sweep -# slope at δ=0, the FD Jacobian column is correct. +# Sweep each linearize input around the operating point and overlay the +# linear predictions from both FiniteDiff and ForwardDiff Jacobians. If +# the two tangents (red and green dashed) match the sweep slope at δ=0, +# both Jacobian columns agree with the local sensitivity. n_unrefined = 4 @@ -24,11 +24,16 @@ wing = ObjWing( ) body_aero = BodyAerodynamics([wing]) +# LOOP is required for AutoForwardDiff (NONLIN uses LAPACK on Float64 +# and is not Dual-compatible). `use_gamma_prev=false` keeps the FD path +# from warm-starting between perturbations, which would bias the FD +# Jacobian relative to the AD result. solver = Solver(body_aero; aerodynamic_model_type=VSM, is_with_artificial_damping=false, rtol=1e-7, - solver_type=NONLIN, + solver_type=LOOP, + use_gamma_prev=false, ) v_a = 15.0 @@ -48,16 +53,36 @@ va_idxs = (n_unrefined + 1):(n_unrefined + 3) omega_idxs = (n_unrefined + 4):(n_unrefined + 6) y0 = [theta_0; va_b_0; omega_b_0] -@info "Computing linearize Jacobian (NONLIN, AutoFiniteDiff) …" -jac, x0, converged = linearize( - solver, body_aero, y0; - theta_idxs, va_idxs, omega_idxs, - aero_coeffs=true, - backend=AutoFiniteDiff(absstep=1e-4, relstep=1e-4), -) -converged || @warn "linearize did not converge at operating point" +@info "Computing FiniteDiff Jacobian …" +t_fd = @elapsed begin + jac_fd, x0_fd, conv_fd = linearize( + solver, body_aero, y0; + theta_idxs, va_idxs, omega_idxs, + aero_coeffs=true, + backend=AutoFiniteDiff(absstep=1e-5, relstep=1e-5), + ) +end +conv_fd || @warn "FiniteDiff linearize did not converge at operating point" + +@info "Computing ForwardDiff Jacobian …" +t_fwd = @elapsed begin + jac_fwd, x0_fwd, conv_fwd = linearize( + solver, body_aero, y0; + theta_idxs, va_idxs, omega_idxs, + aero_coeffs=true, + backend=AutoForwardDiff(), + ) +end +conv_fwd || @warn "ForwardDiff linearize did not converge at operating point" + +x0 = x0_fd @info "Operating point" CFx=x0[1] CFy=x0[2] CFz=x0[3] CM=x0[4:6] +@info "Timing" t_finitediff_s=t_fd t_forwarddiff_s=t_fwd speedup=t_fd / t_fwd + +denom = max(maximum(abs, jac_fwd), eps()) +rel_err_fwd_fd = maximum(abs.(jac_fwd .- jac_fd)) / denom +@info "AutoForwardDiff vs AutoFiniteDiff" rel_err=rel_err_fwd_fd input_labels = [ ["θ_$i" for i in 1:n_unrefined]..., @@ -72,7 +97,8 @@ output_labels = [ n_inputs = length(input_labels) n_outputs = length(output_labels) -@assert size(jac) == (n_outputs, n_inputs) +@assert size(jac_fd) == (n_outputs, n_inputs) +@assert size(jac_fwd) == (n_outputs, n_inputs) input_scales = [ fill(0.05, n_unrefined)..., # θ [rad] : ±0.05 rad ≈ ±2.9° @@ -118,10 +144,13 @@ end # Restore baseline solve_at!(y0) -fig = Figure(size=(180 * n_inputs + 80, 90 * n_outputs + 80)) +fig = Figure(size=(180 * n_inputs + 80, 90 * n_outputs + 100)) Label(fig[0, 1:n_inputs], - "linearize check: sweeps (blue) vs Jacobian tangent (red dashed)"; - fontsize=18, font=:bold, tellwidth=false) + "linearize check: sweeps (blue) vs FiniteDiff tangent (red dashed) " * + "vs ForwardDiff tangent (green dashed) — " * + "FD: $(round(t_fd; digits=2)) s, FwdDiff: $(round(t_fwd; digits=2)) s, " * + "speedup: $(round(t_fd / t_fwd; digits=2))×"; + fontsize=16, font=:bold, tellwidth=false) for ri in 1:n_outputs for ci in 1:n_inputs @@ -133,16 +162,19 @@ for ri in 1:n_outputs xticksvisible = ri == n_outputs, yticksvisible = ci == 1, ) - delta_input = sweep_frac .* input_scales[ci] - ys_sweep = results_sw[ci][:, ri] - ys_linear = x0[ri] .+ jac[ri, ci] .* delta_input + delta_input = sweep_frac .* input_scales[ci] + ys_sweep = results_sw[ci][:, ri] + ys_linear_fd = x0[ri] .+ jac_fd[ri, ci] .* delta_input + ys_linear_fwd = x0[ri] .+ jac_fwd[ri, ci] .* delta_input lines!(ax, delta_input, ys_sweep; color=:steelblue, linewidth=1.5) - lines!(ax, delta_input, ys_linear; + lines!(ax, delta_input, ys_linear_fd; color=:crimson, linestyle=:dash, linewidth=1.2) + lines!(ax, delta_input, ys_linear_fwd; + color=:seagreen, linestyle=:dash, linewidth=1.2) scatter!(ax, [0.0], [x0[ri]]; - color=:crimson, markersize=6) + color=:black, markersize=6) end end @@ -151,66 +183,32 @@ rowgap!(fig.layout, 4) display(fig) -# Worst-case mismatch between sweep slope at δ=0 and Jacobian -# column (central FD on the sweep). Useful as a numerical check -# in addition to the visual one. -# Skip near-zero Jacobian entries — relative error is dominated by -# FD rounding there and not informative. -sig_threshold = 1e-3 * maximum(abs, jac) -global max_rel_err = 0.0 -global worst = (0, 0, 0.0, 0.0) -for ri in 1:n_outputs, ci in 1:n_inputs - delta = sweep_frac .* input_scales[ci] - mid = div(n_sweep, 2) + 1 - fd = (results_sw[ci][mid + 1, ri] - - results_sw[ci][mid - 1, ri]) / - (delta[mid + 1] - delta[mid - 1]) - jc = jac[ri, ci] - max(abs(jc), abs(fd)) < sig_threshold && continue - rel = abs(fd - jc) / max(abs(jc), abs(fd)) - if rel > max_rel_err - global max_rel_err = rel - global worst = (ri, ci, fd, jc) +# Worst-case mismatch between sweep slope at δ=0 and Jacobian columns, +# reported separately for FD and ForwardDiff. Skip near-zero Jacobian +# entries — relative error is dominated by sweep rounding there and is +# not informative. +function worst_jac_vs_sweep(jac, label) + sig_threshold = 1e-3 * maximum(abs, jac) + max_rel = 0.0 + worst = (0, 0, 0.0, 0.0) + for ri in 1:n_outputs, ci in 1:n_inputs + delta = sweep_frac .* input_scales[ci] + mid = div(n_sweep, 2) + 1 + slope = (results_sw[ci][mid + 1, ri] - + results_sw[ci][mid - 1, ri]) / + (delta[mid + 1] - delta[mid - 1]) + jc = jac[ri, ci] + max(abs(jc), abs(slope)) < sig_threshold && continue + rel = abs(slope - jc) / max(abs(jc), abs(slope)) + if rel > max_rel + max_rel = rel + worst = (ri, ci, slope, jc) + end end + @info "Worst $label vs sweep mismatch (significant entries)" rel=max_rel output=output_labels[worst[1]] input=input_labels[worst[2]] sweep_slope=worst[3] jac_entry=worst[4] sig_threshold end -@info "Worst Jacobian/sweep mismatch (significant entries)" rel=max_rel_err output=output_labels[worst[1]] input=input_labels[worst[2]] sweep_slope=worst[3] jac_entry=worst[4] sig_threshold - -# ── ForwardDiff vs FiniteDiff agreement (LOOP solver) ───────────────────── -# NONLIN doesn't support Duals (LAPACK on Float64), so use LOOP here. -solver_loop = Solver(body_aero; - aerodynamic_model_type = VSM, - is_with_artificial_damping = false, - rtol = 1e-7, - solver_type = LOOP, - use_gamma_prev = false, # required for fair FD comparison -) - -@info "Computing ForwardDiff Jacobian (LOOP) …" -t_fwd = @elapsed begin - jac_fwd, x0_fwd, conv_fwd = linearize( - solver_loop, body_aero, y0; - theta_idxs, va_idxs, omega_idxs, - aero_coeffs = true, - backend = AutoForwardDiff(), - ) -end - -@info "Computing FiniteDiff Jacobian (LOOP) …" -t_fd = @elapsed begin - jac_fd, x0_fd, conv_fd = linearize( - solver_loop, body_aero, y0; - theta_idxs, va_idxs, omega_idxs, - aero_coeffs = true, - backend = AutoFiniteDiff(absstep = 1e-5, relstep = 1e-5), - ) -end - -@assert conv_fwd && conv_fd "linearize did not converge at operating point" -denom = max(maximum(abs, jac_fwd), eps()) -rel_err_fwd_fd = maximum(abs.(jac_fwd .- jac_fd)) / denom -@info "AutoForwardDiff vs AutoFiniteDiff (LOOP)" rel_err = rel_err_fwd_fd -@info "Speed" t_fwd_s = t_fwd t_fd_s = t_fd speedup = t_fd / t_fwd -@assert rel_err_fwd_fd < 1e-4 "ForwardDiff and FiniteDiff Jacobians differ by $rel_err_fwd_fd (>1e-4)" +worst_jac_vs_sweep(jac_fd, "FiniteDiff") +worst_jac_vs_sweep(jac_fwd, "ForwardDiff") nothing diff --git a/src/panel.jl b/src/panel.jl index 3d58db3e..d525b8f8 100644 --- a/src/panel.jl +++ b/src/panel.jl @@ -371,24 +371,25 @@ Calculate lift coefficient for given angle of attack. # Returns - `Float64`: Lift coefficient (Cl) """ -function calculate_cl(panel::Panel, alpha::T)::T where T - isnan(alpha) && return T(NaN) +function calculate_cl(panel::Panel{Tp}, alpha::Ta) where {Tp, Ta} + R = promote_type(Tp, Ta) + isnan(alpha) && return R(NaN) if panel.aero_model == LEI_AIRFOIL_BREUKELS cl = evalpoly(rad2deg(alpha), reverse(panel.cl_coeffs)) if abs(alpha) > (π/9) cl = 2 * cos(alpha) * sin(alpha)^2 end - return cl + return R(cl) elseif panel.aero_model == INVISCID - return 2π * alpha + return R(2π * alpha) elseif panel.aero_model == POLAR_VECTORS interp = panel.cl_interp interp isa Union{I1, I2} || throw(ArgumentError("cl_interp is not initialized for POLAR_VECTORS.")) - return (interp::Union{I1, I2})(alpha)::T + return R((interp::Union{I1, I2})(alpha)) elseif panel.aero_model == POLAR_MATRICES interp = panel.cl_interp interp isa Union{I3, I4} || throw(ArgumentError("cl_interp is not initialized for POLAR_MATRICES.")) - return (interp::Union{I3, I4})(alpha, panel.delta)::T + return R((interp::Union{I3, I4})(alpha, panel.delta)) else throw(ArgumentError("Unsupported aero model: $(panel.aero_model)")) end @@ -400,33 +401,34 @@ end Calculate drag and moment coefficients for given angle of attack. """ -function calculate_cd_cm(panel::Panel, alpha::T)::Tuple{T, T} where T - isnan(alpha) && return T(NaN), T(NaN) +function calculate_cd_cm(panel::Panel{Tp}, alpha::Ta) where {Tp, Ta} + R = promote_type(Tp, Ta) + isnan(alpha) && return R(NaN), R(NaN) if panel.aero_model == LEI_AIRFOIL_BREUKELS cd = evalpoly(rad2deg(alpha), reverse(panel.cd_coeffs)) cm = evalpoly(rad2deg(alpha), reverse(panel.cm_coeffs)) if abs(alpha) > (π/9) # Outside ±20 degrees cd = 2 * sin(alpha)^3 end - return cd, cm + return R(cd), R(cm) elseif panel.aero_model == POLAR_VECTORS cd_interp = panel.cd_interp cm_interp = panel.cm_interp cd_interp isa Union{I1, I2, I5} || throw(ArgumentError("cd_interp is not initialized for POLAR_VECTORS.")) cm_interp isa Union{I1, I2} || throw(ArgumentError("cm_interp is not initialized for POLAR_VECTORS.")) - return (cd_interp::Union{I1, I2, I5})(alpha)::T, - (cm_interp::Union{I1, I2})(alpha)::T + return R((cd_interp::Union{I1, I2, I5})(alpha)), + R((cm_interp::Union{I1, I2})(alpha)) elseif panel.aero_model == POLAR_MATRICES cd_interp = panel.cd_interp cm_interp = panel.cm_interp cd_interp isa Union{I3, I4, I6} || throw(ArgumentError("cd_interp is not initialized for POLAR_MATRICES.")) cm_interp isa Union{I3, I4} || throw(ArgumentError("cm_interp is not initialized for POLAR_MATRICES.")) - return (cd_interp::Union{I3, I4, I6})(alpha, panel.delta)::T, - (cm_interp::Union{I3, I4})(alpha, panel.delta)::T + return R((cd_interp::Union{I3, I4, I6})(alpha, panel.delta)), + R((cm_interp::Union{I3, I4})(alpha, panel.delta)) elseif !(panel.aero_model == INVISCID) throw(ArgumentError("Unsupported aero model: $(panel.aero_model)")) end - return zero(T), zero(T) + return zero(R), zero(R) end """ diff --git a/test/solver/test_forwarddiff.jl b/test/solver/test_forwarddiff.jl index c351fe5c..961119f2 100644 --- a/test/solver/test_forwarddiff.jl +++ b/test/solver/test_forwarddiff.jl @@ -51,4 +51,56 @@ using Test theta_idxs=nothing, va_idxs=1:3, omega_idxs=4:6, aero_coeffs=true, backend=AutoForwardDiff()) end + + @testset "AutoForwardDiff matches AutoFiniteDiff (LOOP, POLAR_MATRICES)" begin + # The ram-air-kite ObjWing exercises POLAR_MATRICES, which is the + # branch where calculate_cl(panel::Panel{Tp}, alpha::Ta) sees mixed + # eltypes (alpha=Float64 from calculate_stall_angle_list!, + # panel.delta=Dual from the shadow). INVISCID never hits this path. + data_dir = joinpath(dirname(dirname(@__DIR__)), "data", "ram_air_kite") + body_path = joinpath(tempdir(), "ram_air_kite_body.obj") + foil_path = joinpath(tempdir(), "ram_air_kite_foil.dat") + cp(joinpath(data_dir, "ram_air_kite_body.obj"), body_path; force=true) + cp(joinpath(data_dir, "ram_air_kite_foil.dat"), foil_path; force=true) + for kind in ("cl", "cd", "cm") + name = "ram_air_kite_foil_$(kind)_polar.csv" + cp(joinpath(data_dir, name), joinpath(tempdir(), name); force=true) + end + + ram_wing = ObjWing(body_path, foil_path; + alpha_range=deg2rad.(-5:1:15), + delta_range=deg2rad.(-3:1:5), + n_unrefined_sections=4, + ) + ram_body = BodyAerodynamics([ram_wing]) + ram_solver = Solver(ram_body; + aerodynamic_model_type=VSM, + is_with_artificial_damping=false, + rtol=1e-7, + solver_type=LOOP, + use_gamma_prev=false, + ) + + v_a = 15.0 + aoa_rad = deg2rad(8.0) + y_op = [zeros(4); + [cos(aoa_rad), 0.0, sin(aoa_rad)] * v_a; + zeros(3)] + + jac_fwd, _, conv_fwd = VortexStepMethod.linearize( + ram_solver, ram_body, y_op; + theta_idxs=1:4, va_idxs=5:7, omega_idxs=8:10, + aero_coeffs=true, backend=AutoForwardDiff()) + @test conv_fwd + + jac_fd, _, conv_fd = VortexStepMethod.linearize( + ram_solver, ram_body, y_op; + theta_idxs=1:4, va_idxs=5:7, omega_idxs=8:10, + aero_coeffs=true, + backend=AutoFiniteDiff(absstep=1e-5, relstep=1e-5)) + @test conv_fd + + rel_err = maximum(abs.(jac_fwd .- jac_fd)) / maximum(abs, jac_fwd) + @test rel_err < 1e-3 + end end From aca7cfc32a0064b3265d8bbda50da138285c1301 Mon Sep 17 00:00:00 2001 From: Bart Date: Tue, 5 May 2026 16:02:05 +0200 Subject: [PATCH 3/3] Prune comments --- examples/linearize_check.jl | 15 +--- src/panel.jl | 1 - src/solver.jl | 128 ++++++-------------------------- test/solver/test_forwarddiff.jl | 12 +-- 4 files changed, 28 insertions(+), 128 deletions(-) diff --git a/examples/linearize_check.jl b/examples/linearize_check.jl index 7d67862c..57023755 100644 --- a/examples/linearize_check.jl +++ b/examples/linearize_check.jl @@ -10,9 +10,7 @@ using VortexStepMethod using VortexStepMethod: linearize, unrefined_deform!, reinit! # Sweep each linearize input around the operating point and overlay the -# linear predictions from both FiniteDiff and ForwardDiff Jacobians. If -# the two tangents (red and green dashed) match the sweep slope at δ=0, -# both Jacobian columns agree with the local sensitivity. +# FiniteDiff and ForwardDiff tangents on the sweep curve. n_unrefined = 4 @@ -24,10 +22,6 @@ wing = ObjWing( ) body_aero = BodyAerodynamics([wing]) -# LOOP is required for AutoForwardDiff (NONLIN uses LAPACK on Float64 -# and is not Dual-compatible). `use_gamma_prev=false` keeps the FD path -# from warm-starting between perturbations, which would bias the FD -# Jacobian relative to the AD result. solver = Solver(body_aero; aerodynamic_model_type=VSM, is_with_artificial_damping=false, @@ -108,7 +102,6 @@ input_scales = [ n_sweep = 11 sweep_frac = range(-1.0, 1.0; length=n_sweep) -# results[col][si, ri] results_sw = [zeros(n_sweep, n_outputs) for _ in 1:n_inputs] last_theta = fill(NaN, n_unrefined) @@ -141,7 +134,6 @@ for ci in 1:n_inputs end end -# Restore baseline solve_at!(y0) fig = Figure(size=(180 * n_inputs + 80, 90 * n_outputs + 100)) @@ -183,10 +175,7 @@ rowgap!(fig.layout, 4) display(fig) -# Worst-case mismatch between sweep slope at δ=0 and Jacobian columns, -# reported separately for FD and ForwardDiff. Skip near-zero Jacobian -# entries — relative error is dominated by sweep rounding there and is -# not informative. +# Skip near-zero entries — relative error there is sweep rounding noise. function worst_jac_vs_sweep(jac, label) sig_threshold = 1e-3 * maximum(abs, jac) max_rel = 0.0 diff --git a/src/panel.jl b/src/panel.jl index d525b8f8..0a2e6f94 100644 --- a/src/panel.jl +++ b/src/panel.jl @@ -52,7 +52,6 @@ Represents a panel in a vortex step method simulation. All points and vectors ar va::MVector{3, T} = zeros(MVector{3, T}) corner_points::MMatrix{3, 4, T, 12} = zeros(MMatrix{3, 4, T, 12}) aero_model::AeroModel = INVISCID - # Polar / Breukels coefficients are static lookup-table data — kept Float64 cl_coeffs::Vector{Float64} = zeros(Float64, 3) cd_coeffs::Vector{Float64} = zeros(Float64, 3) cm_coeffs::Vector{Float64} = zeros(Float64, 3) diff --git a/src/solver.jl b/src/solver.jl index 5ad135b1..eff11eaf 100644 --- a/src/solver.jl +++ b/src/solver.jl @@ -993,71 +993,6 @@ function smooth_circulation!( return true end -""" - linearize(solver::Solver, body_aero::BodyAerodynamics, y::Vector{T}; - theta_idxs=1:4, delta_idxs=nothing, va_idxs=nothing, omega_idxs=nothing, - aero_coeffs=false, kwargs...) where T - -Compute Jacobian matrix of aerodynamic outputs with respect to control and kinematic inputs using -finite differences. Used for control system design and linear stability analysis. - -The function uses automatic differentiation with finite differences to compute ∂outputs/∂inputs. -Deformations are applied to the wing's unrefined sections (the original sections before mesh -refinement), with each control angle affecting one unrefined section. - -# Arguments -- `solver::Solver`: Solver instance (must be configured for the wing) -- `body_aero::BodyAerodynamics`: Body aerodynamics with exactly one wing -- `y::Vector{T}`: Input vector at operating point containing control angles and/or kinematic states - -# Keyword Arguments -- `theta_idxs`: Indices in `y` for twist angles (one per unrefined section, default: 1:4) -- `delta_idxs`: Indices in `y` for trailing edge deflections (one per unrefined section, default: nothing) -- `va_idxs`: Indices in `y` for apparent wind velocity components `(vx, vy, vz)` (default: nothing) -- `omega_idxs`: Indices in `y` for angular velocity components `(ωx, ωy, ωz)` (default: nothing) -- `aero_coeffs::Bool`: Return force/moment coefficients instead of dimensional values (default: false) -- `kwargs...`: Additional arguments passed to `solve!` - -# Index Validation -The lengths of `theta_idxs` and `delta_idxs` (if provided) must match `wing.n_unrefined_sections`. -Unrefined sections are the original wing sections before mesh refinement for aerodynamic analysis. - -# Caching -The function caches previous deformation angles to avoid redundant `unrefined_deform!` calls during -Jacobian computation. When the same angles are encountered, geometry deformation is skipped. - -# Returns -- `jac::Matrix{Float64}`: Jacobian matrix (m×n) where m = 6 + n_unrefined_sections, n = length(y) -- `results::Vector{Float64}`: Output vector at operating point - - If `aero_coeffs=false`: `(Fx, Fy, Fz, Mx, My, Mz, moment_unrefined_dist...)` - - If `aero_coeffs=true`: `(CFx, CFy, CFz, CMx, CMy, CMz, cm_unrefined_dist...)` -- `converged::Bool`: `true` iff every internal solve reached the solver's - tolerances. When `false`, a warning is also emitted and the corresponding - Jacobian columns may be unreliable. - -# Example -```julia -# Create deformable wing with 4 unrefined sections -wing = ObjWing("kite.obj", "airfoil.dat"; n_unrefined_sections=4) -body_aero = BodyAerodynamics([wing], va=[15.0, 0, 0]) -solver = Solver(body_aero) - -# Operating point: 4 twist angles + velocity + angular rates -y_op = [zeros(4); # theta angles [rad] - [15.0, 0.0, 0.0]; # va [m/s] - zeros(3)] # omega [rad/s] - -# Compute Jacobian -jac, results, converged = linearize(solver, body_aero, y_op; - theta_idxs=1:4, - va_idxs=5:7, - omega_idxs=8:10, - aero_coeffs=true -) - -# jac is (10×10): [6 force/moment coeffs + 4 unrefined moment coeffs] × [4 theta + 3 va + 3 omega] -``` -""" function _section_with_eltype(section::Section, ::Type{TD}) where TD return Section{TD}( MVector{3, TD}(section.LE_point), @@ -1126,8 +1061,6 @@ function make_dual_shadow(solver::Solver{P, U, Float64}, is_with_artificial_damping = solver.is_with_artificial_damping, artificial_damping = solver.artificial_damping, type_initial_gamma_distribution = solver.type_initial_gamma_distribution, - # Forced off: warm-starting with Duals from a prior chunk would leak - # stale gradient information into the next column of the Jacobian. use_gamma_prev = false, core_radius_fraction = TD(solver.core_radius_fraction), mu = TD(solver.mu), @@ -1138,6 +1071,24 @@ function make_dual_shadow(solver::Solver{P, U, Float64}, return body_aero_d, solver_d end +""" + linearize(solver, body_aero, y; theta_idxs=1:4, delta_idxs=nothing, + va_idxs=nothing, omega_idxs=nothing, aero_coeffs=false, + backend=AutoForwardDiff(), kwargs...) + +Jacobian of aerodynamic outputs w.r.t. control and kinematic inputs at `y`. Each `*_idxs` +selects which entries of `y` map to twist angles (one per unrefined section), trailing-edge +deflections (one per unrefined section), apparent wind `(vx, vy, vz)`, and angular rate +`(ωx, ωy, ωz)` respectively. + +`backend` accepts any `DifferentiationInterface` backend; `AutoForwardDiff()` (the default) +requires `solver_type=LOOP`. `fd_absstep`/`fd_relstep` are forwarded only when the backend is +`AutoFiniteDiff`. + +Returns `(jac, results, converged)` where `results` is `(F, M, moment_unrefined_dist...)` — +or the corresponding coefficients when `aero_coeffs=true` — and `converged` is `false` (with a +warning) if any internal solve missed the solver's tolerances. +""" function linearize(solver::Solver, body_aero::BodyAerodynamics, y::Vector{T}; theta_idxs=1:4, delta_idxs=nothing, @@ -1166,11 +1117,7 @@ function linearize(solver::Solver, body_aero::BodyAerodynamics, y::Vector{T}; end n_failed = Ref(0) - # Lazily-built Dual shadow keyed by element type; rebuilt only when - # eltype changes (e.g. across DI/ForwardDiff tag transitions). shadow_ref = Ref{Any}(nothing) - last_theta_ref = Ref{Any}(nothing) - last_delta_ref = Ref{Any}(nothing) function calc_results!(results, y_in) TI = eltype(y_in) @@ -1180,48 +1127,19 @@ function linearize(solver::Solver, body_aero::BodyAerodynamics, y::Vector{T}; wing_c = wing else shadow = shadow_ref[] - need_new = shadow === nothing || - eltype(shadow[1]._va) !== TI - if need_new + if shadow === nothing || eltype(shadow[1]._va) !== TI shadow_ref[] = make_dual_shadow(solver, body_aero, TI) end body_aero_c, solver_c = shadow_ref[] wing_c = body_aero_c.wings[1] end - if !isnothing(theta_idxs) && - (last_theta_ref[] === nothing || eltype(last_theta_ref[]) !== TI) - last_theta_ref[] = fill(TI(NaN), length(theta_idxs)) - end - if !isnothing(delta_idxs) && - (last_delta_ref[] === nothing || eltype(last_delta_ref[]) !== TI) - last_delta_ref[] = fill(TI(NaN), length(delta_idxs)) - end - @views theta_angles = isnothing(theta_idxs) ? nothing : y_in[theta_idxs] @views delta_angles = isnothing(delta_idxs) ? nothing : y_in[delta_idxs] - last_theta = last_theta_ref[] - last_delta = last_delta_ref[] - - if !isnothing(theta_angles) && isnothing(delta_angles) - if !all(theta_angles .== last_theta) - VortexStepMethod.unrefined_deform!(wing_c, theta_angles, nothing; smooth=false) - VortexStepMethod.reinit!(body_aero_c; init_aero=false) - last_theta .= theta_angles - end - elseif !isnothing(theta_angles) && !isnothing(delta_angles) - if !all(delta_angles .== last_delta) || !all(theta_angles .== last_theta) - VortexStepMethod.unrefined_deform!(wing_c, theta_angles, delta_angles; smooth=false) - VortexStepMethod.reinit!(body_aero_c; init_aero=false) - last_theta .= theta_angles - last_delta .= delta_angles - end - elseif isnothing(theta_angles) && !isnothing(delta_angles) - if !all(delta_angles .== last_delta) - VortexStepMethod.unrefined_deform!(wing_c, nothing, delta_angles; smooth=false) - VortexStepMethod.reinit!(body_aero_c; init_aero=false) - last_delta .= delta_angles - end + + if !isnothing(theta_angles) || !isnothing(delta_angles) + VortexStepMethod.unrefined_deform!(wing_c, theta_angles, delta_angles; smooth=false) + VortexStepMethod.reinit!(body_aero_c; init_aero=false) end va = isnothing(va_idxs) ? MVector{3, TI}(body_aero_c._va) : y_in[va_idxs] diff --git a/test/solver/test_forwarddiff.jl b/test/solver/test_forwarddiff.jl index 961119f2..b3a3a9b5 100644 --- a/test/solver/test_forwarddiff.jl +++ b/test/solver/test_forwarddiff.jl @@ -4,8 +4,6 @@ using LinearAlgebra using Test @testset "ForwardDiff linearize" begin - # Build a small rectangular wing with INVISCID polars so the test runs - # quickly and the comparison is dominated by the LOOP iteration itself. n_panels = 10 span = 20.0 chord = 1.0 @@ -22,9 +20,7 @@ using Test y0 = [va; omega] @testset "AutoForwardDiff matches AutoFiniteDiff (LOOP, INVISCID)" begin - # `use_gamma_prev=false` is required so that the FD path does not - # warm-start from the previous perturbed state — otherwise the FD - # Jacobian carries a small bias unrelated to the AD result. + # FD warm-starts otherwise bias the reference Jacobian. solver = Solver(body_aero; use_gamma_prev=false) jac_fwd, _, fwd_converged = VortexStepMethod.linearize( @@ -53,10 +49,8 @@ using Test end @testset "AutoForwardDiff matches AutoFiniteDiff (LOOP, POLAR_MATRICES)" begin - # The ram-air-kite ObjWing exercises POLAR_MATRICES, which is the - # branch where calculate_cl(panel::Panel{Tp}, alpha::Ta) sees mixed - # eltypes (alpha=Float64 from calculate_stall_angle_list!, - # panel.delta=Dual from the shadow). INVISCID never hits this path. + # Exercises the mixed-eltype path: calculate_stall_angle_list! calls + # calculate_cl with Float64 alpha against Dual-typed panels. data_dir = joinpath(dirname(dirname(@__DIR__)), "data", "ram_air_kite") body_path = joinpath(tempdir(), "ram_air_kite_body.obj") foil_path = joinpath(tempdir(), "ram_air_kite_foil.dat")