src/gray_core.f90: implement adaptive step control
This implements a method to control the integrator step size based on the integration error and resonance conditions. The main advantages are that: - the ray trajectories have a bounded error; - the initial step size can be large as to quickly traverse the vacuum; - the results no longer depend on the choice of the step size. The error is estimated from the real part of the dispersion relation Λ(x̅, N̅), which if solved exactly should be zero. The error bound is set to a strict value when crossing the plasma boundary to ensure a correct coupling and is relaxed afterwards. Finally, when the ray is approaching a resonance the controller ensures the step size is small compared to the absorption profile.
This commit is contained in:
parent
c9c20198a7
commit
92b3ad9bd3
@ -34,6 +34,11 @@ idst = 0
|
|||||||
; 4: 4-stage Runge-Kutta (4⁰ order)
|
; 4: 4-stage Runge-Kutta (4⁰ order)
|
||||||
integrator = 4
|
integrator = 4
|
||||||
|
|
||||||
|
; Whether to automatically adjust the integration step
|
||||||
|
; size based on the local error. If true `dst` will set
|
||||||
|
; the initial step size.
|
||||||
|
adaptive_step = false
|
||||||
|
|
||||||
|
|
||||||
[ecrh_cd]
|
[ecrh_cd]
|
||||||
; Choice of the power absorption model
|
; Choice of the power absorption model
|
||||||
|
@ -22,12 +22,16 @@ module dispersion
|
|||||||
real(wp_), parameter :: tmax = 5.0_wp_
|
real(wp_), parameter :: tmax = 5.0_wp_
|
||||||
real(wp_), parameter :: dtex = 2*tmax/dble(npts)
|
real(wp_), parameter :: dtex = 2*tmax/dble(npts)
|
||||||
|
|
||||||
|
! Maximum value for the argument of the electron distribution,
|
||||||
|
! μ⋅(γ-1), above which the function is considered to be 0.
|
||||||
|
real(wp_), parameter :: expcr = 16.0_wp_
|
||||||
|
|
||||||
! global variables
|
! global variables
|
||||||
real(wp_), dimension(npts+1), save :: ttv, extv
|
real(wp_), dimension(npts+1), save :: ttv, extv
|
||||||
|
|
||||||
private
|
private
|
||||||
public expinit, colddisp, warmdisp
|
public expinit, colddisp, warmdisp
|
||||||
public zetac, harmnumber
|
public zetac, harmnumber, resonance_width
|
||||||
|
|
||||||
contains
|
contains
|
||||||
|
|
||||||
@ -131,10 +135,6 @@ pure subroutine harmnumber(Y, mu, Npl2, weakly, nhmin, nhmax)
|
|||||||
|
|
||||||
! local constants
|
! local constants
|
||||||
|
|
||||||
! Maximum value for μ⋅(γ-1) above which the
|
|
||||||
! distribution function is considered to be 0.
|
|
||||||
real(wp_), parameter :: expcr = 16.0_wp_
|
|
||||||
|
|
||||||
nhmin = 0
|
nhmin = 0
|
||||||
nhmax = 0
|
nhmax = 0
|
||||||
|
|
||||||
@ -218,6 +218,79 @@ pure subroutine harmnumber(Y, mu, Npl2, weakly, nhmin, nhmax)
|
|||||||
end subroutine harmnumber
|
end subroutine harmnumber
|
||||||
|
|
||||||
|
|
||||||
|
function resonance_width(Y, mu, Npl2, R)
|
||||||
|
! Estimates the width, as the extent in major radius, of the
|
||||||
|
! resonating plasma layer at the smallest possible harmonic
|
||||||
|
!
|
||||||
|
! This computes, following the same logic of `harmnumber`, the
|
||||||
|
! smallest possible harmonic, then estimates the width as the
|
||||||
|
! value ΔR of major radius that causes a change Δγ ≈ dγ/dR ΔR
|
||||||
|
! in the argument of the electron distribution equals to 1/μ.
|
||||||
|
implicit none
|
||||||
|
|
||||||
|
! subroutine arguments
|
||||||
|
|
||||||
|
! CMA Y variable: Y=ω_c/ω
|
||||||
|
real(wp_), intent(in) :: Y
|
||||||
|
! squared parallel refractive index: N∥²=N²cos²θ
|
||||||
|
real(wp_), intent(in) :: Npl2
|
||||||
|
! reciprocal of adimensional temperature: μ=mc²/kT
|
||||||
|
real(wp_), intent(in) :: mu
|
||||||
|
! major radius R=√(x² + y²)
|
||||||
|
real(wp_), intent(in) :: R
|
||||||
|
! width of the resonance
|
||||||
|
real(wp_) :: resonance_width
|
||||||
|
|
||||||
|
! local variables
|
||||||
|
integer :: nh, nhc, nhmin
|
||||||
|
real(wp_) :: Yc, Yn, gamma, rdu2, argexp
|
||||||
|
|
||||||
|
! Derivatives of the argument A ≡ μ⋅γ(Y, N∥, n)
|
||||||
|
real(wp_) :: dAdR, dAdY
|
||||||
|
|
||||||
|
! local constants
|
||||||
|
|
||||||
|
nhmin = 0 ! Minimum harmonic number
|
||||||
|
resonance_width = 0 ! The result, ΔR
|
||||||
|
|
||||||
|
Yc = sqrt(max(1 - npl2, zero)) ! Critical Y value
|
||||||
|
nhc = ceiling(Yc/Y) ! Critical harmonic number
|
||||||
|
|
||||||
|
! Check a few numbers starting with nhc
|
||||||
|
do nh = nhc, nhc + 10
|
||||||
|
Yn = Y*nh
|
||||||
|
|
||||||
|
! γ = [Yn - √(N∥²(Yn²-Yc²))]/Yc²
|
||||||
|
rdu2 = Yn**2 - Yc**2
|
||||||
|
gamma = (Yn - sqrt(Npl2*rdu2))/(1 - Npl2)
|
||||||
|
argexp = mu*(gamma - one)
|
||||||
|
|
||||||
|
if (argexp <= expcr) then
|
||||||
|
! The are enough electrons with this energy
|
||||||
|
nhmin = nh
|
||||||
|
exit
|
||||||
|
end if
|
||||||
|
end do
|
||||||
|
|
||||||
|
! No harmonics possible
|
||||||
|
if (nhmin == 0) return
|
||||||
|
|
||||||
|
! The derivative of the minimum γ = γ(N∥, Y, n) is
|
||||||
|
!
|
||||||
|
! dγ/dY = n (Yn - γ)/(Yn - γ⋅Yc²)
|
||||||
|
!
|
||||||
|
dAdY = mu * nhmin * (Yn - gamma)/(Yn - gamma*Yc**2)
|
||||||
|
|
||||||
|
! dAdR = dAdY⋅dY/dR, assuming the magnetic field varies
|
||||||
|
! solely as B(R) ≈ B₀⋅R₀/R, then dY/dR = -Y/R
|
||||||
|
dAdR = dAdY * (-Y/R)
|
||||||
|
|
||||||
|
! Take ΔR = |ΔA / A/dR|, where ΔA = μΔγ = 1
|
||||||
|
resonance_width = 1 / abs(dAdR)
|
||||||
|
|
||||||
|
end function resonance_width
|
||||||
|
|
||||||
|
|
||||||
subroutine warmdisp(X, Y, mu, Npl, Npr_cold, sox, &
|
subroutine warmdisp(X, Y, mu, Npl, Npr_cold, sox, &
|
||||||
error, Npr, e, &
|
error, Npr, e, &
|
||||||
model, nlarmor, max_iters, fallback)
|
model, nlarmor, max_iters, fallback)
|
||||||
|
@ -6,11 +6,13 @@ module gray_core
|
|||||||
implicit none
|
implicit none
|
||||||
|
|
||||||
abstract interface
|
abstract interface
|
||||||
function rhs_function(y) result(f)
|
function rhs_function(y, e) result(f)
|
||||||
! Function passed to the integrator subroutine
|
! Function passed to the integrator subroutine
|
||||||
|
! This represent the right-hand side of the ODE: dy/ds = f(y)
|
||||||
use const_and_precisions, only : wp_
|
use const_and_precisions, only : wp_
|
||||||
real(wp_), intent(in) :: y(6)
|
real(wp_), intent(in) :: y(6) ! variable y
|
||||||
real(wp_) :: f(6)
|
real(wp_), intent(inout), optional :: e ! error estimator
|
||||||
|
real(wp_) :: f(6) ! f(y)
|
||||||
end function
|
end function
|
||||||
end interface
|
end interface
|
||||||
|
|
||||||
@ -85,7 +87,7 @@ contains
|
|||||||
real(wp_), dimension(:), pointer :: p0jk=>null()
|
real(wp_), dimension(:), pointer :: p0jk=>null()
|
||||||
real(wp_), dimension(:), pointer :: jphi_beam=>null(),pins_beam=>null(), &
|
real(wp_), dimension(:), pointer :: jphi_beam=>null(),pins_beam=>null(), &
|
||||||
currins_beam=>null(), dpdv_beam=>null(),jcd_beam=>null(),stv=>null(), &
|
currins_beam=>null(), dpdv_beam=>null(),jcd_beam=>null(),stv=>null(), &
|
||||||
psipv=>null(),chipv=>null()
|
psipv=>null(),chipv=>null(),dst=>null()
|
||||||
complex(wp_), dimension(:), pointer :: ext=>null(), eyt=>null()
|
complex(wp_), dimension(:), pointer :: ext=>null(), eyt=>null()
|
||||||
integer, dimension(:), pointer :: iiv=>null(),iop=>null(),iow=>null()
|
integer, dimension(:), pointer :: iiv=>null(),iop=>null(),iow=>null()
|
||||||
logical, dimension(:), pointer :: iwait=>null()
|
logical, dimension(:), pointer :: iwait=>null()
|
||||||
@ -119,13 +121,11 @@ contains
|
|||||||
call pec_init(params%output%ipec, rhout)
|
call pec_init(params%output%ipec, rhout)
|
||||||
nnd = size(rhop_tab) ! number of radial profile points
|
nnd = size(rhop_tab) ! number of radial profile points
|
||||||
|
|
||||||
call alloc_multipass(nnd, iwait, iroff, iop, iow, yynext, yypnext, yw0, ypw0, stnext, &
|
! Initialise multipass module
|
||||||
stv, p0ray, taus, tau1, etau1, cpls, cpl1, lgcpl1, jphi_beam, &
|
call alloc_multipass(nnd, iwait, iroff, iop, iow, yynext, yypnext, &
|
||||||
pins_beam, currins_beam, dpdv_beam, jcd_beam, psipv, chipv)
|
yw0, ypw0, stnext, stv, dst, p0ray, taus, tau1, &
|
||||||
|
etau1, cpls, cpl1, lgcpl1, jphi_beam, pins_beam, &
|
||||||
! Allocate memory for the results...
|
currins_beam, dpdv_beam, jcd_beam, psipv, chipv)
|
||||||
allocate(results%dpdv(params%output%nrho))
|
|
||||||
allocate(results%jcd(params%output%nrho))
|
|
||||||
|
|
||||||
! ...and initialise them
|
! ...and initialise them
|
||||||
results%pabs = zero
|
results%pabs = zero
|
||||||
@ -208,8 +208,8 @@ contains
|
|||||||
index_rt = index_rt +1
|
index_rt = index_rt +1
|
||||||
iO = 2*index_rt +1 ! * index_rt of O-mode derived ray (iX=iO+1)
|
iO = 2*index_rt +1 ! * index_rt of O-mode derived ray (iX=iO+1)
|
||||||
|
|
||||||
call initbeam(index_rt,iroff,iboff,iwait,stv,jphi_beam, &
|
call initbeam(params, index_rt, iroff, iboff, iwait, stv, dst, &
|
||||||
pins_beam,currins_beam,dpdv_beam,jcd_beam)
|
jphi_beam, pins_beam, currins_beam, dpdv_beam, jcd_beam)
|
||||||
|
|
||||||
write(msg, '(" beam: ",g0," (",a1," mode)")') index_rt, mode(iox)
|
write(msg, '(" beam: ",g0," (",a1," mode)")') index_rt, mode(iox)
|
||||||
call log_info(msg, mod='gray_core', proc='gray_main')
|
call log_info(msg, mod='gray_core', proc='gray_main')
|
||||||
@ -273,10 +273,11 @@ contains
|
|||||||
! advance one step with "frozen" grad(S_I)
|
! advance one step with "frozen" grad(S_I)
|
||||||
do jk=1,params%raytracing%nray
|
do jk=1,params%raytracing%nray
|
||||||
if(iwait(jk)) cycle ! jk ray is waiting for next pass
|
if(iwait(jk)) cycle ! jk ray is waiting for next pass
|
||||||
stv(jk) = stv(jk) + params%raytracing%dst ! current ray step
|
call step_controller( &
|
||||||
call integrator(yw(:, jk), ypw(:, jk), rhs, &
|
y=yw(:, jk), yp=ypw(:, jk), f=rhs, &
|
||||||
params%raytracing%dst, &
|
h=dst(jk), method=params%raytracing%integrator, &
|
||||||
params%raytracing%integrator)
|
adaptive=params%raytracing%adaptive_step, Bres=Bres)
|
||||||
|
stv(jk) = stv(jk) + dst(jk) ! current ray step
|
||||||
end do
|
end do
|
||||||
! update position and grad
|
! update position and grad
|
||||||
if(igrad_b == 1) call gradi_upd(yw,ak0,xc,du1,gri,ggri)
|
if(igrad_b == 1) call gradi_upd(yw,ak0,xc,du1,gri,ggri)
|
||||||
@ -346,7 +347,7 @@ contains
|
|||||||
if(ip < params%raytracing%ipass) then ! + not last pass
|
if(ip < params%raytracing%ipass) then ! + not last pass
|
||||||
yynext(:,jk,index_rt) = yw0(:,jk) ! . copy starting coordinates
|
yynext(:,jk,index_rt) = yw0(:,jk) ! . copy starting coordinates
|
||||||
yypnext(:,jk,index_rt) = ypw0(:,jk) ! for next pass from last step
|
yypnext(:,jk,index_rt) = ypw0(:,jk) ! for next pass from last step
|
||||||
stnext(jk,index_rt) = stv(jk) - params%raytracing%dst ! . starting step for next pass = last step
|
stnext(jk,index_rt) = stv(jk) - dst(jk) ! . starting step for next pass = last step
|
||||||
|
|
||||||
if(cpl(1) < etaucr) then ! . low coupled power for O-mode => de-activate derived rays
|
if(cpl(1) < etaucr) then ! . low coupled power for O-mode => de-activate derived rays
|
||||||
call turnoffray(jk,ip+1,2*ib-1,iroff)
|
call turnoffray(jk,ip+1,2*ib-1,iroff)
|
||||||
@ -468,15 +469,15 @@ contains
|
|||||||
|
|
||||||
! Computation of the ray τ, dP/ds, P(s), dI/ds, I(s)
|
! Computation of the ray τ, dP/ds, P(s), dI/ds, I(s)
|
||||||
|
|
||||||
! optical depth: τ = ∫α(s)ds using the trapezoid rule
|
! optical depth: τ = ∫α(s)ds using the trapezoidal rule
|
||||||
tau = tau0(jk) + 0.5_wp_*(alphaabs0(jk) + alpha) * dersdst * params%raytracing%dst
|
tau = tau0(jk) + 0.5_wp_*(alphaabs0(jk) + alpha) * dersdst * dst(jk)
|
||||||
|
|
||||||
pow = p0ray(jk) * exp(-tau) ! residual power: P = P₀exp(-τ)
|
pow = p0ray(jk) * exp(-tau) ! residual power: P = P₀exp(-τ)
|
||||||
ppabs(jk,i) = p0ray(jk) - pow ! absorbed power: P_abs = P₀ - P
|
ppabs(jk,i) = p0ray(jk) - pow ! absorbed power: P_abs = P₀ - P
|
||||||
dids = didp * pow * alpha ! current driven: dI/ds = dI/dP⋅dP/ds = dI/dP⋅P⋅α
|
dids = didp * pow * alpha ! current driven: dI/ds = dI/dP⋅dP/ds = dI/dP⋅P⋅α
|
||||||
|
|
||||||
! current: I = ∫dI/ds⋅ds using the trapezoid rule
|
! current: I = ∫dI/ds⋅ds using the trapezoidal rule
|
||||||
ccci(jk,i) = ccci0(jk) + 0.5_wp_*(dids0(jk) + dids) * dersdst * params%raytracing%dst
|
ccci(jk,i) = ccci0(jk) + 0.5_wp_*(dids0(jk) + dids) * dersdst * dst(jk)
|
||||||
|
|
||||||
tau0(jk) = tau
|
tau0(jk) = tau
|
||||||
alphaabs0(jk) = alpha
|
alphaabs0(jk) = alpha
|
||||||
@ -621,7 +622,7 @@ contains
|
|||||||
alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv)
|
alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv)
|
||||||
call dealloc_pec
|
call dealloc_pec
|
||||||
call dealloc_multipass(iwait,iroff,iop,iow,yynext,yypnext,yw0,ypw0, &
|
call dealloc_multipass(iwait,iroff,iop,iow,yynext,yypnext,yw0,ypw0, &
|
||||||
stnext,stv,p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,jphi_beam, &
|
stnext,stv,dst,p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,jphi_beam, &
|
||||||
pins_beam,currins_beam,dpdv_beam,jcd_beam,psipv,chipv)
|
pins_beam,currins_beam,dpdv_beam,jcd_beam,psipv,chipv)
|
||||||
! =========== free memory END ===========
|
! =========== free memory END ===========
|
||||||
|
|
||||||
@ -629,15 +630,16 @@ contains
|
|||||||
|
|
||||||
! Functions that needs the scope of gray_main
|
! Functions that needs the scope of gray_main
|
||||||
|
|
||||||
function rhs(y) result(dery)
|
function rhs(y, e) result(f)
|
||||||
! Computes the right-hand-side terms of the ray equations
|
! Computes the right-hand side terms of the ray equations
|
||||||
! To be passed to the integrator subroutine
|
! To be passed to the integrator subroutine
|
||||||
implicit none
|
implicit none
|
||||||
|
|
||||||
! function arguments
|
! function arguments
|
||||||
real(wp_), dimension(6), intent(in) :: y ! (x̅, N̅)
|
real(wp_), intent(in) :: y(6) ! (x̅, N̅)
|
||||||
|
real(wp_), intent(inout), optional :: e ! |Λ(x̅, N̅)| as an error
|
||||||
! result
|
! result
|
||||||
real(wp_), dimension(6) :: dery
|
real(wp_) :: f(6) ! (dx̅/ds, dN̅/ds)
|
||||||
|
|
||||||
! local variables
|
! local variables
|
||||||
real(wp_) :: xg, yg
|
real(wp_) :: xg, yg
|
||||||
@ -654,7 +656,14 @@ contains
|
|||||||
|
|
||||||
! computes derivatives of dispersion relation: ∂Λ/∂x̅, ∂Λ/∂N̅
|
! computes derivatives of dispersion relation: ∂Λ/∂x̅, ∂Λ/∂N̅
|
||||||
call disp_deriv(anv, sox, xg, yg, derxg, deryg, bv, derbv, &
|
call disp_deriv(anv, sox, xg, yg, derxg, deryg, bv, derbv, &
|
||||||
gri(:, jk), ggri(:, :, jk), igrad_b, dery)
|
gri(:, jk), ggri(:, :, jk), igrad_b, dery=f, &
|
||||||
|
ddr=e)
|
||||||
|
|
||||||
|
! make the error positive and correct it for an unknown bias:
|
||||||
|
! on the correct trajectory |Λ(x̅, N̅)| ≈ -kX, instead of zero.
|
||||||
|
if (present(e)) then
|
||||||
|
e = abs(e + 4.15e-4 * xg)
|
||||||
|
end if
|
||||||
end function rhs
|
end function rhs
|
||||||
|
|
||||||
end subroutine gray_main
|
end subroutine gray_main
|
||||||
@ -1009,66 +1018,209 @@ contains
|
|||||||
end subroutine ic_gb
|
end subroutine ic_gb
|
||||||
|
|
||||||
|
|
||||||
|
function integrator(y, yp, f, h, method) result(y1)
|
||||||
subroutine integrator(y, yp, f, h, method)
|
|
||||||
! Integrator of the raytracing equations
|
! Integrator of the raytracing equations
|
||||||
|
|
||||||
implicit none
|
implicit none
|
||||||
|
|
||||||
real(wp_), dimension(6), intent(inout) :: y ! y̅ = (x̅, N̅)
|
real(wp_), dimension(6), intent(in) :: y ! y̅ = (x̅, N̅)
|
||||||
real(wp_), dimension(6), intent(in) :: yp ! y̅˙ = (dx̅/dσ, dN̅/dσ)
|
real(wp_), dimension(6), intent(in) :: yp ! y̅˙ = f(y̅)
|
||||||
procedure(rhs_function) :: f ! dy̅/dσ = f̅(y̅)
|
procedure(rhs_function) :: f ! dy̅/dσ = f̅(y̅)
|
||||||
real(wp_), intent(in) :: h ! step size
|
real(wp_), intent(in) :: h ! step size
|
||||||
integer, intent(in) :: method
|
integer, intent(in) :: method ! kind of integrator
|
||||||
|
real(wp_), dimension(6) :: y1 ! the new y̅
|
||||||
|
|
||||||
! local variables
|
! local variables
|
||||||
real(wp_), dimension(6) :: yy, k1, k2, k3, k4
|
real(wp_), dimension(6) :: k1, k2, k3, k4
|
||||||
|
|
||||||
select case (method)
|
select case (method)
|
||||||
case (0)
|
case (0)
|
||||||
! Explicit Euler (1⁰ order)
|
! Explicit Euler (1⁰ order)
|
||||||
y = y + yp*h
|
y1 = y + yp*h
|
||||||
|
|
||||||
case (1)
|
case (1)
|
||||||
! Semi-implicit Euler (1⁰ order, symplectic)
|
! Semi-implicit Euler (1⁰ order, symplectic)
|
||||||
! P = p - ∂H/∂q(q, p)
|
! P = p - ∂H/∂q(q, p)⋅h
|
||||||
! Q = q + ∂H/∂p(q, P)
|
! Q = q + ∂H/∂p(q, P)⋅h
|
||||||
k1 = yp
|
k1 = h*yp
|
||||||
y(4:6) = y(4:6) + k1(4:6)*h
|
y1(1:3) = y(1:3)
|
||||||
k2 = f(y)
|
y1(4:6) = y(4:6) + k1(4:6)
|
||||||
y(1:3) = y(1:3) + k2(1:3)*h
|
k2 = h*f(y1)
|
||||||
|
y1(1:3) = y1(1:3) + k2(1:3)
|
||||||
|
|
||||||
case (2)
|
case (2)
|
||||||
! Velocity Verlet (2⁰ order, symplectic)
|
! Velocity Verlet (2⁰ order, symplectic)
|
||||||
! p(n+½) = p(n) - ∂H/∂q(q(n), p(n))⋅h/2
|
! p(n+½) = p(n) - ∂H/∂q(q(n), p(n))⋅h/2
|
||||||
! q(n+1) = q(n) + ∂H/∂p(q(n), p(n+½))⋅h
|
! q(n+1) = q(n) + ∂H/∂p(q(n), p(n+½))⋅h
|
||||||
! p(n+1) = p(n+½) - ∂H/∂q(q(n+1), p(n+½))⋅h/2
|
! p(n+1) = p(n+½) - ∂H/∂q(q(n+1), p(n+½))⋅h/2
|
||||||
k1 = yp
|
k1 = h*yp
|
||||||
y(4:6) = y(4:6) + k1(4:6)*h/2
|
y1(1:3) = y(1:3)
|
||||||
k2 = f(y)
|
y1(4:6) = y(4:6) + k1(4:6)/2
|
||||||
y(1:3) = y(1:3) + k2(1:3)*h
|
k2 = h*f(y1)
|
||||||
k3 = f(y)
|
y1(1:3) = y(1:3) + k2(1:3)
|
||||||
y(4:6) = y(4:6) + k3(4:6)*h/2
|
k3 = h*f(y1)
|
||||||
|
y1(4:6) = y1(4:6) + k3(4:6)/2
|
||||||
|
|
||||||
case (3)
|
case (3)
|
||||||
! 2-stage Runge-Kutta (2⁰ order)
|
! 2-stage Runge-Kutta (2⁰ order)
|
||||||
k1 = yp
|
k1 = h*yp
|
||||||
yy = y + k1*h
|
k2 = h*f(y + k1/2)
|
||||||
k2 = f(yy)
|
y1 = y + k2
|
||||||
yy = y + k2*h
|
|
||||||
y = y + (k1 + k2)*h/2
|
|
||||||
|
|
||||||
case default
|
case default
|
||||||
! 4-stage Runge-Kutta (4⁰ order)
|
! 4-stage Runge-Kutta (4⁰ order)
|
||||||
k1 = yp
|
k1 = h*yp
|
||||||
yy = y + k1*h/2
|
k2 = h*f(y + k1/2)
|
||||||
k2 = f(yy)
|
k3 = h*f(y + k2/2)
|
||||||
yy = y + k2*h/2
|
k4 = h*f(y + k3)
|
||||||
k3 = f(yy)
|
y1 = y + k1/6 + k2/3 + k3/3 + k4/6
|
||||||
yy = y + k3*h
|
|
||||||
k4 = f(yy)
|
|
||||||
y = y + (k1 + 2*k2 + 2*k3 + k4)*h/6
|
|
||||||
end select
|
end select
|
||||||
end subroutine integrator
|
end function integrator
|
||||||
|
|
||||||
|
|
||||||
|
subroutine step_controller(y, yp, f, h, method, adaptive, Bres)
|
||||||
|
! Advances the integration of dy/dσ = f(y) by one step while
|
||||||
|
! controlling the error, the latter estimated by the dispersion relation:
|
||||||
|
! |Λ(x̅, N̅)| ≠ 0.
|
||||||
|
use logger, only : log_debug, log_warning
|
||||||
|
|
||||||
|
implicit none
|
||||||
|
|
||||||
|
! subroutine arguments
|
||||||
|
real(wp_), dimension(6), intent(inout) :: y ! y̅ = (x̅, N̅)
|
||||||
|
real(wp_), dimension(6), intent(in) :: yp ! y̅˙ = (dx̅/dσ, dN̅/dσ)
|
||||||
|
procedure(rhs_function) :: f ! dy̅/dσ = f̅(y̅)
|
||||||
|
real(wp_), intent(inout) :: h ! step size
|
||||||
|
integer, intent(in) :: method ! kind of integrator
|
||||||
|
logical, intent(in) :: adaptive ! whether to change the step
|
||||||
|
|
||||||
|
! arguments for adaptive control
|
||||||
|
real(wp_), optional, intent(in) :: Bres ! resonant magnetic field
|
||||||
|
|
||||||
|
! local variables
|
||||||
|
real(wp_), dimension(6) :: y1, dummy ! new position, dummy variable
|
||||||
|
real(wp_) :: e ! error at new position
|
||||||
|
real(wp_) :: h_max ! max step size
|
||||||
|
character(256) :: msg
|
||||||
|
|
||||||
|
! local constants
|
||||||
|
real(wp_), parameter :: h_min = 1e-2_wp_ ! min step size (cm)
|
||||||
|
real(wp_), parameter :: e_min = 1e-4_wp_ ! min error
|
||||||
|
real(wp_), parameter :: e_max = 1e-3_wp_ ! max error
|
||||||
|
|
||||||
|
! Compute the max step size: this is 1/10 the width of the
|
||||||
|
! resonating plasma layer or 5cm otherwise
|
||||||
|
h_max = max_plasma_step(y(1:3), y(4:6), Bres)
|
||||||
|
|
||||||
|
! Check if the step could miss the resonance
|
||||||
|
if (h > h_max) then
|
||||||
|
if (.not. adaptive) then
|
||||||
|
write(msg, '("step size is too large: h=", g0.2, " h_max=", g0.2)') h, h_max
|
||||||
|
call log_warning(msg, mod='gray_core', proc='step_controller')
|
||||||
|
else
|
||||||
|
h = h_max
|
||||||
|
end if
|
||||||
|
end if
|
||||||
|
|
||||||
|
do
|
||||||
|
! Advance by one step
|
||||||
|
y1 = integrator(y, yp, f, h, method)
|
||||||
|
|
||||||
|
if (.not. adaptive) exit
|
||||||
|
|
||||||
|
! Compute the error
|
||||||
|
dummy = f(y1, e)
|
||||||
|
|
||||||
|
! Try to keep the error bounded to e_max
|
||||||
|
if (e > e_max .and. h/2 > h_min) then
|
||||||
|
h = h/2
|
||||||
|
write(msg, '("e=", 1pe8.2, ": decreasing step to h=", g0.2)') e, h
|
||||||
|
call log_debug(msg, mod='gray_core', proc='step_controller')
|
||||||
|
cycle
|
||||||
|
end if
|
||||||
|
|
||||||
|
if (e < e_min .and. h*2 < h_max) then
|
||||||
|
h = h*2
|
||||||
|
write(msg, '("e=", 1pe8.2, ": increasing step to h=", g0.2)') e, h
|
||||||
|
call log_debug(msg, mod='gray_core', proc='step_controller')
|
||||||
|
end if
|
||||||
|
|
||||||
|
exit
|
||||||
|
end do
|
||||||
|
|
||||||
|
! Update the position
|
||||||
|
y = y1
|
||||||
|
|
||||||
|
end subroutine step_controller
|
||||||
|
|
||||||
|
|
||||||
|
function max_plasma_step(x, N, Bres) result(ds)
|
||||||
|
! Takes the position x̅, refractive index N̅, resonant magnetic field
|
||||||
|
! Bres and returns the maximum integration step `ds` that can be
|
||||||
|
! taken inside the plasma such that it's still possible to resolve
|
||||||
|
! the resonance profile well enough.
|
||||||
|
use equilibrium, only : bfield, equinum_psi
|
||||||
|
use dispersion, only : resonance_width
|
||||||
|
use coreprofiles, only : temp
|
||||||
|
use const_and_precisions, only : mc2=>mc2_
|
||||||
|
|
||||||
|
implicit none
|
||||||
|
|
||||||
|
! function arguments
|
||||||
|
real(wp_), intent(in) :: x(3), N(3) ! position, refractive index
|
||||||
|
real(wp_), intent(in) :: Bres ! resonant magnetic field
|
||||||
|
real(wp_) :: ds ! maximum step size
|
||||||
|
|
||||||
|
! local variables
|
||||||
|
real(wp_) :: R, dR, z ! cylindrical coordinates
|
||||||
|
real(wp_) :: B(3), BR, Bphi ! magnetic field components
|
||||||
|
real(wp_) :: Te, psi ! temperature, poloidal flux
|
||||||
|
real(wp_) :: Npl ! parallel component of N̅
|
||||||
|
|
||||||
|
! To convert from CGS (internal) to SI (equilibrium data)
|
||||||
|
real(wp_), parameter :: cm = 1e-2_wp_
|
||||||
|
|
||||||
|
! Initially assume we are in a vacuum outside the plasma
|
||||||
|
! and return ds=5cm as a fallback value
|
||||||
|
ds = 5
|
||||||
|
|
||||||
|
! Compute the local flux and temperature to check
|
||||||
|
! whether we are inside the plasma
|
||||||
|
R = norm2(x(1:2))
|
||||||
|
z = x(3)
|
||||||
|
call equinum_psi(R*cm, z*cm, psi)
|
||||||
|
|
||||||
|
! No flux data ⇒ outside plasma
|
||||||
|
if (psi <= 0) return
|
||||||
|
|
||||||
|
! No temperature data ⇒ outside plasma
|
||||||
|
Te = temp(psi)
|
||||||
|
if (Te <= 0) return
|
||||||
|
|
||||||
|
! Inside the plasma, check for possible harmonics
|
||||||
|
|
||||||
|
! Compute magnetic field in Cartesian coordinates
|
||||||
|
call bfield(R*cm, z*cm, Bphi=Bphi, BR=BR, Bz=B(3))
|
||||||
|
B(1) = (BR*x(1) - Bphi*x(2)) / R
|
||||||
|
B(2) = (BR*x(2) + Bphi*x(1)) / R
|
||||||
|
|
||||||
|
Npl = dot_product(N, B)/norm2(B) ! N∥ = N̅⋅b̅
|
||||||
|
|
||||||
|
! Compute the extent ΔR of the resonating plasma
|
||||||
|
! layer in the major radius R
|
||||||
|
dR = resonance_width(Y=norm2(B)/Bres, mu=mc2/Te, Npl2=Npl**2, R=R)
|
||||||
|
|
||||||
|
! No resonance, return the vacuum step
|
||||||
|
if (dR == 0) return
|
||||||
|
|
||||||
|
! Compute the extent in the ray direction:
|
||||||
|
!
|
||||||
|
! ΔR = Δs⋅sinθ ⇒ Δs = ΔR/sinθ = ΔR/√[1 - (N∥/N)²]
|
||||||
|
!
|
||||||
|
! and divide by a safety factor of 10:
|
||||||
|
ds = dR / sqrt(1 - (Npl/norm2(N))**2) / 10
|
||||||
|
|
||||||
|
end function max_plasma_step
|
||||||
|
|
||||||
|
|
||||||
subroutine ywppla_upd(xv,anv,dgr,ddgr,sox,bres,xgcn,dery,psinv,dens,btot, &
|
subroutine ywppla_upd(xv,anv,dgr,ddgr,sox,bres,xgcn,dery,psinv,dens,btot, &
|
||||||
|
@ -59,6 +59,7 @@ module gray_params
|
|||||||
integer :: nstep ! Max number of integration steps
|
integer :: nstep ! Max number of integration steps
|
||||||
integer :: idst ! Choice of the integration variable
|
integer :: idst ! Choice of the integration variable
|
||||||
integer :: integrator ! Choice of the integration method
|
integer :: integrator ! Choice of the integration method
|
||||||
|
logical :: adaptive_step ! Allow variable step sizes
|
||||||
integer :: ipass ! Number of plasma passes
|
integer :: ipass ! Number of plasma passes
|
||||||
integer :: ipol ! Whether to compute wave polarisation
|
integer :: ipol ! Whether to compute wave polarisation
|
||||||
end type
|
end type
|
||||||
@ -373,6 +374,7 @@ contains
|
|||||||
! Default values of parameters introduced after
|
! Default values of parameters introduced after
|
||||||
! gray_params.data has been deprecated
|
! gray_params.data has been deprecated
|
||||||
params%raytracing%integrator = 4
|
params%raytracing%integrator = 4
|
||||||
|
params%raytracing%adaptive_step = .false.
|
||||||
|
|
||||||
end subroutine read_gray_params
|
end subroutine read_gray_params
|
||||||
|
|
||||||
|
@ -11,7 +11,7 @@ sets='antenna equilibrium profiles raytracing ecrh_cd output misc'
|
|||||||
antenna='alpha beta power psi chi iox ibeam filenm fghz pos w ri phi'
|
antenna='alpha beta power psi chi iox ibeam filenm fghz pos w ri phi'
|
||||||
equilibrium='ssplps ssplf factb sgnb sgni ixp iequil icocos ipsinorm idesc ifreefmt filenm'
|
equilibrium='ssplps ssplf factb sgnb sgni ixp iequil icocos ipsinorm idesc ifreefmt filenm'
|
||||||
profiles='psnbnd sspld factne factte iscal irho iprof filenm'
|
profiles='psnbnd sspld factne factte iscal irho iprof filenm'
|
||||||
raytracing='rwmax dst nrayr nrayth nstep igrad idst ipass ipol integrator'
|
raytracing='rwmax dst nrayr nrayth nstep igrad idst ipass ipol integrator adaptive_step'
|
||||||
ecrh_cd='iwarm ilarm imx ieccd'
|
ecrh_cd='iwarm ilarm imx ieccd'
|
||||||
output='ipec nrho istpr istpl'
|
output='ipec nrho istpr istpl'
|
||||||
misc='rwall'
|
misc='rwall'
|
||||||
|
@ -133,24 +133,34 @@ contains
|
|||||||
end if
|
end if
|
||||||
|
|
||||||
end subroutine wall_out
|
end subroutine wall_out
|
||||||
! ------------------------------
|
|
||||||
subroutine initbeam(i,iroff,iboff,iwait,stv,jphi_beam,pins_beam,currins_beam, &
|
|
||||||
dpdv_beam,jcd_beam) ! initialization at beam propagation start
|
subroutine initbeam(params, i, iroff, iboff, iwait, stv, dst, jphi_beam, &
|
||||||
use logger, only : log_info, log_warning
|
pins_beam, currins_beam, dpdv_beam, jcd_beam)
|
||||||
|
! Initialises the beam variables at the start of the beam propagation
|
||||||
|
|
||||||
|
use gray_params, only : gray_parameters
|
||||||
|
use logger, only : log_warning
|
||||||
|
|
||||||
implicit none
|
implicit none
|
||||||
! arguments
|
|
||||||
|
! subroutine arguments
|
||||||
|
type(gray_parameters), intent(in) :: params
|
||||||
integer, intent(in) :: i ! beam index
|
integer, intent(in) :: i ! beam index
|
||||||
logical, dimension(:,:), intent(in), pointer :: iroff ! global ray status (F = active, T = inactive)
|
logical, pointer, intent(in) :: iroff(:,:) ! global ray status (F = active, T = inactive)
|
||||||
logical, intent(out) :: iboff
|
logical, intent(out) :: iboff ! beam status (F = active, T = inactive)
|
||||||
logical, dimension(:), intent(out), pointer :: iwait
|
logical, pointer, intent(out) :: iwait(:)
|
||||||
real(wp_), dimension(:), intent(out), pointer :: jphi_beam,pins_beam, &
|
real(wp_), pointer, intent(out), dimension(:) :: &
|
||||||
currins_beam,dpdv_beam,jcd_beam,stv
|
jphi_beam, pins_beam, currins_beam, dpdv_beam, jcd_beam, stv, dst
|
||||||
|
|
||||||
|
! local variables
|
||||||
character(256) :: msg ! buffer for formatting log messages
|
character(256) :: msg ! buffer for formatting log messages
|
||||||
|
|
||||||
iboff = .false. ! beam status (F = active, T = inactive)
|
iboff = .false.
|
||||||
iwait = iroff(:,i) ! copy ray status for current beam from global ray status
|
iwait = iroff(:,i) ! copy current beam status from the global one
|
||||||
if(all(iwait)) then ! no rays active => stop beam
|
|
||||||
|
if (all(iwait)) then
|
||||||
|
! no rays active => stop beam
|
||||||
iboff = .true.
|
iboff = .true.
|
||||||
else if (any(iwait)) then
|
else if (any(iwait)) then
|
||||||
! only some rays active
|
! only some rays active
|
||||||
@ -158,15 +168,18 @@ contains
|
|||||||
call log_warning(msg, mod='multipass', proc='initbeam')
|
call log_warning(msg, mod='multipass', proc='initbeam')
|
||||||
end if
|
end if
|
||||||
|
|
||||||
stv = zero ! starting step
|
stv = zero ! starting ray parameter (s, c⋅t, S_R)
|
||||||
|
dst = params%raytracing%dst ! starting step size (ds, c⋅dt, dS_R)
|
||||||
|
|
||||||
jphi_beam = zero ! 1D beam profiles
|
! 1D beam profiles
|
||||||
|
jphi_beam = zero
|
||||||
pins_beam = zero
|
pins_beam = zero
|
||||||
currins_beam = zero
|
currins_beam = zero
|
||||||
dpdv_beam = zero
|
dpdv_beam = zero
|
||||||
jcd_beam = zero
|
jcd_beam = zero
|
||||||
end subroutine initbeam
|
end subroutine initbeam
|
||||||
! ------------------------------
|
|
||||||
|
|
||||||
subroutine initmultipass(i,iox,iroff,yynext,yypnext,yw0,ypw0,stnext,p0ray, &
|
subroutine initmultipass(i,iox,iroff,yynext,yypnext,yw0,ypw0,stnext,p0ray, &
|
||||||
taus,tau1,etau1,cpls,cpl1,lgcpl1,psipv,chipv) ! initialization before pass loop
|
taus,tau1,etau1,cpls,cpl1,lgcpl1,psipv,chipv) ! initialization before pass loop
|
||||||
implicit none
|
implicit none
|
||||||
@ -219,71 +232,121 @@ contains
|
|||||||
end if
|
end if
|
||||||
|
|
||||||
end subroutine turnoffray
|
end subroutine turnoffray
|
||||||
! ------------------------------
|
|
||||||
subroutine alloc_multipass(dim,iwait,iroff,iop,iow,yynext,yypnext,yw0,ypw0,stnext, &
|
|
||||||
stv,p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,jphi_beam, &
|
|
||||||
pins_beam,currins_beam,dpdv_beam,jcd_beam,psipv,chipv)
|
|
||||||
implicit none
|
|
||||||
integer :: dim
|
|
||||||
logical, dimension(:), intent(out), pointer :: iwait
|
|
||||||
logical, dimension(:,:), intent(out), pointer :: iroff
|
|
||||||
integer, dimension(:), intent(out), pointer :: iop,iow
|
|
||||||
real(wp_), dimension(:), intent(out), pointer :: jphi_beam,pins_beam,currins_beam, &
|
|
||||||
dpdv_beam,jcd_beam,stv,tau1,etau1,cpl1,lgcpl1,p0ray,psipv,chipv
|
|
||||||
real(wp_), dimension(:,:), intent(out), pointer :: taus,cpls,stnext,yw0,ypw0
|
|
||||||
real(wp_), dimension(:,:,:), intent(out), pointer :: yynext,yypnext
|
|
||||||
|
|
||||||
call dealloc_multipass(iwait,iroff,iop,iow,yynext,yypnext,yw0,ypw0,stnext,stv, &
|
|
||||||
p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,jphi_beam,pins_beam,currins_beam, &
|
subroutine alloc_multipass(&
|
||||||
dpdv_beam,jcd_beam,psipv,chipv)
|
dim, iwait, iroff, iop, iow, yynext, yypnext, yw0, ypw0, stnext, &
|
||||||
|
stv, dst, p0ray, taus, tau1, etau1, cpls, cpl1, lgcpl1, jphi_beam, &
|
||||||
|
pins_beam, currins_beam, dpdv_beam, jcd_beam, psipv, chipv)
|
||||||
|
|
||||||
|
implicit none
|
||||||
|
|
||||||
|
! subroutine arguments
|
||||||
|
integer, intent(in) :: dim
|
||||||
|
logical, pointer, dimension(:), intent(out) :: iwait
|
||||||
|
logical, pointer, dimension(:,:), intent(out) :: iroff
|
||||||
|
integer, pointer, dimension(:), intent(out) :: iop, iow
|
||||||
|
real(wp_), pointer, dimension(:), intent(out) :: &
|
||||||
|
jphi_beam, pins_beam, currins_beam, dpdv_beam, &
|
||||||
|
jcd_beam, stv, dst, tau1, etau1, cpl1, lgcpl1, &
|
||||||
|
p0ray, psipv, chipv
|
||||||
|
real(wp_), pointer, dimension(:, :), intent(out) :: taus, cpls, stnext
|
||||||
|
real(wp_), pointer, dimension(:, :), intent(out) :: yw0, ypw0
|
||||||
|
real(wp_), pointer, dimension(:, :, :), intent(out) :: yynext, yypnext
|
||||||
|
|
||||||
|
call dealloc_multipass(&
|
||||||
|
iwait, iroff, iop, iow, yynext, yypnext, yw0, ypw0, stnext, &
|
||||||
|
stv, dst, p0ray, taus, tau1, etau1, cpls, cpl1, lgcpl1, jphi_beam, &
|
||||||
|
pins_beam, currins_beam, dpdv_beam, jcd_beam, psipv, chipv)
|
||||||
|
|
||||||
|
|
||||||
nbeam_max = 2**ipass ! max n of beams active at a time
|
nbeam_max = 2**ipass ! max n of beams active at a time
|
||||||
nbeam_tot = 2**(ipass+1)-2 ! total n of beams
|
nbeam_tot = 2**(ipass+1)-2 ! total n of beams
|
||||||
|
|
||||||
allocate(iwait(nray),iroff(nray,nbeam_tot),iop(nray),iow(nray), &
|
allocate(iwait(nray))
|
||||||
yynext(6,nray,nbeam_max-2),yypnext(6,nray,nbeam_max-2), &
|
allocate(iroff(nray, nbeam_tot))
|
||||||
yw0(6,nray),ypw0(6,nray),stnext(nray,nbeam_tot),stv(nray), &
|
allocate(iop(nray))
|
||||||
p0ray(nray),taus(nray,nbeam_tot),tau1(nray),etau1(nray), &
|
allocate(iow(nray))
|
||||||
cpls(nray,nbeam_tot),cpl1(nray),lgcpl1(nray),jphi_beam(dim), &
|
|
||||||
pins_beam(dim),currins_beam(dim),dpdv_beam(dim),jcd_beam(dim), &
|
allocate(yynext(6, nray, nbeam_max-2))
|
||||||
psipv(nbeam_tot),chipv(nbeam_tot))
|
allocate(yypnext(6, nray, nbeam_max-2))
|
||||||
|
|
||||||
|
allocate(yw0(6, nray))
|
||||||
|
allocate(ypw0(6, nray))
|
||||||
|
|
||||||
|
allocate(stnext(nray, nbeam_tot))
|
||||||
|
allocate(stv(nray))
|
||||||
|
allocate(dst(nray))
|
||||||
|
|
||||||
|
allocate(p0ray(nray))
|
||||||
|
allocate(taus(nray, nbeam_tot))
|
||||||
|
allocate(tau1(nray))
|
||||||
|
allocate(etau1(nray))
|
||||||
|
|
||||||
|
allocate(cpls(nray, nbeam_tot))
|
||||||
|
allocate(cpl1(nray))
|
||||||
|
allocate(lgcpl1(nray))
|
||||||
|
allocate(jphi_beam(dim))
|
||||||
|
|
||||||
|
allocate(pins_beam(dim))
|
||||||
|
allocate(currins_beam(dim))
|
||||||
|
allocate(dpdv_beam(dim))
|
||||||
|
allocate(jcd_beam(dim))
|
||||||
|
|
||||||
|
allocate(psipv(nbeam_tot))
|
||||||
|
allocate(chipv(nbeam_tot))
|
||||||
|
|
||||||
end subroutine alloc_multipass
|
end subroutine alloc_multipass
|
||||||
! ------------------------------
|
|
||||||
subroutine dealloc_multipass(iwait,iroff,iop,iow,yynext,yypnext,yw0,ypw0,stnext, &
|
|
||||||
stv,p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,jphi_beam, &
|
subroutine dealloc_multipass(&
|
||||||
|
iwait, iroff, iop, iow, yynext, yypnext, yw0, ypw0, stnext, &
|
||||||
|
stv, dst, p0ray, taus, tau1, etau1, cpls, cpl1, lgcpl1, jphi_beam, &
|
||||||
pins_beam, currins_beam, dpdv_beam, jcd_beam, psipv, chipv)
|
pins_beam, currins_beam, dpdv_beam, jcd_beam, psipv, chipv)
|
||||||
|
|
||||||
implicit none
|
implicit none
|
||||||
logical, dimension(:), intent(out), pointer :: iwait
|
|
||||||
logical, dimension(:,:), intent(out), pointer :: iroff
|
logical, pointer, dimension(:), intent(out) :: iwait
|
||||||
integer, dimension(:), intent(out), pointer :: iop,iow
|
logical, pointer, dimension(:,:), intent(out) :: iroff
|
||||||
real(wp_), dimension(:), intent(out), pointer :: stv,p0ray,tau1,etau1,cpl1,lgcpl1, &
|
integer, pointer, dimension(:), intent(out) :: iop, iow
|
||||||
jphi_beam,pins_beam,currins_beam,dpdv_beam,jcd_beam,psipv,chipv
|
real(wp_), pointer, dimension(:), intent(out) :: &
|
||||||
real(wp_), dimension(:,:), intent(out), pointer :: yw0,ypw0,stnext,taus,cpls
|
jphi_beam, pins_beam, currins_beam, dpdv_beam, &
|
||||||
real(wp_), dimension(:,:,:), intent(out), pointer :: yynext,yypnext
|
jcd_beam, stv, dst, tau1, etau1, cpl1, lgcpl1, &
|
||||||
|
p0ray, psipv, chipv
|
||||||
|
real(wp_), pointer, dimension(:, :), intent(out) :: taus, cpls, stnext
|
||||||
|
real(wp_), pointer, dimension(:, :), intent(out) :: yw0, ypw0
|
||||||
|
real(wp_), pointer, dimension(:, :, :), intent(out) :: yynext, yypnext
|
||||||
|
|
||||||
if (associated(iwait)) deallocate(iwait)
|
if (associated(iwait)) deallocate(iwait)
|
||||||
if (associated(iroff)) deallocate(iroff)
|
if (associated(iroff)) deallocate(iroff)
|
||||||
if (associated(iop)) deallocate(iop)
|
if (associated(iop)) deallocate(iop)
|
||||||
if (associated(iow)) deallocate(iow)
|
if (associated(iow)) deallocate(iow)
|
||||||
|
|
||||||
if (associated(yynext)) deallocate(yynext)
|
if (associated(yynext)) deallocate(yynext)
|
||||||
if (associated(yypnext)) deallocate(yypnext)
|
if (associated(yypnext)) deallocate(yypnext)
|
||||||
|
|
||||||
if (associated(yw0)) deallocate(yw0)
|
if (associated(yw0)) deallocate(yw0)
|
||||||
if (associated(ypw0)) deallocate(ypw0)
|
if (associated(ypw0)) deallocate(ypw0)
|
||||||
|
|
||||||
if (associated(stnext)) deallocate(stnext)
|
if (associated(stnext)) deallocate(stnext)
|
||||||
if (associated(stv)) deallocate(stv)
|
if (associated(stv)) deallocate(stv)
|
||||||
|
if (associated(dst)) deallocate(dst)
|
||||||
|
|
||||||
if (associated(p0ray)) deallocate(p0ray)
|
if (associated(p0ray)) deallocate(p0ray)
|
||||||
if (associated(taus)) deallocate(taus)
|
if (associated(taus)) deallocate(taus)
|
||||||
if (associated(tau1)) deallocate(tau1)
|
if (associated(tau1)) deallocate(tau1)
|
||||||
if (associated(etau1)) deallocate(etau1)
|
if (associated(etau1)) deallocate(etau1)
|
||||||
|
|
||||||
if (associated(cpls)) deallocate(cpls)
|
if (associated(cpls)) deallocate(cpls)
|
||||||
if (associated(cpl1)) deallocate(cpl1)
|
if (associated(cpl1)) deallocate(cpl1)
|
||||||
if (associated(lgcpl1)) deallocate(lgcpl1)
|
if (associated(lgcpl1)) deallocate(lgcpl1)
|
||||||
if (associated(jphi_beam)) deallocate(jphi_beam)
|
if (associated(jphi_beam)) deallocate(jphi_beam)
|
||||||
|
|
||||||
if (associated(pins_beam)) deallocate(pins_beam)
|
if (associated(pins_beam)) deallocate(pins_beam)
|
||||||
if (associated(currins_beam)) deallocate(currins_beam)
|
if (associated(currins_beam)) deallocate(currins_beam)
|
||||||
if (associated(dpdv_beam)) deallocate(dpdv_beam)
|
if (associated(dpdv_beam)) deallocate(dpdv_beam)
|
||||||
if (associated(jcd_beam)) deallocate(jcd_beam)
|
if (associated(jcd_beam)) deallocate(jcd_beam)
|
||||||
|
|
||||||
if (associated(psipv)) deallocate(psipv)
|
if (associated(psipv)) deallocate(psipv)
|
||||||
if (associated(chipv)) deallocate(chipv)
|
if (associated(chipv)) deallocate(chipv)
|
||||||
end subroutine dealloc_multipass
|
end subroutine dealloc_multipass
|
||||||
|
Loading…
Reference in New Issue
Block a user