Compare commits

...

8 Commits

Author SHA1 Message Date
Michele Guerini Rocco
39b019db1d
src/polarization.f90: rewrite 2024-04-11 09:23:04 +02:00
Michele Guerini Rocco
5966ee8e9b
fix incorrect coupling for X mode beams 2024-04-11 09:23:04 +02:00
Michele Guerini Rocco
7eeb34c7dc
src/gray_core.f90: refine realtime termination check
In some very rare cases the residual power check can stop the
integration too early.

For example, this extremely unlikely chain of events was observed in a
few cases while performing a parameter sweep (~3000 simulations):

  1. n⊥ converges on wrong branch ⇒ α jumps ⇒ dP/ds jumps (common)
  2. dP/ds jumps close to the peak (unlikely)
  3. the peak of dP/ds is close to 0.6P₀ (unlikely)
  4. dP/ds jumps to dP/ds_max + 10⁻¹² ⇒ wrong peak found (very unlikely)
  5. peak is at exactly the current point
     ⇒ three-point interpolation fails (unlikely)
2024-04-11 09:23:04 +02:00
Michele Guerini Rocco
ffed0dc1c5
src/gray_core.f90: fast absorption computation
This implements an explicit formula for the absorption
coefficient in the low temperature limit, available
with iwarm=4.
2024-03-24 09:25:51 +01:00
Michele Guerini Rocco
899f524782
src/main.f90: add server mode
This adds a sort of simplified JSON RPC. It makes possible to interface
with GRAY from any other program without writing bindings or using some
FFI. It works simply by starting GRAY in a subprocess and communicating
with it using a pipe.

Both requests and replies are a single line of text: commands are sent
to the stdin and GRAY replies with a JSON object on the stdout.
The commands include setting/getting any GRAY parameter, reloading the
input files, starting the simulation and quitting.
2024-03-24 09:25:50 +01:00
Michele Guerini Rocco
7342566ac0
add a switch for realtime mode
This adds a single switch to configure GRAY for realtime operation.

In realtime a single ray is traced until absorption reaches ≈50% of the
total. The simulation is stopped immediately after returning only the
position (as ρ_p=√ψ) of the peak. So, no post-processing is performed at
all. In addition:

 - all outputs units are inactivated (equivalent to passing --units 0);

 - current drive computation is disabled (ecrh_cd.ieccd=0);

 - absorption is computed in weakly relativistic approximation
   (ecrh_cd.iwarm=1);

 - reflections and multiple plasma passes are disabled;
2024-03-24 09:25:50 +01:00
Michele Guerini Rocco
92b3ad9bd3
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.
2024-02-26 14:44:19 +01:00
Michele Guerini Rocco
c9c20198a7
src/gray_core.f90: make integrator configurable
This change makes the integration method of the raytracing equations
configurable and significantly simplifies the integrator subroutine
by moving the implementation details outside.
2024-02-26 13:50:07 +01:00
13 changed files with 1700 additions and 546 deletions

View File

@ -26,6 +26,31 @@ nstep = 12000
; 2: real part of the eikonal (S_r) ; 2: real part of the eikonal (S_r)
idst = 0 idst = 0
; Choice of the integration method
; 0: Explicit Euler (1⁰ order)
; 1: Semi-implicit Euler (1⁰ order, symplectic)
; 2: Velocity Verlet (2⁰ order, symplectic)
; 3: 2-stage Runge-Kutta (2⁰ order)
; 4: 4-stage Runge-Kutta (4⁰ order)
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
; Enable the realtime mode
; In realtime a single ray is traced until absorption reaches ≈50% of the
; total. The simulation is stopped immediately after returning only the
; position (as ρ_p=√ψ) of the peak. So, no post-processing is
; performed at all. In addition:
; - all outputs units are inactivated (equivalent to passing --units 0);
; - current drive computation is disabled (ecrh_cd.ieccd=0);
; - absorption is computed in weakly relativistic approximation
; (ecrh_cd.iwarm=1);
; - reflections and multiple plasma passes are disabled;
realtime = false
[ecrh_cd] [ecrh_cd]
; Choice of the power absorption model ; Choice of the power absorption model

400
src/absorption.f90 Normal file
View File

@ -0,0 +1,400 @@
! This modules implements a simplified formula for the plasma absorption
! coefficient close to the harmonics valid for low temperature (< 10keV)
! and low harmonic numbers (<6).
!
! Reference: 1983 Nuclear Fusion 23 1153 (https://doi.org/bm6zcr)
!
module absorption
use const_and_precisions, only : wp_
implicit none
private
public :: alpha_fast
contains
pure function line_shape(Y, Npl2, theta) result(phi)
! The line shape function of the first harmonic,
! with exception of the X mode in the tenuous plasma regime:
!
! φ(ζ) = Im(-1/Z(ζ))
!
! From the same considerations as in `line_shape_harmonics`, we have:
!
! φ(ζ) = 1/π exp(ζ²)/[1 + erfi(ζ)²]
!
! Note: Since we already have an implementation of Z(ζ) we
! use that and write Φ(ζ) = Im(Z)/[Re(Z)² + Im(Z)²].
!
use const_and_precisions, only: zero
use dispersion, only: zetac
implicit none
! function arguments
! CMA Y variable: Y=ω_c/ω
real(wp_), intent(in) :: Y
! squared parallel refractive index: N²=N²cos²θ
real(wp_), intent(in) :: Npl2
! adimensional temperature: Θ = kT/mc²
real(wp_), intent(in) :: theta
! line shape Φ(ζ)
real(wp_) :: phi
! local variables
real(wp_) :: a, b, z
integer :: err
z = (1 - Y)/sqrt(2 * theta * Npl2) ! ζ
call zetac(z, zero, a, b, err) ! a=Re(Z(ζ)), b=Im(Z(ζ))
phi = b/(a**2 + b**2) ! Im(-1/Z)
end function line_shape
pure function line_shape_harmonics(Y, Npl2, theta, n) result(phi)
! The line shape function of all modes at higher harmonics (n>1)
! and the X mode at the first harmonic:
!
! φ(ζ) = Im(Z(ζ))
!
! where Z(ζ) = 1/π dz exp(-z²)/(z-ζ);
! ζ = (ω - nω_c)/(2 k v_t)
! = (1 - nY)/((2Θ)N).
!
! Since the plasma is weakly dissipative, the wavenumber has a small
! positive imaginary part, so Im(ζ)<0. By the SokhotskiPlemelj
! theorem we have that:
!
! lim_Im(ζ)0 Z(ζ) = 1/π P dz exp(-z²)/(z-ζ) + iπ exp(-ζ²)
! = -π exp(-ζ²) erfi(ζ) + iπ exp(-ζ²)
!
! where erfi(ζ) = -ierf(). So, Φ(ζ) = π exp(-ζ²).
!
use const_and_precisions, only : sqrt_pi
implicit none
! function arguments
! CMA Y variable: Y=ω_c/ω
real(wp_), intent(in) :: Y
! squared parallel refractive index: N²=N²cos²θ
real(wp_), intent(in) :: Npl2
! adimensional temperature: Θ = kT/mc²
real(wp_), intent(in) :: theta
! harmonic number
integer, intent(in) :: n
! line shape Φ(ζ)
real(wp_) :: phi
! local variables
real(wp_) :: z2
z2 = (1 - n*Y)**2/(2 * theta * Npl2)
phi = sqrt_pi * exp(-z2)
end function line_shape_harmonics
pure function warm_index(d, Npl2, Npr2, sox) result(M2)
! The real part of the warm plasma refractive index
! in the finite density regime near the first harmonic:
!
! M² = (1 - δ + ½ N²/N² ½ Δ) N²/N²
!
! where Δ = N/N + 4n²(1-δ)²N²/N²;
! δ = X/Y².
!
! Reference: 1983 Nuclear Fusion 23 1153 - table VII
!
implicit none
! function arguments
! parameter δ=(ω_pe/ω_ce)²
real(wp_), intent(in) :: d
! squared refractive index: N², N² (cold dispersion)
real(wp_), intent(in) :: Npl2, Npr2
! sign of polarisation mode: -1 O, +1 X
integer, intent(in) :: sox
! warm refactive indexL M²
real(wp_) :: M2
! local variables
real(wp_) :: N2, delta
! total refractive index N²
N2 = Npl2 + Npr2
delta = (Npr2/N2)**2 + 4*(1-d)**2 * (Npl2/N2)
M2 = (1 - d + Npr2/N2/2 + sox*sqrt(delta)/2) * N2/Npr2
end function warm_index
pure function warm_index_harmonics(d, Npl2, Npr2, sox, n) result(M2)
! The real part of the warm plasma refractive index
! in the finite density regime near the harmonics (n>2)
!
! M² = 1 - δf
!
! where f = (1 - δ) / [(1 - δ) - (N²/N² ρ) / (2n²)];
! ρ² = N/N + 4n²(1 - δ)² N²/N²;
! δ = X/(nY)².
!
! Reference: 1983 Nuclear Fusion 23 1153 - table VIII
!
implicit none
! function arguments
! parameter δ=(ω_p/nω_c)²
real(wp_), intent(in) :: d
! squared refractive index: N², N² (cold dispersion)
real(wp_), intent(in) :: Npl2, Npr2
! sign of polarisation mode: -1 O, +1 X
integer, intent(in) :: sox
! harmonic number
integer, intent(in) :: n
! warm refactive index
real(wp_) :: M2
! local variables
real(wp_) :: N2, f, r2
! total refractive index N²
N2 = Npl2 + Npr2
r2 = (Npr2/N2)**2 + 4*n**2 * (1 - d)**2 * Npl2/N2
f = (1 - d) / ((1 - d) - (Npr2/N2 + sox * sqrt(r2)) / (2*n**2))
M2 = 1 - d*f
end function warm_index_harmonics
pure function polarisation(X, Y, N2, Npl2, Npr2, sox) result(R)
! The polarisation function R(θ,O/X) in the finite density regime
! for the first harmonic:
!
! R(N, N, O/X) = [(1 - δ)(1 - δ/2 - M²) - M²]²
! 1/(a² + b²) M 1/d
!
! where δ = X/Y²
! a² = [(1 - δ - M²)² + (1 - d)M²]² M²
! b² = (2 - 2δ - M²)² (1 - d - M²)² M²
! M is the real part of the warm refractive index
!
! Reference: 1983 Nuclear Fusion 23 1153 - formula (3.1.68)
!
implicit none
! function arguments
! CMA diagram variables: X=(ω_pe/ω)², Y=ω_ce/ω
real(wp_), intent(in) :: X, Y
! squared refractive index: N², N², N² (cold dispersion)
real(wp_), intent(in) :: N2, Npl2, Npr2
! sign of polarisation mode: -1 O, +1 X
integer, intent(in) :: sox
! polarisation function
real(wp_) :: R
! local variables
real(wp_) :: a2, b2, d
real(wp_) :: M2, Mpl2, Mpr2
d = X/Y**2 ! δ=(ω_pe/ω_ce)²
M2 = warm_index(d, Npl2, Npr2, sox)
Mpl2 = M2 * Npl2/N2 ! M² = M²cos²θ
Mpr2 = M2 * Npr2/N2 ! M² = M²sin²θ
a2 = ((1 - d - Mpr2)**2 + (1 - d)*Mpl2)**2 * Mpr2
b2 = (2 - 2*d - Mpr2)**2 * (1 - d - Mpr2)**2 * Mpl2
R = ((1 - d)*(1 - d/2 - Mpl2) - Mpr2)**2 / sqrt(a2 + b2) &
* sqrt(Mpl2) / d
end function polarisation
pure function polarisation_harmonics(X, Y, N2, Npl2, Npr2, sox, n) result(mu)
! The polarisation function μ(n,θ,O/X) times 2(1+cos²θ)
! in the finite-density plasma regime for harmonics (n>1):
!
! μ2(1+cos²θ) = M^(2n-3) (n-1)² (1 - (1+1/n)f) / (a²+b²)
!
! where f as in `warm_index_harmonics`;
! a = (N/N) (1 + c/e² M²);
! b = (N/N) (1 + c/e);
! c = (1-δ) n²[1 - (1-1/n²)f]²;
! e = 1-δ-M²
! M = M/N N = M cosθ;
! M = M/N N = M sinθ;
! M is the real part of the warm refractive index.
!
! Reference: 1983 Nuclear Fusion 23 1153 - formula (3.1.77)
!
implicit none
! function arguments
! CMA diagram variables: X=(ω_pe/ω)², Y=ω_ce/ω
real(wp_), intent(in) :: X, Y
! squared refractive index: N², N², N² (cold dispersion)
real(wp_), intent(in) :: N2, Npl2, Npr2
! sign of polarisation mode: -1 O, +1 X
integer, intent(in) :: sox
! harmonic number
integer, intent(in) :: n
! polarisation function
real(wp_) :: mu
! local variables
real(wp_) :: d, f, a2, b2, c, e
real(wp_) :: M2, Mpl2, Mpr2
! δ=(ω_pe/nω_ce)²
d = X/(n*Y)**2
M2 = warm_index_harmonics(d, Npl2, Npr2, sox, n)
Mpl2 = M2 * Npl2/N2 ! M = Mcosθ
Mpr2 = M2 * Npr2/N2 ! M = Msinθ
f = (1 - M2)/d
c = (1 - d) * n**2 * (1 - (1 - 1/n**2) * f)**2
e = 1 - d - Mpr2
a2 = Npr2/N2 * (1 + c/e**2 * Mpl2)**2 ! a²
b2 = Npl2/N2 * (1 + c/e)**2 ! b²
mu = M2**(n-3.0_wp_/2) * (n-1)**2 &
* (1 - (1 + 1/n) * f)**2 &
/ sqrt(a2 + b2)
end function polarisation_harmonics
function alpha_fast(X, Y, theta, k0, Npl, Npr, sox, &
nhmin, nhmax) result(alpha)
! The absorption coefficient around ω=nω_c in the low
! temperature (< 10keV), low harmonic number limit (< 6),
! and oblique propagation:
!
! α(n,ω,θ,O/X) = α(n,θ)μ(n,θ,O/X)Φ(n,ω)
!
! where α(n,θ) is the nth-harmonic absorption coeff.;
! μ(n,θ,O/X) is the polarisation part;
! Φ(n,ω) is the line shape function.
!
! Finally, for the X1 mode:
!
! Notes:
! 1. The approximation is decent for
! δ = (ω_pe/nω_ce)² / (2 Θ N) << 1 (tenuous plasma)
! >> 1 (finite density);
! 2. In the implementation the angular dependencies
! have been replaced by cosθ=N/N, sinθ=N/N;
! 3. The special cases for n=1 have been recast
! from the original form (tbl. XI, eq. 3.1.67)
! to match with eq. 3.1.73.
!
implicit none
! function arguments
! CMA diagram variables: X=(ω_pe/ω)², Y=ω_ce/ω
real(wp_), intent(in) :: X, Y
! adimensional temperature: Θ = kT/mc²
real(wp_), intent(in) :: theta
! vacuum wavenumber k=ω/c
real(wp_), intent(in) :: k0
! refractive index: N, N (cold dispersion)
real(wp_), intent(in) :: Npl, Npr
! sign of polarisation mode: -1 O, +1 X
integer, intent(in) :: sox
! min/max harmonic number
integer, intent(in) :: nhmin, nhmax
! absorption coefficient
real(wp_) :: alpha
! local variables
integer :: n ! harmonic number
real(wp_) :: N2, Npr2, Npl2
real(wp_) :: delta
real(wp_) :: shape, polar, absorp
Npr2 = Npr**2 ! N² refractive index
Npl2 = Npl**2 ! N²
N2 = Npr2 + Npl2 ! N²
! tenuous/finite density parameter:
! δ = (ω_p/ω_c)²/(2Θ N)
delta = X/Y**2 / (2*abs(Npl)*sqrt(theta))
! First harmonic
if (delta < 1) then
! Tenuous plasma
if (sox < 0) then
! O mode
! absorption coeff: kX
absorp = k0 * X
! polarisation part: N/N² (N²+2N²)²/(N²+ N²)³
polar = Npr2**2/N2 * (N2 + 2*Npl2)**2/(N2 + Npl2)**3
! line shape part: Φ(ζ) = Im(-1/Z(ζ)) / ((2/Θ)Y|N|)
shape = line_shape(Y, Npl2, theta) &
/ (sqrt(2/theta) * Y * abs(Npl))
else
! X mode
! polarisation part: (N² + N²)/N
polar = (N2 + Npl2) / sqrt(N2)
! line shape part: Φ(ζ) = Im(Z(ζ)) / (2(2θ)Y|N|)
shape = line_shape_harmonics(Y, Npl2, theta, n) &
/ (2 * sqrt(2*theta) * Y * abs(Npl))
end if
else
! Finite density (δ > 1)
! absorption coeff: kY
absorp = k0 * Y
! polarisation part: R(N, N, O/X)
polar = polarisation(X, Y, N2, Npl2, Npr2, sox)
! line shape part: Φ(ζ) = Im(-1/Z(ζ)) 2(2Θ)
shape = line_shape(Y, Npl2, theta) &
* 2 * sqrt(2*theta)
end if
alpha = absorp * polar * shape
if (nhmax == 1) return
! n-independent part of α: kX
absorp = k0 * X
! Higher harmonics
! note: the loop starts from n=1 to compute
! the powers/factorials of n, even when nhmin>1.
do n=1,nhmax
! absorption part: α(n,θ)/[(1+cos²θ)n^(2n)(πω)]
absorp = absorp / (2*n) ! computes (2n)!!
if (n >= nhmin) then
! polarisation part: (1+cos²θ)μ(n,θ)
polar = polarisation_harmonics(X, Y, N2, Npl2, Npr2, sox, n)
! line shape part: Φ(n,ω)(πω)
shape = line_shape_harmonics(Y, Npl2, theta, n) &
/ (sqrt(2*theta) * n*Y * abs(Npl))
! full absorption coefficient: α(n,ω,θ)
alpha = alpha + absorp*n**(2*n) * polar * shape
end if
! computes * (Θ N²/N²)^(n-1)
absorp = absorp * (theta * Npr2/N2)
end do
end function alpha_fast
end module absorption

View File

@ -3,31 +3,27 @@ module beamdata
implicit none implicit none
integer, save :: nray,nrayr,nrayth,nstep,jkray1 integer, save :: nray,nrayr,nrayth,nstep,jkray1
real(wp_), save :: dst,h,hh,h6,rwmax,twodr2 real(wp_), save :: dst,rwmax,twodr2
contains contains
subroutine init_btr(rtrparam,ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, & subroutine init_btr(rtrparam,ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, &
tau0,alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv) tau0,alphaabs0,dpds,dids0,ccci0,p0jk,ext,eyt,iiv)
use gray_params, only : raytracing_parameters use gray_params, only : raytracing_parameters
use const_and_precisions, only : half,two use const_and_precisions, only : two
implicit none implicit none
type(raytracing_parameters), intent(inout) :: rtrparam type(raytracing_parameters), intent(inout) :: rtrparam
real(wp_), dimension(:,:), intent(out), pointer :: ywork,ypwork, & real(wp_), dimension(:,:), intent(out), pointer :: ywork,ypwork, &
gri,psjki,ppabs,ccci gri,psjki,ppabs,ccci
real(wp_), dimension(:,:,:), intent(out), pointer :: xc,du1,ggri real(wp_), dimension(:,:,:), intent(out), pointer :: xc,du1,ggri
real(wp_), dimension(:), intent(out), pointer :: tau0,alphaabs0, & real(wp_), dimension(:), intent(out), pointer :: tau0,alphaabs0, &
dids0,ccci0,p0jk dpds,dids0,ccci0,p0jk
complex(wp_), dimension(:), intent(out), pointer :: ext, eyt complex(wp_), dimension(:), intent(out), pointer :: ext, eyt
integer, dimension(:), intent(out), pointer :: iiv integer, dimension(:), intent(out), pointer :: iiv
integer :: jray1 integer :: jray1
dst = rtrparam%dst dst = rtrparam%dst
h = dst
hh = h*half
h6 = h/6.0_wp_
nrayr = rtrparam%nrayr nrayr = rtrparam%nrayr
nrayth = rtrparam%nrayth nrayth = rtrparam%nrayth
rwmax = rtrparam%rwmax rwmax = rtrparam%rwmax
@ -56,7 +52,7 @@ contains
! yp = dy/dt, ! yp = dy/dt,
! etc. ! etc.
call alloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, & call alloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, &
tau0,alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv) tau0,alphaabs0,dpds,dids0,ccci0,p0jk,ext,eyt,iiv)
end subroutine init_btr end subroutine init_btr
@ -170,36 +166,36 @@ contains
subroutine alloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, & subroutine alloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, &
tau0,alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv) tau0,alphaabs0,dpds,dids0,ccci0,p0jk,ext,eyt,iiv)
implicit none implicit none
real(wp_), dimension(:,:), intent(out), pointer :: ywork,ypwork, & real(wp_), dimension(:,:), intent(out), pointer :: ywork,ypwork, &
gri,psjki,ppabs,ccci gri,psjki,ppabs,ccci
real(wp_), dimension(:,:,:), intent(out), pointer :: xc,du1,ggri real(wp_), dimension(:,:,:), intent(out), pointer :: xc,du1,ggri
real(wp_), dimension(:), intent(out), pointer :: tau0,alphaabs0, & real(wp_), dimension(:), intent(out), pointer :: tau0,alphaabs0, &
dids0,ccci0,p0jk dpds,dids0,ccci0,p0jk
complex(wp_), dimension(:), intent(out), pointer :: ext, eyt complex(wp_), dimension(:), intent(out), pointer :: ext, eyt
integer, dimension(:), intent(out), pointer :: iiv integer, dimension(:), intent(out), pointer :: iiv
call dealloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, & call dealloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, &
tau0,alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv) tau0,alphaabs0,dpds,dids0,ccci0,p0jk,ext,eyt,iiv)
allocate(ywork(6,nray), ypwork(6,nray), gri(3,nray), ggri(3,3,nray), & allocate(ywork(6,nray), ypwork(6,nray), gri(3,nray), ggri(3,3,nray), &
xc(3,nrayth,nrayr), du1(3,nrayth,nrayr), & xc(3,nrayth,nrayr), du1(3,nrayth,nrayr), &
psjki(nray,nstep), ppabs(nray,nstep), ccci(nray,nstep), & psjki(nray,nstep), ppabs(nray,nstep), ccci(nray,nstep), &
tau0(nray), alphaabs0(nray), dids0(nray), ccci0(nray), & tau0(nray), alphaabs0(nray), dpds(nstep), dids0(nray), &
p0jk(nray), ext(nray), eyt(nray), iiv(nray)) ccci0(nray), p0jk(nray), ext(nray), eyt(nray), iiv(nray))
end subroutine alloc_beam end subroutine alloc_beam
subroutine dealloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, & subroutine dealloc_beam(ywork,ypwork,xc,du1,gri,ggri,psjki,ppabs,ccci, &
tau0,alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv) tau0,alphaabs0,dpds,dids0,ccci0,p0jk,ext,eyt,iiv)
implicit none implicit none
real(wp_), dimension(:,:), intent(out), pointer :: ywork,ypwork, & real(wp_), dimension(:,:), intent(out), pointer :: ywork,ypwork, &
gri,psjki,ppabs,ccci gri,psjki,ppabs,ccci
real(wp_), dimension(:,:,:), intent(out), pointer :: xc,du1,ggri real(wp_), dimension(:,:,:), intent(out), pointer :: xc,du1,ggri
real(wp_), dimension(:), intent(out), pointer :: tau0,alphaabs0, & real(wp_), dimension(:), intent(out), pointer :: tau0,alphaabs0, &
dids0,ccci0,p0jk dpds,dids0,ccci0,p0jk
complex(wp_), dimension(:), intent(out), pointer :: ext, eyt complex(wp_), dimension(:), intent(out), pointer :: ext, eyt
integer, dimension(:), intent(out), pointer :: iiv integer, dimension(:), intent(out), pointer :: iiv
@ -214,6 +210,7 @@ contains
if (associated(ccci)) deallocate(ccci) if (associated(ccci)) deallocate(ccci)
if (associated(tau0)) deallocate(tau0) if (associated(tau0)) deallocate(tau0)
if (associated(alphaabs0)) deallocate(alphaabs0) if (associated(alphaabs0)) deallocate(alphaabs0)
if (associated(dpds)) deallocate(dpds)
if (associated(dids0)) deallocate(dids0) if (associated(dids0)) deallocate(dids0)
if (associated(ccci0)) deallocate(ccci0) if (associated(ccci0)) deallocate(ccci0)
if (associated(p0jk)) deallocate(p0jk) if (associated(p0jk)) deallocate(p0jk)

View File

@ -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 = dAdYdY/dR, assuming the magnetic field varies
! solely as B(R) BR/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)

View File

@ -12,6 +12,7 @@ module gray_cli
type cli_options type cli_options
! Switches ! Switches
logical :: quiet logical :: quiet
logical :: server
! Files ! Files
character(len=:), allocatable :: output_dir character(len=:), allocatable :: output_dir
character(len=:), allocatable :: params_file character(len=:), allocatable :: params_file
@ -46,6 +47,7 @@ contains
print '(a)', ' -v, --verbose print more information messages;' print '(a)', ' -v, --verbose print more information messages;'
print '(a)', ' repeating -v increase the log verbosity' print '(a)', ' repeating -v increase the log verbosity'
print '(a)', ' -q, --quiet suppress all non-critical messages' print '(a)', ' -q, --quiet suppress all non-critical messages'
print '(a)', ' -S, --server run in server mode: handle requests from stdin'
print '(a)', ' -o, --output-dir DIR specify where to write the output files' print '(a)', ' -o, --output-dir DIR specify where to write the output files'
print '(a)', ' (default: current directory)' print '(a)', ' (default: current directory)'
print '(a)', ' -p, --params-file FILE set the (legacy) parameters file' print '(a)', ' -p, --params-file FILE set the (legacy) parameters file'
@ -90,6 +92,7 @@ contains
print '(a)' , 'switches:' print '(a)' , 'switches:'
print '(a,l)' , ' - quiet: ' , opts%quiet print '(a,l)' , ' - quiet: ' , opts%quiet
print '(a,l)' , ' - server: ' , opts%server
print '(a)' , 'files:' print '(a)' , 'files:'
print '(a,a)' , ' output-dir: ' , opts%output_dir print '(a,a)' , ' output-dir: ' , opts%output_dir
print '(a,a)' , ' param-file: ' , opts%params_file print '(a,a)' , ' param-file: ' , opts%params_file
@ -119,6 +122,7 @@ contains
! Default option values ! Default option values
opts%verbose = WARNING opts%verbose = WARNING
opts%quiet = .false. opts%quiet = .false.
opts%server = .false.
opts%params_file = 'gray_params.data' opts%params_file = 'gray_params.data'
opts%units = [ucenr, usumm] opts%units = [ucenr, usumm]
@ -147,6 +151,9 @@ contains
case ('-q', '--quiet') case ('-q', '--quiet')
opts%quiet = .true. opts%quiet = .true.
case ('-S', '--server')
opts%server = .true.
case ('-o', '--output-dir') case ('-o', '--output-dir')
call get_next_command(i, opts%output_dir) call get_next_command(i, opts%output_dir)

View File

@ -5,12 +5,24 @@ module gray_core
implicit none implicit none
abstract interface
function rhs_function(y, e) result(f)
! 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_
real(wp_), intent(in) :: y(6) ! variable y
real(wp_), intent(inout), optional :: e ! error estimator
real(wp_) :: f(6) ! f(y)
end function
end interface
contains contains
subroutine gray_main(params, data, results, error, rhout) subroutine gray_main(params, data, results, error, rhout)
use const_and_precisions, only : zero, one, degree, comp_tiny use const_and_precisions, only : zero, one, degree, comp_tiny
use coreprofiles, only : temp, fzeff use coreprofiles, only : temp, fzeff
use dispersion, only : expinit use dispersion, only : expinit
use polarization, only : ellipse_to_field
use gray_params, only : gray_parameters, gray_data, gray_results, & use gray_params, only : gray_parameters, gray_data, gray_results, &
print_parameters print_parameters
use beams, only : xgygcoeff, launchangles2n use beams, only : xgygcoeff, launchangles2n
@ -41,6 +53,7 @@ contains
integer, intent(out) :: error integer, intent(out) :: error
! local variables ! local variables
! taucr: max τ before considering a ray fully absorbed
real(wp_), parameter :: taucr = 12._wp_, etaucr = exp(-taucr) real(wp_), parameter :: taucr = 12._wp_, etaucr = exp(-taucr)
character, dimension(2), parameter :: mode=['O','X'] character, dimension(2), parameter :: mode=['O','X']
@ -52,7 +65,7 @@ contains
real(wp_) :: rhotp,drhotp,rhotj,drhotj,dpdvmx,jphimx,ratjamx,ratjbmx real(wp_) :: rhotp,drhotp,rhotj,drhotj,dpdvmx,jphimx,ratjamx,ratjbmx
real(wp_) :: pabs_beam,icd_beam,cpl_beam1,cpl_beam2,cpl_cbeam1,cpl_cbeam2 real(wp_) :: pabs_beam,icd_beam,cpl_beam1,cpl_beam2,cpl_cbeam1,cpl_cbeam2
real(wp_), dimension(2) :: pabs_pass,icd_pass,cpl,cpl0 real(wp_), dimension(2) :: pabs_pass,icd_pass,cpl
real(wp_), dimension(3) :: xv,anv0,anv,bv,derxg real(wp_), dimension(3) :: xv,anv0,anv,bv,derxg
! Ray variables ! Ray variables
@ -62,8 +75,8 @@ contains
! i: integration step, jk: global ray index ! i: integration step, jk: global ray index
integer :: i, jk integer :: i, jk
integer :: iox,nharm,nhf,nnd,iokhawa,ierrn,ierrhcd,index_rt integer :: iox,nharm,nhf,nnd,iokhawa,ierrn,ierrhcd, index_rt, parent_index_rt
integer :: ip,ib,iopmin,ipar,iO integer :: ip,ib,iopmin,ipar,child_index_rt
integer :: igrad_b,istop_pass,nbeam_pass,nlim integer :: igrad_b,istop_pass,nbeam_pass,nlim
logical :: ins_pl,ins_wl,ent_pl,ext_pl,ent_wl,ext_wl,iboff logical :: ins_pl,ins_wl,ent_pl,ext_pl,ent_wl,ext_wl,iboff
@ -71,12 +84,14 @@ contains
real(wp_), dimension(:,:), pointer :: psjki=>null(),ppabs=>null(),ccci=>null() real(wp_), dimension(:,:), pointer :: psjki=>null(),ppabs=>null(),ccci=>null()
real(wp_), dimension(:,:), pointer :: taus=>null(),stnext=>null(), & real(wp_), dimension(:,:), pointer :: taus=>null(),stnext=>null(), &
yw0=>null(),ypw0=>null(),cpls=>null() yw0=>null(),ypw0=>null(),cpls=>null()
! Note: dpds is only used in realtime mode to compute the power absorption peak
real(wp_), dimension(:), pointer :: p0ray=>null(),tau0=>null(),alphaabs0=>null(), & real(wp_), dimension(:), pointer :: p0ray=>null(),tau0=>null(),alphaabs0=>null(), &
dids0=>null(),ccci0=>null(),tau1=>null(),etau1=>null(),cpl1=>null(),lgcpl1=>null() dpds=>null(), dids0=>null(),ccci0=>null(),tau1=>null(),etau1=>null(),cpl1=>null(), &
lgcpl1=>null()
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()
@ -98,54 +113,67 @@ contains
! Initialise the ray variables (beamtracing) ! Initialise the ray variables (beamtracing)
call init_btr(params%raytracing, yw, ypw, xc, du1, gri, ggri, psjki, ppabs, ccci, & call init_btr(params%raytracing, yw, ypw, xc, du1, gri, ggri, psjki, ppabs, ccci, &
tau0, alphaabs0, dids0, ccci0, p0jk, ext, eyt, iiv) tau0, alphaabs0, dpds, dids0, ccci0, p0jk, ext, eyt, iiv)
! Initialise the dispersion module ! Initialise the dispersion module
if(params%ecrh_cd%iwarm > 1) call expinit if (params%ecrh_cd%iwarm > 1) call expinit
! Initialise the magsurf_data module ! In realtime mode the raytracing is stopped as soon as
call flux_average ! requires frhotor for dadrhot,dvdrhot ! possible and all these extra features are unnecessary
if (params%raytracing%realtime) then
nnd = 0
else
! Initialise the magsurf_data module
! Note: 1. needed for computing flux surface averages (dP/dV, etc.)
! 2. requires frhotor for dadrhot, dvdrhot
call flux_average
! Initialise the output profiles ! Initialise output profiles module
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, & ! Allocate memory for the results...
stv, p0ray, taus, tau1, etau1, cpls, cpl1, lgcpl1, jphi_beam, & allocate(results%dpdv(params%output%nrho))
pins_beam, currins_beam, dpdv_beam, jcd_beam, psipv, chipv) allocate(results%jcd(params%output%nrho))
! Allocate memory for the results... ! ...and initialise them
allocate(results%dpdv(params%output%nrho)) results%pabs = zero
allocate(results%jcd(params%output%nrho)) results%icd = zero
results%dpdv = zero
results%jcd = zero
end if
! Initialise multipass module
call alloc_multipass(nnd, 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)
! ...and initialise them
results%pabs = zero
results%icd = zero
results%dpdv = zero
results%jcd = zero
! ========= set environment END ========= ! ========= set environment END =========
! ======== pre-proc prints BEGIN ======== ! ======== pre-proc prints BEGIN ========
call print_headers(params) if (.not. params%raytracing%realtime) then
call print_headers(params)
! print ψ surface for q=1.5 and q=2 on file and log psi,rhot,rhop ! print ψ surface for q=1.5 and q=2 on file and log psi,rhot,rhop
call print_surfq([1.5_wp_, 2.0_wp_]) call print_surfq([1.5_wp_, 2.0_wp_])
! print initial position ! print initial position
write (msg, '("initial position:",3(x,g0.3))') params%antenna%pos write (msg, '("initial position:",3(x,g0.3))') params%antenna%pos
call log_info(msg, mod='gray_core', proc='gray_main') call log_info(msg, mod='gray_core', proc='gray_main')
write (msg, '("initial direction:",2(x,a,"=",g0.2))') & write (msg, '("initial direction:",2(x,a,"=",g0.2))') &
'α', params%antenna%alpha, 'β', params%antenna%beta 'α', params%antenna%alpha, 'β', params%antenna%beta
call log_info(msg, mod='gray_core', proc='gray_main') call log_info(msg, mod='gray_core', proc='gray_main')
! print Btot=Bres ! print Btot=Bres
! print ne, Te, q, Jphi versus psi, rhop, rhot ! print ne, Te, q, Jphi versus psi, rhop, rhot
call print_bres(bres) call print_bres(bres)
call print_prof(params%profiles) call print_prof(params%profiles)
call print_maps(bres, xgcn, & call print_maps(bres, xgcn, &
norm2(params%antenna%pos(1:2)) * 0.01_wp_, & norm2(params%antenna%pos(1:2)) * 0.01_wp_, &
sin(params%antenna%beta*degree)) sin(params%antenna%beta*degree))
end if
! ========= pre-proc prints END ========= ! ========= pre-proc prints END =========
! =========== main loop BEGIN =========== ! =========== main loop BEGIN ===========
@ -153,21 +181,15 @@ contains
iroff,yynext,yypnext,yw0,ypw0, & iroff,yynext,yypnext,yw0,ypw0, &
stnext,p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,psipv,chipv) stnext,p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,psipv,chipv)
if(params%raytracing%ipol == 0) then
if(params%antenna%iox == 2) then ! only X mode on 1st pass
cpl0 = [zero, one]
else ! only O mode on 1st pass
cpl0 = [one, zero]
end if
end if
sox=1 ! mode inverted for each beam sox=1 ! mode inverted for each beam
iox=2 ! start with O: sox=-1, iox=1 iox=2 ! start with O: sox=-1, iox=1
psipol = params%antenna%psi
chipol = params%antenna%chi
call pweight(params%antenna%power, p0jk) call pweight(params%antenna%power, p0jk)
! Set original polarisation
psipv(0) = params%antenna%psi
chipv(0) = params%antenna%chi
nbeam_pass=1 ! max n of beam per pass nbeam_pass=1 ! max n of beam per pass
index_rt=0 ! global beam index: 1,O 2,X 1st pass index_rt=0 ! global beam index: 1,O 2,X 1st pass
! | | | | ! | | | |
@ -195,12 +217,12 @@ contains
sox = -sox ! invert mode sox = -sox ! invert mode
iox = 3-iox ! O-mode at ip=1,ib=1 iox = 3-iox ! O-mode at ip=1,ib=1
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) child_index_rt = 2*index_rt + 1 ! * index_rt of O-mode child beam
parent_index_rt = ceiling(index_rt / 2.0_wp_) - 1 ! * index_rt of parent beam
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')
@ -211,7 +233,7 @@ contains
cycle cycle
end if end if
call vectinit(psjki,ppabs,ccci,tau0,alphaabs0,dids0,ccci0,iiv) call vectinit(psjki,ppabs,ccci,tau0,alphaabs0,dpds,dids0,ccci0,iiv)
if(ip == 1) then ! 1st pass if(ip == 1) then ! 1st pass
igrad_b = params%raytracing%igrad ! * input value, igrad_b=0 from 2nd pass igrad_b = params%raytracing%igrad ! * input value, igrad_b=0 from 2nd pass
@ -222,17 +244,17 @@ contains
lgcpl1 = zero lgcpl1 = zero
p0ray = p0jk ! * initial beam power p0ray = p0jk ! * initial beam power
call ic_gb(params, anv0, ak0, yw, ypw, & ! * initial conditions call ic_gb(params, anv0, ak0, yw, ypw, xc, du1, gri, ggri, index_rt) ! * initial conditions
xc, du1, gri, ggri, index_rt)
call set_pol(yw, bres, sox, params%raytracing%ipol, & ! * initial polarization
psipol, chipol, ext, eyt)
do jk=1,params%raytracing%nray do jk=1,params%raytracing%nray
zzm = yw(3,jk)*0.01_wp_ zzm = yw(3,jk)*0.01_wp_
rrm = sqrt(yw(1,jk)*yw(1,jk)+yw(2,jk)*yw(2,jk))*0.01_wp_ rrm = sqrt(yw(1,jk)*yw(1,jk)+yw(2,jk)*yw(2,jk))*0.01_wp_
if(inside(data%equilibrium%rlim, data%equilibrium%zlim, & ! Note: `inside` call is expensive and can be skipped in realtime
nlim, rrm, zzm)) then ! * start propagation in/outside vessel? if (params%raytracing%realtime) then
iow(jk) = 1
else if (inside(data%equilibrium%rlim, data%equilibrium%zlim, & ! * start propagation in/outside vessel?
nlim, rrm, zzm)) then
iow(jk) = 1 ! + inside iow(jk) = 1 ! + inside
else else
iow(jk) = 0 ! + outside iow(jk) = 0 ! + outside
@ -264,8 +286,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 rkstep(sox,bres,xgcn,yw(:,jk),ypw(:,jk),gri(:,jk),ggri(:,:,jk),igrad_b) y=yw(:, jk), yp=ypw(:, jk), f=rhs, &
h=dst(jk), method=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)
@ -293,9 +318,13 @@ contains
zzm = xv(3)*0.01_wp_ zzm = xv(3)*0.01_wp_
rrm = sqrt(xv(1)*xv(1)+xv(2)*xv(2))*0.01_wp_ rrm = sqrt(xv(1)*xv(1)+xv(2)*xv(2))*0.01_wp_
! Note: `inside` call is expensive and can be skipped in realtime
if (params%raytracing%realtime) then
ins_wl = .true.
else
ins_wl = inside(data%equilibrium%rlim, data%equilibrium%zlim, nlim,rrm,zzm) ! in/out vessel?
end if
ins_pl = (psinv>=zero .and. psinv<params%profiles%psnbnd) ! in/out plasma? ins_pl = (psinv>=zero .and. psinv<params%profiles%psnbnd) ! in/out plasma?
ins_wl = inside(data%equilibrium%rlim, data%equilibrium%zlim, &
nlim,rrm,zzm) ! in/out vessel?
ent_pl = (mod(iop(jk),2) == 0 .and. ins_pl) ! enter plasma ent_pl = (mod(iop(jk),2) == 0 .and. ins_pl) ! enter plasma
ext_pl = (mod(iop(jk),2) == 1 .and. .not.ins_pl) ! exit plasma ext_pl = (mod(iop(jk),2) == 1 .and. .not.ins_pl) ! exit plasma
ent_wl = (mod(iow(jk),2) == 0 .and. ins_wl) ! enter vessel ent_wl = (mod(iow(jk),2) == 0 .and. ins_wl) ! enter vessel
@ -304,14 +333,14 @@ contains
if(ent_pl) then ! ray enters plasma if(ent_pl) then ! ray enters plasma
write (msg, '(" ray ",g0," entered plasma (",g0," steps)")') jk, i write (msg, '(" ray ",g0," entered plasma (",g0," steps)")') jk, i
call log_debug(msg, mod='gray_core', proc='gray_main') call log_debug(msg, mod='gray_core', proc='gray_main')
call plasma_in(jk,xv,anv,bres,sox,cpl,psipol,chipol,iop,ext,eyt) call ellipse_to_field(psipv(parent_index_rt), chipv(parent_index_rt), & ! compute polarisation and couplings
ext, eyt)
call plasma_in(jk, xv, anv, bres, sox, cpl, psipol, chipol, iop, ext, eyt, &
perfect=params%raytracing%ipol == 0 .and. params%antenna%iox == iox .and. ip == 1)
if(iop(jk) == 1 .and. ip==1) then ! * 1st entrance on 1st pass (ray hasn't entered in plasma yet) => continue current pass if(iop(jk) == 1 .and. ip==1) then ! * 1st entrance on 1st pass (ray hasn't entered in plasma yet) => continue current pass
if(params%raytracing%ipol == 0) then ! + IF single mode propagation if(cpl(iox) < etaucr) then ! + IF low coupled power for current mode => de-activate derived rays
cpl = cpl0
p0ray(jk) = p0ray(jk)*cpl(iox)
else if(cpl(iox) < etaucr) then ! + ELSE IF low coupled power for current mode => de-activate derived rays
call turnoffray(jk,ip+1,2*ib+2-iox,iroff) call turnoffray(jk,ip+1,2*ib+2-iox,iroff)
iwait(jk) = .true. ! . stop advancement and H&CD computation for current ray iwait(jk) = .true. ! . stop advancement and H&CD computation for current ray
if(cpl(iox).le.comp_tiny) cpl(iox)=etaucr if(cpl(iox).le.comp_tiny) cpl(iox)=etaucr
@ -324,6 +353,9 @@ contains
write (msg,'(" 1st pass - central ray (",a1,"-mode) c=",g0.4)') & write (msg,'(" 1st pass - central ray (",a1,"-mode) c=",g0.4)') &
mode(iox), cpl(iox) mode(iox), cpl(iox)
call log_info(msg, mod='gray_core', proc='gray_main') call log_info(msg, mod='gray_core', proc='gray_main')
write (msg,'(" polarisation: ψ=",g0.5,"°, χ=",g0.5,"°")') &
psipol, chipol
call log_debug(msg, mod='gray_core', proc='gray_main')
psipv(index_rt) = psipol ! + polarization angles at plasma boundary for central ray psipv(index_rt) = psipol ! + polarization angles at plasma boundary for central ray
chipv(index_rt) = chipol chipv(index_rt) = chipol
end if end if
@ -335,7 +367,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)
@ -346,13 +378,13 @@ contains
if(cpl(2).le.comp_tiny) cpl(2)=etaucr if(cpl(2).le.comp_tiny) cpl(2)=etaucr
end if end if
taus(jk,iO:iO+1) = tau1(jk) + tau0(jk) ! . starting tau for next O-mode pass taus(jk,child_index_rt:child_index_rt+1) = tau1(jk) + tau0(jk) ! . starting tau for next O-mode pass
cpls(jk,iO) = cpl1(jk) * cpl(1) ! . cumulative coupling for next O-mode pass cpls(jk,child_index_rt) = cpl1(jk) * cpl(1) ! . cumulative coupling for next O-mode pass
cpls(jk,iO+1) = cpl1(jk) * cpl(2) ! . cumulative coupling for next X-mode pass cpls(jk,child_index_rt+1) = cpl1(jk) * cpl(2) ! . cumulative coupling for next X-mode pass
if(jk == 1) then ! . polarization angles at plasma boundary for central ray if(jk == 1) then ! . polarization angles at plasma boundary for central ray
psipv(iO:iO+1) = psipol psipv(child_index_rt:child_index_rt+1) = psipol
chipv(iO:iO+1) = chipol chipv(child_index_rt:child_index_rt+1) = chipol
end if end if
else ! * 1st entrance on 2nd+ pass (ray hasn't entered in plasma since end of previous pass) => continue current pass else ! * 1st entrance on 2nd+ pass (ray hasn't entered in plasma since end of previous pass) => continue current pass
cpl = [zero, zero] cpl = [zero, zero]
@ -394,7 +426,8 @@ contains
yypnext(:,jk,index_rt) = ypw(:,jk) ! for next pass = reflection point yypnext(:,jk,index_rt) = ypw(:,jk) ! for next pass = reflection point
stnext(jk,index_rt) = stv(jk) ! . starting step for next pass = step after reflection stnext(jk,index_rt) = stv(jk) ! . starting step for next pass = step after reflection
call plasma_in(jk,xv,anv,bres,sox,cpl,psipol,chipol,iop,ext,eyt) ! . ray re-enters plasma after reflection call plasma_in(jk, xv, anv, bres, sox, cpl, psipol, chipol, & ! . ray re-enters plasma after reflection
iop, ext, eyt, perfect=.false.)
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)
@ -405,13 +438,13 @@ contains
if(cpl(2).le.comp_tiny) cpl(2)=etaucr if(cpl(2).le.comp_tiny) cpl(2)=etaucr
end if end if
taus(jk,iO:iO+1) = tau1(jk) + tau0(jk) ! . starting tau for next O-mode pass taus(jk,child_index_rt:child_index_rt+1) = tau1(jk) + tau0(jk) ! . starting tau for next O-mode pass
cpls(jk,iO) = cpl1(jk) * cpl(1) ! . cumulative coupling for next O-mode pass cpls(jk,child_index_rt) = cpl1(jk) * cpl(1) ! . cumulative coupling for next O-mode pass
cpls(jk,iO+1) = cpl1(jk) * cpl(2) ! . cumulative coupling for next X-mode pass cpls(jk,child_index_rt+1) = cpl1(jk) * cpl(2) ! . cumulative coupling for next X-mode pass
if(jk == 1) then ! + polarization angles at plasma boundary for central ray if(jk == 1) then ! + polarization angles at plasma boundary for central ray
psipv(iO:iO+1) = psipol psipv(child_index_rt:child_index_rt+1) = psipol
chipv(iO:iO+1) = chipol chipv(child_index_rt:child_index_rt+1) = chipol
end if end if
end if end if
end if end if
@ -457,15 +490,16 @@ 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 = Pexp(-τ) pow = p0ray(jk) * exp(-tau) ! residual power: P = Pexp(-τ)
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/dPdP/ds = dI/dPPα dpds(i) = pow * alpha ! power density: dP/ds = Pα
dids = didp * dpds(i) ! current driven: dI/ds = dI/dPdP/ds
! current: I = dI/dsds using the trapezoid rule ! current: I = dI/dsds 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
@ -491,6 +525,38 @@ contains
end do end do
end if end if
if (params%raytracing%realtime) then
! Check whether we are past the absorption peak
block
logical :: past_peak
integer :: tail
! We assume so if dP/ds has been decreasing in the last 8 steps
tail = max(2, i-8)
past_peak = i > 8 .and. all(dpds(tail:i) - dpds(tail-1:i-1) < 0)
if (past_peak .or. pow <= 0.1_wp_*p0ray(1)) then
! Compute the approximate position of the absorption peak
block
use utils, only : vmax, parabola_vertex
real(wp_) :: power, peak(2)
integer :: index
! Find maximum in dP/ds
call vmax(dpds, i, power, index)
! Interpolate the peak with a parabola
peak = parabola_vertex(psjki(1, index - 1:index + 1), &
dpds(index - 1:index + 1))
results%rho_peak = sqrt(peak(1))
end block
! Stop propagation loop
exit
end if
end block
end if
! print ray positions for j=nrayr in local reference system ! print ray positions for j=nrayr in local reference system
if(mod(i,params%output%istpr) == 0) then if(mod(i,params%output%istpr) == 0) then
if(params%raytracing%nray > 1 .and. all(.not.iwait)) & if(params%raytracing%nray > 1 .and. all(.not.iwait)) &
@ -521,20 +587,23 @@ contains
icd_beam = sum(ccci(:,i)) icd_beam = sum(ccci(:,i))
call vmaxmin(tau0,params%raytracing%nray,taumn,taumx) ! taumn,taumx for print call vmaxmin(tau0,params%raytracing%nray,taumn,taumx) ! taumn,taumx for print
! compute power and current density profiles for all rays if (.not. params%raytracing%realtime) then
call spec(psjki,ppabs,ccci,iiv,pabs_beam,icd_beam,dpdv_beam,jphi_beam,jcd_beam, & ! Compute power and current density profiles for all rays
pins_beam,currins_beam) call spec(psjki, ppabs, ccci, iiv, pabs_beam, icd_beam, &
dpdv_beam, jphi_beam, jcd_beam, pins_beam, currins_beam)
end if
pabs_pass(iox) = pabs_pass(iox) + pabs_beam ! 0D results for current pass, sum on O/X mode beams pabs_pass(iox) = pabs_pass(iox) + pabs_beam ! 0D results for current pass, sum on O/X mode beams
icd_pass(iox) = icd_pass(iox) + icd_beam icd_pass(iox) = icd_pass(iox) + icd_beam
if(ip < params%raytracing%ipass .and. iopmin > 2) then ! not last pass AND at least one ray re-entered plasma if(ip < params%raytracing%ipass .and. iopmin > 2) then ! not last pass AND at least one ray re-entered plasma
cpl_beam1 = sum(p0ray * exp(-tau0) * cpls(:,iO)/cpl1, MASK=iop > 2) / & cpl_beam1 = sum(&
sum(p0ray * exp(-tau0), MASK=iop > 2) ! * average O-mode coupling for next beam (on active rays) p0ray * exp(-tau0) * cpls(:,child_index_rt)/cpl1, MASK=iop > 2) / &
sum(p0ray * exp(-tau0), MASK=iop > 2) ! * average O-mode coupling for next beam (on active rays)
cpl_beam2 = one - cpl_beam1 ! * average X-mode coupling for next beam cpl_beam2 = one - cpl_beam1 ! * average X-mode coupling for next beam
if(iop(1) > 2) then ! * central ray O/X-mode coupling for next beam if(iop(1) > 2) then ! * central ray O/X-mode coupling for next beam
cpl_cbeam1 = cpls(1,iO)/cpl1(1) cpl_cbeam1 = cpls(1,child_index_rt)/cpl1(1)
cpl_cbeam2 = one - cpl_cbeam1 cpl_cbeam2 = one - cpl_cbeam1
end if end if
else ! last pass OR no ray re-entered plasma else ! last pass OR no ray re-entered plasma
@ -563,22 +632,36 @@ contains
if(iop(1) > 2) then if(iop(1) > 2) then
write(msg, '(3x,a,(g0.4,", ",g0.4))') & write(msg, '(3x,a,(g0.4,", ",g0.4))') &
'coupling [ctr ray, O/X]:', cpl_cbeam1, cpl_cbeam2 ! central ray coupling for next O/X beams 'coupling [ctr ray, O/X]:', cpl_cbeam1, cpl_cbeam2 ! central ray coupling for next O/X beams
call log_info(msg, mod='gray_core', proc='gray_main')
end if end if
end if end if
call print_pec(rhop_tab,rhot_tab,jphi_beam,jcd_beam,dpdv_beam,currins_beam, & if (.not. params%raytracing%realtime) then
pins_beam,ip) ! *print power and current density profiles for current beam call print_pec(rhop_tab, rhot_tab, jphi_beam, jcd_beam, &
dpdv_beam, currins_beam, pins_beam, ip) ! *print power and current density profiles for current beam
call postproc_profiles(pabs_beam,icd_beam,rhot_tab,dpdv_beam,jphi_beam, & call postproc_profiles(pabs_beam, icd_beam, rhot_tab, dpdv_beam, &
rhotpav,drhotpav,rhotjava,drhotjava,dpdvp,jphip,rhotp,drhotp,rhotj, & jphi_beam, rhotpav, drhotpav, rhotjava, &
drhotj,dpdvmx,jphimx,ratjamx,ratjbmx) ! *compute profiles width for current beam drhotjava, dpdvp, jphip, rhotp, drhotp, &
rhotj, drhotj, dpdvmx, jphimx, ratjamx, ratjbmx) ! *compute profiles width for current beam
call print_finals(pabs_beam,icd_beam,dpdvp,jphip,rhotpav,rhotjava, & call print_finals(pabs_beam, icd_beam, dpdvp, jphip, rhotpav, &
drhotpav,drhotjava,dpdvmx,jphimx,rhotp,rhotj,drhotp,drhotj,ratjamx, & rhotjava, drhotpav, drhotjava, dpdvmx, jphimx, &
ratjbmx,stv(1),psipv(index_rt),chipv(index_rt),index_rt,sum(p0ray), & rhotp, rhotj, drhotp, drhotj, ratjamx, ratjbmx, &
cpl_beam1,cpl_beam2) ! *print 0D results for current beam stv(1), psipv(index_rt), chipv(index_rt), &
index_rt, sum(p0ray), cpl_beam1, cpl_beam2) ! *print 0D results for current beam
end if
! ============ post-proc END ============ ! ============ post-proc END ============
! Store the accurate position of the absorption peak
if (.not. params%raytracing%realtime .and. ip == 1 .and. rhotpav /= 0) then
! Note: rho_peak is poloidal, we covert ρ_t to ρ_p
block
use equilibrium, only: frhopol
results%rho_peak = frhopol(rhotpav)
end block
end if
end do beam_loop end do beam_loop
call log_debug('beam loop end', mod='gray_core', proc='gray_main') call log_debug('beam loop end', mod='gray_core', proc='gray_main')
! ============ beam loop END ============ ! ============ beam loop END ============
@ -607,23 +690,64 @@ contains
! ========== free memory BEGIN ========== ! ========== free memory BEGIN ==========
call dealloc_surfvec call dealloc_surfvec
call dealloc_beam(yw,ypw,xc,du1,gri,ggri,psjki,ppabs,ccci,tau0, & call dealloc_beam(yw,ypw,xc,du1,gri,ggri,psjki,ppabs,ccci,tau0, &
alphaabs0,dids0,ccci0,p0jk,ext,eyt,iiv) alphaabs0,dpds,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 ===========
contains
! Functions that needs the scope of gray_main
function rhs(y, e) result(f)
! Computes the right-hand side terms of the ray equations
! To be passed to the integrator subroutine
implicit none
! function arguments
real(wp_), intent(in) :: y(6) ! (, )
real(wp_), intent(inout), optional :: e ! |Λ(, )| as an error
! result
real(wp_) :: f(6) ! (dx̅/ds, dN̅/ds)
! local variables
real(wp_) :: xg, yg
real(wp_), dimension(3) :: xv, anv, bv, derxg, deryg
real(wp_), dimension(3, 3) :: derbv
xv = y(1:3) ! position
anv = y(4:6) ! refractive index
! computes derivatives of plasma quantities: , X, Y,
! (these are needed for the next part)
call plas_deriv(xv, bres, xgcn, dens, btot, bv, derbv, &
xg, yg, derxg, deryg)
! computes derivatives of dispersion relation: Λ/, Λ/
call disp_deriv(anv, sox, xg, yg, derxg, deryg, bv, derbv, &
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 |Λ(, )| -kX, instead of zero.
if (present(e)) then
e = abs(e + 4.15e-4 * xg)
end if
end function rhs
end subroutine gray_main end subroutine gray_main
subroutine vectinit(psjki,ppabs,ccci,tau0,alphaabs0,dids0,ccci0,iiv) subroutine vectinit(psjki,ppabs,ccci,tau0,alphaabs0,dpds,dids0,ccci0,iiv)
use const_and_precisions, only : zero use const_and_precisions, only : zero
implicit none implicit none
! arguments ! arguments
real(wp_), dimension(:,:), intent(out) :: psjki,ppabs,ccci real(wp_), dimension(:,:), intent(out) :: psjki,ppabs,ccci
real(wp_), dimension(:), intent(out) :: tau0,alphaabs0,dids0,ccci0 real(wp_), dimension(:), intent(out) :: tau0,alphaabs0,dpds,dids0,ccci0
integer, dimension(:), intent(out) :: iiv integer, dimension(:), intent(out) :: iiv
!! common/external functions/variables !! common/external functions/variables
! integer :: jclosest ! integer :: jclosest
@ -640,6 +764,7 @@ contains
ccci = zero ccci = zero
tau0 = zero tau0 = zero
alphaabs0 = zero alphaabs0 = zero
dpds = zero
dids0 = zero dids0 = zero
ccci0 = zero ccci0 = zero
iiv = 1 iiv = 1
@ -965,56 +1090,209 @@ contains
end subroutine ic_gb end subroutine ic_gb
function integrator(y, yp, f, h, method) result(y1)
! Integrator of the raytracing equations
subroutine rkstep(sox,bres,xgcn,y,yp,dgr,ddgr,igrad)
! Runge-Kutta integrator
! use gray_params, only : igrad
use beamdata, only : h,hh,h6
implicit none implicit none
real(wp_), intent(in) :: bres,xgcn
real(wp_), dimension(6), intent(inout) :: y
real(wp_), dimension(6), intent(in) :: yp
real(wp_), dimension(3), intent(in) :: dgr
real(wp_), dimension(3,3), intent(in) :: ddgr
integer, intent(in) :: igrad,sox
real(wp_), dimension(6) :: yy,fk1,fk2,fk3,fk4 real(wp_), dimension(6), intent(in) :: y ! = (, )
real(wp_), dimension(6), intent(in) :: yp ! ˙ = f()
procedure(rhs_function) :: f ! dy̅/dσ = ()
real(wp_), intent(in) :: h ! step size
integer, intent(in) :: method ! kind of integrator
real(wp_), dimension(6) :: y1 ! the new
fk1 = yp ! local variables
yy = y + fk1*hh real(wp_), dimension(6) :: k1, k2, k3, k4
call rhs(sox,bres,xgcn,yy,dgr,ddgr,fk2,igrad)
yy = y + fk2*hh
call rhs(sox,bres,xgcn,yy,dgr,ddgr,fk3,igrad)
yy = y + fk3*h
call rhs(sox,bres,xgcn,yy,dgr,ddgr,fk4,igrad)
y = y + h6*(fk1 + 2*fk2 + 2*fk3 + fk4) select case (method)
end subroutine rkstep case (0)
! Explicit Euler (1 order)
y1 = y + yp*h
case (1)
! Semi-implicit Euler (1 order, symplectic)
! P = p - H/q(q, p)h
! Q = q + H/p(q, P)h
k1 = h*yp
y1(1:3) = y(1:3)
y1(4:6) = y(4:6) + k1(4:6)
k2 = h*f(y1)
y1(1:3) = y1(1:3) + k2(1:3)
case (2)
! Velocity Verlet (2 order, symplectic)
! p(n+½) = p(n) - H/q(q(n), p(n))h/2
! 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
k1 = h*yp
y1(1:3) = y(1:3)
y1(4:6) = y(4:6) + k1(4:6)/2
k2 = h*f(y1)
y1(1:3) = y(1:3) + k2(1:3)
k3 = h*f(y1)
y1(4:6) = y1(4:6) + k3(4:6)/2
case (3)
! 2-stage Runge-Kutta (2 order)
k1 = h*yp
k2 = h*f(y + k1/2)
y1 = y + k2
case default
! 4-stage Runge-Kutta (4 order)
k1 = h*yp
k2 = h*f(y + k1/2)
k3 = h*f(y + k2/2)
k4 = h*f(y + k3)
y1 = y + k1/6 + k2/3 + k3/3 + k4/6
end select
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:
! |Λ(, )| 0.
use logger, only : log_debug, log_warning
subroutine rhs(sox,bres,xgcn,y,dgr,ddgr,dery,igrad)
! Compute right-hand side terms of the ray equations (dery)
! used in R-K integrator
implicit none implicit none
! arguments
real(wp_), dimension(6), intent(in) :: y
real(wp_), intent(in) :: bres,xgcn
real(wp_), dimension(3), intent(in) :: dgr
real(wp_), dimension(3,3), intent(in) :: ddgr
real(wp_), dimension(6), intent(out) :: dery
integer, intent(in) :: igrad,sox
! local variables
real(wp_) :: dens,btot,xg,yg
real(wp_), dimension(3) :: xv,anv,bv,derxg,deryg
real(wp_), dimension(3,3) :: derbv
xv = y(1:3) ! subroutine arguments
call plas_deriv(xv,bres,xgcn,dens,btot,bv,derbv,xg,yg,derxg,deryg) real(wp_), dimension(6), intent(inout) :: y ! = (, )
anv = y(4:6) real(wp_), dimension(6), intent(in) :: yp ! ˙ = (dx̅/dσ, dN̅/dσ)
call disp_deriv(anv,sox,xg,yg,derxg,deryg,bv,derbv,dgr,ddgr,igrad,dery) procedure(rhs_function) :: f ! dy̅/dσ = ()
end subroutine rhs 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 , refractive index , 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
! 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 =
! 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 = Δssinθ Δ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, &
@ -1718,7 +1996,7 @@ contains
real(wp_), intent(in) :: psinv real(wp_), intent(in) :: psinv
! CMA diagram variables: X=(ω_pe/ω)², Y=ω_ce/ω ! CMA diagram variables: X=(ω_pe/ω)², Y=ω_ce/ω
real(wp_), intent(in) :: X, Y real(wp_), intent(in) :: X, Y
! densityity [10¹ m³], temperature [keV] ! density [10¹ m³], temperature [keV]
real(wp_), intent(in) :: density, temperature real(wp_), intent(in) :: density, temperature
! vacuum wavenumber k=ω/c, resonant B field ! vacuum wavenumber k=ω/c, resonant B field
real(wp_), intent(in) :: k0, Bres real(wp_), intent(in) :: k0, Bres
@ -1782,28 +2060,48 @@ contains
end if end if
end if end if
! Compute α from the solution of the dispersion relation if (params%iwarm < 4) then
! The absoption coefficient is defined as ! Compute α from the solution of the dispersion relation
! accurate: block
! α = 2 Im() ! Compute α from the solution of the dispersion relation
! ! The absoption coefficient is defined as
! where = v̅_g/|v_g|, the direction of the energy flow. !
! Since v̅_g = - Λ/ / Λ/ω, using the cold dispersion ! α = 2 Im()
! relation, we have that !
! ! where = v̅_g/|v_g|, the direction of the energy flow.
! = Λ/ / |Λ/| ! Since v̅_g = - Λ/ / Λ/ω, using the cold dispersion
! = [2 - (N²s)/N ! relation, we have that
! + ½(S_I)² ³(N²s)/N³ ] / |Λ/| !
! ! = Λ/ / |Λ/|
! Assuming Im(k)=0: ! = [2 - (N²s)/N
! ! + ½(S_I)² ³(N²s)/N³ ] / |Λ/|
! α = 4 Im(k)N / |Λ/| !
! ! Assuming Im(k)=0:
block !
real(wp_) :: k_im ! α = 4 Im(k)N / |Λ/|
k_im = k0 * Npr%im ! imaginary part of k !
alpha = 4 * k_im*Npr_cold / derdnm real(wp_) :: k_im
end block k_im = k0 * Npr%im ! imaginary part of k
alpha = 4 * k_im*Npr_cold / derdnm
end block accurate
else
! Compute a fast and approximate α
fast: block
use logger, only: log_warning
use absorption, only: alpha_fast
character(256) :: msg
! the absorption coefficient in the tenuous plasma limit
alpha = alpha_fast(X, Y, 1/mu, k0, Npl, Npr_cold, sox, nhmin, nhmax)
if (temperature > 10 .or. nhmax > 5) then
write (msg, '(a,g0.3,a,g0)') &
'iwarm=4 is inaccurate: Te=', temperature, ' nhmax=', nhmax
call log_warning(msg, mod='gray_core', proc='alpha_effj')
end if
end block fast
end if
if (alpha < 0) then if (alpha < 0) then
error = raise_error(error, negative_absorption) error = raise_error(error, negative_absorption)
@ -1849,71 +2147,6 @@ contains
end subroutine alpha_effj end subroutine alpha_effj
subroutine set_pol(ywrk0, bres, sox, ipol, psipol0, chipol0, ext0, eyt0)
use const_and_precisions, only : degree, zero, one, half, im
use beamdata, only : nray,nrayth
use equilibrium, only : bfield
use polarization, only : pol_limit, polellipse, &
stokes_ce, stokes_ell
implicit none
! subroutine arguments
real(wp_), dimension(6, nray), intent(in) :: ywrk0
real(wp_), intent(in) :: bres
integer, intent(in) :: sox, ipol
real(wp_), intent(inout) :: psipol0, chipol0
complex(wp_), dimension(nray), intent(out) :: ext0, eyt0
! local variables
integer :: j,k,jk
real(wp_), dimension(3) :: xmv, anv, bv
real(wp_) :: rm, csphi, snphi, bphi, br, bz, qq, uu, vv, deltapol
j=1
k=0
do jk=1,nray
k=k+1
if(jk == 2 .or. k > nrayth) then
j=j+1
k=1
end if
if(ipol == 0) then
xmv=ywrk0(1:3,jk)*0.01_wp_ ! convert from cm to m
anv=ywrk0(4:6,jk)
rm=sqrt(xmv(1)**2+xmv(2)**2)
csphi=xmv(1)/rm
snphi=xmv(2)/rm
call bfield(rm,xmv(3),bphi,br,bz)
! bv(i) = B_i in cartesian coordinates
bv(1)=br*csphi-bphi*snphi
bv(2)=br*snphi+bphi*csphi
bv(3)=bz
call pol_limit(anv,bv,bres,sox,ext0(jk),eyt0(jk))
if (jk == 1) then
call stokes_ce(ext0(jk),eyt0(jk),qq,uu,vv)
call polellipse(qq,uu,vv,psipol0,chipol0)
psipol0=psipol0/degree ! convert from rad to degree
chipol0=chipol0/degree
end if
else
call stokes_ell(chipol0*degree,psipol0*degree,qq,uu,vv)
if(qq**2 < one) then
deltapol=asin(vv/sqrt(one - qq**2))
ext0(jk)= sqrt(half*(one + qq))
eyt0(jk)= sqrt(half*(one - qq))*exp(-im*deltapol)
else
ext0(jk)= one
eyt0(jk)= zero
end if
endif
end do
end subroutine set_pol
subroutine cniteq(rqgrid,zqgrid,matr2dgrid,nr,nz,h,ncon,npts,icount,rcon,zcon) subroutine cniteq(rqgrid,zqgrid,matr2dgrid,nr,nz,h,ncon,npts,icount,rcon,zcon)
! v2.01 12/07/95 -- written by d v bartlett, jet joint undertaking. ! v2.01 12/07/95 -- written by d v bartlett, jet joint undertaking.
! (based on an older code) ! (based on an older code)

View File

@ -5,6 +5,9 @@ module gray_params
integer, parameter :: lenfnm = 256 integer, parameter :: lenfnm = 256
integer, parameter :: headw = 132, headl = 21 integer, parameter :: headw = 132, headl = 21
! Note: when adding/removing a parameter remember to keep
! the gray_params.sh script in sync with this file
! Antenna/wave launcher parameters ! Antenna/wave launcher parameters
type antenna_parameters type antenna_parameters
! From gray_params.data: ! From gray_params.data:
@ -55,8 +58,11 @@ module gray_params
integer :: igrad ! Complex eikonal switch integer :: igrad ! Complex eikonal switch
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
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
logical :: realtime ! Enable the realtime mode
end type end type
! EC resonant heating & Current Drive parameters ! EC resonant heating & Current Drive parameters
@ -127,6 +133,7 @@ module gray_params
type gray_results type gray_results
real(wp_) :: pabs ! Total absorbed power real(wp_) :: pabs ! Total absorbed power
real(wp_) :: icd ! Total driven current real(wp_) :: icd ! Total driven current
real(wp_) :: rho_peak ! Position of the absoprtion peak
real(wp_), allocatable :: dpdv(:) ! Absorbed power density real(wp_), allocatable :: dpdv(:) ! Absorbed power density
real(wp_), allocatable :: jcd(:) ! Driven current density real(wp_), allocatable :: jcd(:) ! Driven current density
end type end type
@ -365,6 +372,13 @@ contains
read(u, *) params%output%istpr, params%output%istpl read(u, *) params%output%istpr, params%output%istpl
close(u) close(u)
! Default values of parameters introduced after
! gray_params.data has been deprecated
params%raytracing%integrator = 4
params%raytracing%adaptive_step = .false.
params%raytracing%realtime = .false.
end subroutine read_gray_params end subroutine read_gray_params
@ -386,7 +400,8 @@ contains
istpr0 = params%output%istpr istpr0 = params%output%istpr
istpl0 = params%output%istpl istpl0 = params%output%istpl
if (params%raytracing%nrayr < 5) then if (.not. params%raytracing%realtime &
.and. params%raytracing%nrayr < 5) then
params%raytracing%igrad = 0 params%raytracing%igrad = 0
call log_warning('nrayr < 5 ⇒ optical case only', & call log_warning('nrayr < 5 ⇒ optical case only', &
mod="gray_params", proc="set_globals") mod="gray_params", proc="set_globals")

View File

@ -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' raytracing='rwmax dst nrayr nrayth nstep igrad idst ipass ipol integrator adaptive_step realtime'
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'

View File

@ -13,6 +13,7 @@
module ini_parser module ini_parser
use logger, only : log_error use logger, only : log_error
use utils, only : getline
! INI syntax constants ! INI syntax constants
character, parameter :: comment_sign = ';' character, parameter :: comment_sign = ';'
@ -148,29 +149,4 @@ contains
close(ini) close(ini)
end subroutine parse_ini end subroutine parse_ini
subroutine getline(unit, line, error)
! Reads a line into a deferred length string
! subroutine arguments
integer, intent(in) :: unit
character(len=:), allocatable, intent(out) :: line
integer, intent(out) :: error
integer, parameter :: bufsize = 512
character(len=bufsize) :: buffer
integer :: chunk
allocate(character(len=0) :: line)
do
read(unit, '(a)', advance='no', iostat=error, size=chunk) buffer
if (error > 0) exit
line = line // buffer(:chunk)
if (error < 0) then
if (is_iostat_eor(error)) error = 0
exit
end if
end do
end subroutine getline
end module ini_parser end module ini_parser

View File

@ -32,9 +32,6 @@ program main
if (opts%quiet) opts%verbose = ERROR if (opts%quiet) opts%verbose = ERROR
call set_log_level(opts%verbose) call set_log_level(opts%verbose)
! Activate the given output units
call set_active_units(opts%units)
! Load the parameters from file and move to its directory ! Load the parameters from file and move to its directory
! (all other filepaths are assumed relative to it) ! (all other filepaths are assumed relative to it)
if (allocated(opts%config_file)) then if (allocated(opts%config_file)) then
@ -65,10 +62,23 @@ program main
! Apply CLI overrides to the parameters ! Apply CLI overrides to the parameters
call parse_param_overrides(params) call parse_param_overrides(params)
! Realtime mode
if (params%raytracing%realtime) then
params%ecrh_cd%ieccd = 0 ! Disable current drive compuration
params%ecrh_cd%iwarm = 1 ! Use the weakly relativistic dispersion
params%raytracing%nrayr = 1 ! One ray
params%raytracing%ipass = 1 ! Single pass only
opts%units = [0] ! Disable all output files
call log_message(level=INFO, mod='main', msg='running in realtime mode')
end if
! Copy the parameters into global variables ! Copy the parameters into global variables
! exported by the gray_params module ! exported by the gray_params module
call params_set_globals(params) call params_set_globals(params)
! Activate the given output units
call set_active_units(opts%units)
! Read the input data and set the global variables ! Read the input data and set the global variables
! of the respective module. Note: order matters. ! of the respective module. Note: order matters.
call init_equilibrium(params, data, err) call init_equilibrium(params, data, err)
@ -93,6 +103,7 @@ program main
end if end if
if (allocated(opts%sum_filelist)) then if (allocated(opts%sum_filelist)) then
! Combine the output profiles from many individual simulations
call log_message(level=INFO, mod='main', msg='summing profiles') call log_message(level=INFO, mod='main', msg='summing profiles')
sum: block sum: block
@ -181,25 +192,48 @@ program main
deallocate(extracol) deallocate(extracol)
deallocate(opts%params_file) deallocate(opts%params_file)
end block sum end block sum
elseif (opts%server) then
! Handle requests from stdin
block
logical :: done
do
call handle_one_request(done)
if (done) exit
end do
end block
else else
! Run the main GRAY routine
call gray_main(params, data, results, err) call gray_main(params, data, results, err)
end if end if
print_res: block print_results: block
character(256) :: msg character(256) :: msg
write(msg, '(a,g0.3," MW")') 'total absoption: P=', results%pabs
write(msg, '(a,g0.5)') 'absorption peak: ρ=', results%rho_peak
call log_message(msg, level=INFO, mod='main') call log_message(msg, level=INFO, mod='main')
write(msg, '(a,g0.3," kA")') 'total current drive: I=', results%icd * 1.0e3_wp_
call log_message(msg, level=INFO, mod='main') if (.not. params%raytracing%realtime) then
end block print_res if (params%ecrh_cd%iwarm > 0) then
write(msg, '(a,g0.3," MW")') 'total absoption: P=', results%pabs
call log_message(msg, level=INFO, mod='main')
end if
if (params%ecrh_cd%ieccd > 0) then
write(msg, '(a,g0.3," kA")') 'total current drive: I=', results%icd * 1000
call log_message(msg, level=INFO, mod='main')
end if
end if
end block print_results
! Free memory ! Free memory
call deinit_equilibrium(data%equilibrium) cleanup: block
call deinit_profiles(data%profiles) call deinit_equilibrium(data%equilibrium)
call deinit_misc call deinit_profiles(data%profiles)
call deinit_cli_options(opts) call deinit_misc
deallocate(results%dpdv, results%jcd) call deinit_cli_options(opts)
call close_units if (allocated(results%dpdv)) deallocate(results%dpdv, results%jcd)
call close_units
end block cleanup
contains contains
@ -496,7 +530,7 @@ contains
real(wp_), dimension(:, :), pointer :: psjki=>null(), ppabs=>null(), ccci=>null() real(wp_), dimension(:, :), pointer :: psjki=>null(), ppabs=>null(), ccci=>null()
real(wp_), dimension(:), pointer :: tau0=>null(), alphaabs0=>null(), & real(wp_), dimension(:), pointer :: tau0=>null(), alphaabs0=>null(), &
dids0=>null(), ccci0=>null() dpds=>null(), dids0=>null(), ccci0=>null()
real(wp_), dimension(:), pointer :: p0jk=>null() real(wp_), dimension(:), pointer :: p0jk=>null()
complex(wp_), dimension(:), pointer :: ext=>null(), eyt=>null() complex(wp_), dimension(:), pointer :: ext=>null(), eyt=>null()
integer, dimension(:), pointer :: iiv=>null() integer, dimension(:), pointer :: iiv=>null()
@ -511,8 +545,8 @@ contains
! Initialise the ray variables (beamtracing) ! Initialise the ray variables (beamtracing)
call init_btr(params%raytracing, yw, ypw, xc, du1, & call init_btr(params%raytracing, yw, ypw, xc, du1, &
gri, ggri, psjki, ppabs, ccci, & gri, ggri, psjki, ppabs, ccci, &
tau0, alphaabs0, dids0, ccci0, & tau0, alphaabs0, dpds, dids0, &
p0jk, ext, eyt, iiv) ccci0, p0jk, ext, eyt, iiv)
! Initialise the dispersion module ! Initialise the dispersion module
if (params%ecrh_cd%iwarm > 1) call expinit if (params%ecrh_cd%iwarm > 1) call expinit
@ -554,9 +588,128 @@ contains
! Free memory ! Free memory
call dealloc_surfvec ! for fluxval call dealloc_surfvec ! for fluxval
call dealloc_beam(yw, ypw, xc, du1, gri, ggri, psjki, ppabs, ccci, & call dealloc_beam(yw, ypw, xc, du1, gri, ggri, psjki, ppabs, ccci, tau0, &
tau0, alphaabs0, dids0, ccci0, p0jk, ext, eyt, iiv) alphaabs0, dpds, dids0, ccci0, p0jk, ext, eyt, iiv)
call dealloc_pec call dealloc_pec
end subroutine sum_profiles end subroutine sum_profiles
subroutine handle_one_request(done)
! Handles a user request from the stdin
!
! Available commands:
! - run run a simulation
! - set ID=VAL update the value of a GRAY parameter
! - reload (profiles|equilibrium) reload the input files
! - quit stop the program
!
! All replies are JSON encoded, include a boolean `error` to
! indicate a failure and, optionally, contain an explanation
! in the `msg` string.
use, intrinsic :: iso_fortran_env, only : input_unit
use ini_parser, only : ERR_SUCCESS, ERR_VALUE, ERR_UNKNOWN
use gray_params, only : update_parameter
use utils, only : getline
! subroutine arguments
logical, intent(out) :: done ! user requested to stop
! local variables
integer :: sep, err
character(len=:), target, allocatable :: line
character(len=:), pointer :: cmd, args
! read one command from stdin
call getline(input_unit, line, err)
if (err /= 0) return
sep = index(line, ' ')
if (sep /= 0) then
! command has arguments
cmd => line(1:sep - 1)
args => line(sep + 1:)
else
! no arguments
cmd => line
end if
done = .false.
select case (cmd)
! run the simulation
case ('run')
call gray_main(params, data, results, err)
if (err /= 0) then
print '(a, g0, a)', '{"error": true, "error_code": ', &
err, ', "msg": "simulation failed"}'
else if (params%raytracing%realtime) then
print '(a, 3(a,g0), a)', &
'{"error": false, "error_code": 0, "result": ', &
'{"rho_peak": ', results%rho_peak, &
', "power": null', &
', "current": null}}'
else
print '(a, 3(a,g0), a)', &
'{"error": false, "error_code": 0, "result": ', &
'{"rho_peak": ', results%rho_peak, &
', "power": ', results%pabs, &
', "current": ', results%icd, '}}'
end if
! stop the program
case ('quit')
print '(a)', '{"error": false, "msg": "quitting"}'
done = .true.
! set a GRAY parameter
case ('set')
! args split at "=" (id=value)
block
character(len=:), pointer :: id, val
sep = index(args, '=')
id => args(1:sep - 1)
val => args(sep + 1:)
select case (update_parameter(params, id, val))
case (ERR_VALUE)
print '(a)', '{"error": true, "msg": "invalid value"}'
case (ERR_UNKNOWN)
print '(a)', '{"error": true, "msg": "unknown parameter"}'
case (ERR_SUCCESS)
print '(a)', '{"error": false, "msg": "done"}'
end select
end block
! reload inputs
case ('reload')
select case (args)
case ('equilibrium')
call init_equilibrium(params, data, err)
if (err /= 0) then
print '(a)', '{"error": true, "msg": "equilibrium initialisation failed"}'
else
print '(a)', '{"error": false, "msg": "equilibrium reloaded"}'
end if
case ('profiles')
call init_profiles(params%profiles, params%equilibrium%factb, &
params%antenna%pos, data%profiles, err)
if (err /= 0) then
print '(a)', '{"error": true, "msg": "profiles initialisation failed"}'
else
print '(a)', '{"error": false, "msg": "profiles reloaded"}'
end if
case default
print '(a)', '{"error": true, "msg": "invalid type"}'
end select
case default
print '(a)', '{"error": true, msg: "invalid command"}'
end select
deallocate(line)
end subroutine handle_one_request
end program main end program main

View File

@ -2,7 +2,7 @@ module multipass
use const_and_precisions, only : wp_, zero, half, one, degree, czero use const_and_precisions, only : wp_, zero, half, one, degree, czero
use beamdata, only : dst, nray use beamdata, only : dst, nray
use gray_params, only : ipass use gray_params, only : ipass
use polarization, only : pol_limit, stokes_ce, polellipse use polarization, only : pol_limit, field_to_ellipse
use reflections, only : wall_refl use reflections, only : wall_refl
use equilibrium, only : bfield use equilibrium, only : bfield
@ -13,56 +13,68 @@ module multipass
contains contains
! ------------------------------ subroutine plasma_in(i, x, N, Bres, sox, cpl, psi, chi, iop, ext, eyt, perfect)
subroutine plasma_in(i,xv,anv,bres,sox,cpl,psipol1,chipol1,iop,ext,eyt) ! ray enters plasma ! Computes the ray polarisation and power couplings when it enteres the plasma
implicit none use const_and_precisions, only: cm
! arguments
integer, intent(in) :: i ! ray index ! subroutine arguments
real(wp_), dimension(3), intent(in) :: xv,anv integer, intent(in) :: i ! ray index
real(wp_), intent(in) :: bres real(wp_), intent(in) :: x(3), N(3) ! position, refactive index
integer, intent(in) :: sox real(wp_), intent(in) :: Bres ! resonant B field
real(wp_), dimension(2), intent(out) :: cpl ! coupling (O/X) integer, intent(in) :: sox ! sign of polarisation mode: -1 O, +1 X
real(wp_), intent(out) :: psipol1,chipol1 real(wp_), intent(out) :: cpl(2) ! power coupling vector (O, X)
integer, dimension(:), intent(inout), pointer :: iop ! in/out plasma flag real(wp_), intent(out) :: psi, chi ! polarisation ellipse angles
complex(wp_), dimension(:), intent(inout), pointer :: ext,eyt integer, intent(inout), pointer :: iop(:) ! inside/outside plasma flag
! local variables complex(wp_), intent(inout), pointer :: ext(:), eyt(:) ! ray polarisation vector (e_x, e_y)
real(wp_) :: rm,csphi,snphi,bphi,br,bz logical, intent(in) :: perfect ! whether to assume perfect coupling
real(wp_) :: qq1,uu1,vv1,qq,uu,vv,powcpl
real(wp_), dimension(3) :: bv,xmv ! local variables
complex(wp_) :: ext1,eyt1 real(wp_) :: R, z, cosphi, sinphi, B_phi, B_R, B_z
! real(wp_) :: B(3)
iop(i)=iop(i)+1 ! out->in real(wp_) :: c
complex(wp_) :: e_mode(2), e_ray(2)
xmv=xv*0.01_wp_ ! convert from cm to m
rm=sqrt(xmv(1)**2+xmv(2)**2) ! Update the inside/outside flag
csphi=xmv(1)/rm iop(i) = iop(i) + 1
snphi=xmv(2)/rm
call bfield(rm,xmv(3),bphi,br,bz) ! Compute B in cartesian coordinates
bv(1)=br*csphi-bphi*snphi R = norm2(x(1:2)) * cm
bv(2)=br*snphi+bphi*csphi z = x(3) * cm
bv(3)=bz cosphi = x(1)/R * cm
sinphi = x(2)/R * cm
call pol_limit(anv,bv,bres,sox,ext1,eyt1) call bfield(R, z, B_phi, B_R, B_z)
call stokes_ce(ext1,eyt1,qq1,uu1,vv1) ! stokes parameter at plasma entrance B(1) = B_R*cosphi - B_phi*sinphi
call stokes_ce(ext(i),eyt(i),qq,uu,vv) ! stokes parameter at plasma exit/wall reflection B(2) = B_R*sinphi + B_phi*cosphi
powcpl = half*(one + vv*vv1+uu*uu1+qq*qq1) ! coupling for incoming mode B(3) = B_z
if(sox.eq.-one) then ! incoming mode = O ! Get the polarisation vector of the given mode
cpl=(/powcpl,one-powcpl/) call pol_limit(N, B, Bres, sox, e_mode(1), e_mode(2))
else ! incoming mode = X
cpl=(/one-powcpl,powcpl/) if(i == 1) then
end if ! For the central ray, compute the polarization ellipse
call field_to_ellipse(e_mode(1), e_mode(2), psi, chi)
if(i.eq.1) then ! polarization angles at plasma entrace for central ray
call polellipse(qq1,uu1,vv1,psipol1,chipol1)
psipol1=psipol1/degree ! convert from rad to degree
chipol1=chipol1/degree
else else
psipol1 = zero psi = 0
chipol1 = zero chi = 0
end if end if
if (perfect) then
! Ignore the given vector and use the expected one
! Note: this will give 100% coupling to the current mode
ext(i) = e_mode(1)
eyt(i) = e_mode(2)
end if
! Compute the power coupling with the current mode
e_ray = [ext(i), eyt(i)]
c = abs(dot_product(e_mode, e_ray))**2
! Store both O and X couplings, in this order
c = merge(c, 1-c, sox == -1)
cpl = [c, 1-c]
end subroutine plasma_in end subroutine plasma_in
! ------------------------------
subroutine plasma_out(i,xv,anv,bres,sox,iop,ext,eyt) ! ray exits plasma subroutine plasma_out(i,xv,anv,bres,sox,iop,ext,eyt) ! ray exits plasma
implicit none implicit none
! arguments ! arguments
@ -110,7 +122,6 @@ contains
complex(wp_), dimension(:), intent(inout), pointer :: ext,eyt complex(wp_), dimension(:), intent(inout), pointer :: ext,eyt
! local variables ! local variables
integer :: irfl integer :: irfl
real(wp_) :: qq1,uu1,vv1
real(wp_), dimension(3) :: xvrfl,anvrfl,walln real(wp_), dimension(3) :: xvrfl,anvrfl,walln
complex(wp_) :: ext1,eyt1 complex(wp_) :: ext1,eyt1
! !
@ -122,35 +133,42 @@ contains
xv = xvrfl xv = xvrfl
anv = anvrfl anv = anvrfl
if(i.eq.1) then ! polarization angles at wall reflection for central ray if(i == 1) then ! polarization angles at wall reflection for central ray
call stokes_ce(ext1,eyt1,qq1,uu1,vv1) call field_to_ellipse(ext1, eyt1, psipol1, chipol1)
call polellipse(qq1,uu1,vv1,psipol1,chipol1)
psipol1=psipol1/degree ! convert from rad to degree
chipol1=chipol1/degree
else else
psipol1 = zero psipol1 = zero
chipol1 = zero chipol1 = zero
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
integer, intent(in) :: i ! beam index ! subroutine arguments
logical, dimension(:,:), intent(in), pointer :: iroff ! global ray status (F = active, T = inactive) type(gray_parameters), intent(in) :: params
logical, intent(out) :: iboff integer, intent(in) :: i ! beam index
logical, dimension(:), intent(out), pointer :: iwait logical, pointer, intent(in) :: iroff(:,:) ! global ray status (F = active, T = inactive)
real(wp_), dimension(:), intent(out), pointer :: jphi_beam,pins_beam, & logical, intent(out) :: iboff ! beam status (F = active, T = inactive)
currins_beam,dpdv_beam,jcd_beam,stv logical, pointer, intent(out) :: iwait(:)
character(256) :: msg ! buffer for formatting log messages real(wp_), pointer, intent(out), dimension(:) :: &
jphi_beam, pins_beam, currins_beam, dpdv_beam, jcd_beam, stv, dst
iboff = .false. ! beam status (F = active, T = inactive)
iwait = iroff(:,i) ! copy ray status for current beam from global ray status ! local variables
if(all(iwait)) then ! no rays active => stop beam character(256) :: msg ! buffer for formatting log messages
iboff = .false.
iwait = iroff(:,i) ! copy current beam status from the global one
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 +176,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, ct, S_R)
dst = params%raytracing%dst ! starting step size (ds, cdt, 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 +240,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, & subroutine alloc_multipass(&
pins_beam,currins_beam,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 implicit none
integer :: dim
logical, dimension(:), intent(out), pointer :: iwait ! subroutine arguments
logical, dimension(:,:), intent(out), pointer :: iroff integer, intent(in) :: dim
integer, dimension(:), intent(out), pointer :: iop,iow logical, pointer, dimension(:), intent(out) :: iwait
real(wp_), dimension(:), intent(out), pointer :: jphi_beam,pins_beam,currins_beam, & logical, pointer, dimension(:,:), intent(out) :: iroff
dpdv_beam,jcd_beam,stv,tau1,etau1,cpl1,lgcpl1,p0ray,psipv,chipv integer, pointer, dimension(:), intent(out) :: iop, iow
real(wp_), dimension(:,:), intent(out), pointer :: taus,cpls,stnext,yw0,ypw0 real(wp_), pointer, dimension(:), intent(out) :: &
real(wp_), dimension(:,:,:), intent(out), pointer :: yynext,yypnext 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, & call dealloc_multipass(&
p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,jphi_beam,pins_beam,currins_beam, & iwait, iroff, iop, iow, yynext, yypnext, yw0, ypw0, stnext, &
dpdv_beam,jcd_beam,psipv,chipv) 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(0:nbeam_tot))
allocate(chipv(0: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(&
pins_beam,currins_beam,dpdv_beam,jcd_beam,psipv,chipv) 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 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

View File

@ -1,156 +1,292 @@
! This module contains subroutines to convert between different descriptions
! of the wave polarisation and to compute the polarisation of the plasma modes
module polarization module polarization
interface stokes
module procedure stokes_ce,stokes_ell use const_and_precisions, only : wp_, pi, im
end interface
implicit none
private
public ellipse_to_field, field_to_ellipse ! Converting between descriptions
public pol_limit ! Plasma modes polarisations
contains contains
subroutine stokes_ce(ext,eyt,qq,uu,vv)
use const_and_precisions, only : wp_
implicit none
! arguments
complex(wp_), intent(in) :: ext,eyt
real(wp_), intent(out) :: qq,uu,vv
qq = abs(ext)**2 - abs(eyt)**2 pure subroutine ellipse_to_field(psi, chi, e_x, e_y)
uu = 2*real(ext*conjg(eyt)) ! Computes the normalised Jones vector from the
vv = 2*imag(ext*conjg(eyt)) ! polarisation ellipse angles ψ, χ
end subroutine stokes_ce !
! Notes:
! - ψ[-π/2, π/2] is the angle between the x and the major axis
! - χ[-π/4, π/4] is defined by tan(χ) = b/a, where a,b are the
! major,minor semi-axis, respectively; χ>0 for positive helicity
! (left-handed wave), χ<0 for negative helicity (right-handed wave).
! subroutine arguments
real(wp_), intent(in) :: psi, chi
complex(wp_), intent(out) :: e_x(:), e_y(:)
! The Eikonal ansatz is:
!
! (, t) = Re () exp(-ikS() + iωt)
!
! where () = [|e|exp(), |e|exp(), 0], since the wave
! is transversal in vacuum. At a fixed position =0, ignoring
! the third component, we have:
!
! (0, t) = [|e|cos(φ + ωt), |e|cos(φ + ωt)]
! = [|e|cos(φ)cos(ωt) - |e|sin(φ)sin(ωt),
! |e|cos(φ)cos(ωt) - |e|sin(φ)sin(ωt)]
!
! Then, we compare this to the parametric equation of
! an ellipse rotated by ψ through the origin,
!
! (t) = R(ψ) [acos(ωt), bsin(ωt)]
! = [cos(ψ)acos(ωt), -sin(ψ)bsin(ωt),
! sin(ψ)acos(ωt), cos(ψ)bsin(ωt)]
!
! at ωt=0 and ωt=π/2, so:
!
! 1. |e|cos(φ) = acos(ψ)
! 2. |e|cos(φ) = asin(ψ)
! 3. |e|sin(φ) = bsin(ψ)
! 4. |e|sin(φ) = -bcos(ψ)
!
! From 1²+3² and 2²+4² we have
!
! |e|² = a²cos(ψ)²+b²sin(ψ)²
! |e|² = a²sin(ψ)²+b²cos(ψ)²
!
! |e|² + |e|² = a² + b²
!
! Assuming is normalised, that is *=|e|²+|e|²=1,
! we have a²+b²=1, so we can define a=cos(χ), b=sin(χ).
!
! We can then rewrite:
!
! 1. Re e = cos(χ)cos(ψ)
! 2. Re e = cos(χ)sin(ψ)
! 3. Im e = +sin(χ)sin(ψ)
! 4. Im e = -sin(χ)cos(ψ)
!
! from which:
!
! e = cos(χ)cos(ψ) + isin(χ)sin(ψ)
! e = cos(χ)sin(ψ) - isin(χ)cos(ψ)
!
e_x = cosd(chi)*cosd(psi) + im * sind(chi)*sind(psi)
e_y = cosd(chi)*sind(psi) - im * sind(chi)*cosd(psi)
end subroutine ellipse_to_field
subroutine stokes_ell(chi,psi,qq,uu,vv) pure subroutine field_to_ellipse(e_x, e_y, psi, chi)
use const_and_precisions, only : wp_,two ! Computes the polarisation ellipse angles ψ, χ
implicit none ! from the normalised Jones vector
! arguments
real(wp_), intent(in) :: chi,psi
real(wp_), intent(out) :: qq,uu,vv
qq=cos(two*chi)*cos(two*psi) ! subroutine arguments
uu=cos(two*chi)*sin(two*psi) complex(wp_), intent(in) :: e_x, e_y
vv=sin(two*chi) real(wp_), intent(out) :: psi, chi
end subroutine stokes_ell
! First, to make the map (ψ, χ) unit ellipse
! unique we restricted its domain to
! [-π/2, π/2]×[-π/4, π/4]. Then, starting from
!
! e = cos(χ)cos(ψ) + isin(χ)sin(ψ)
! e = cos(χ)sin(ψ) - isin(χ)cos(ψ)
!
! (see `ellipse_to_field`), we obtain χ doing
!
! 2ee* = cos(2χ)sin(2ψ) + i sin(2χ)
! χ = ½ asin(Im(2ee*))
!
! This gives the angle χ in the correct interval since
! the range of asin is [-π/2, π/2] by definition.
!
! For ψ notice that:
!
! ee = e²-e² = cos(χ)²cos(2ψ) - sin(χ)²cos(2ψ)
! = cos(2χ)cos(2ψ)
!
! Combining this to the previous expression:
!
! tan(2ψ) = Re(2ee*)/(ee)
!
! Finally, since atan2 gives the principal branch
! (-π, π], ψ is given within the correct interval as:
!
! ψ = ½ atan2(Re(2ee*), (ee))
!
chi = asind(imag(2 * e_x * conjg(e_y))) / 2
psi = atan2d(real(2 * e_x * conjg(e_y)), abs(e_x)**2 - abs(e_y)**2) / 2
end subroutine field_to_ellipse
subroutine polellipse(qq,uu,vv,psi,chi) pure subroutine pol_limit(N, B, Bres, sox, e_x, e_y)
use const_and_precisions, only : wp_,half ! Computes the Jones vectors of the cold plasma dispersion
implicit none ! relation in the limit of vanishing electron density
! arguments !
real(wp_), intent(in) :: qq,uu,vv ! Note: the Jones vectors are given in the local beam frame,
real(wp_), intent(out) :: psi,chi ! that is, the z axis is aligned with the wave vector and x axis
! real(wp_) :: ll,aa,bb,ell ! lies in the tokamak equatorial plane.
! This allows to directly compare the beam polarisation with
! the plasma modes Jones vectors to obtain the power couplings.
! ll = sqrt(qq**2 + uu**2) ! subroutine arguments
! aa = sqrt(half*(1 + ll)) real(wp_), intent(in) :: N(3) ! refractive index
! bb = sqrt(half*(1 - ll)) real(wp_), intent(in) :: B(3) ! magnetic field
! ell = bb/aa real(wp_), intent(in) :: Bres ! resonant magnetic field
psi = half*atan2(uu,qq) ! sign of polarisation mode: -1 O, +1 X
chi = half*asin(vv) integer, intent(in) :: sox
end subroutine polellipse ! Components of the Jones vector
complex(wp_), intent(out) :: e_x, e_y
subroutine pol_limit(anv,bv,bres,sox,ext,eyt) !,gam) ! local variables
use const_and_precisions, only : wp_,ui=>im,zero,one real(wp_) :: Y, Npl, delta
implicit none real(wp_) :: z(3), R(2,2), gamma
! arguments complex(wp_) :: f, e(2)
real(wp_), dimension(3), intent(in) :: anv,bv
real(wp_), intent(in) :: bres
integer, intent(in) :: sox
complex(wp_), intent(out) :: ext,eyt
! real(wp_), optional, intent(out) :: gam
! local variables
real(wp_), dimension(3) :: bnv
real(wp_) :: anx,any,anz,an2,an,anpl2,anpl,anpr,anxy, &
btot,yg,den,dnl,del0,ff,ff2,sngam,csgam
!
btot = sqrt(bv(1)**2+bv(2)**2+bv(3)**2)
bnv = bv/btot
yg = btot/bres
anx = anv(1) Y = norm2(B) / Bres ! Y = ω_ce/ω
any = anv(2) Npl = dot_product(N, B) / norm2(B) ! N = /B
anz = anv(3)
an2 = anx**2 + any**2 + anz**2
an = sqrt(an2)
anxy = sqrt(anx**2 + any**2)
anpl = (anv(1)*bnv(1) + anv(2)*bnv(2) + anv(3)*bnv(3)) ! Coordinate systems in use
anpl2= anpl**2 ! 1. plasma basis, definition of dielectric tensor
anpr = sqrt(an2 - anpl2) ! = /N
! = /B×/N
! = /B
! 2. polarisation basis, definition of /
! = -/N×(/B×/N)= -/B
! = /B×/N
! = /N
! 3. beam basis, definition of rays initial conditions
! = /N×
! = /N×(/N×)
! = /N
dnl = one - anpl2 ! The cold plasma dispersion relation tensor in the plasma
del0 = sqrt(dnl**2 + 4.0_wp_*anpl2/yg**2) ! basis (the usual one) is:
!
sngam = (anz*anpl - an2*bnv(3))/(an*anxy*anpr) ! [ (R+L)/2 - N² -i(R-L)/2 NN ]
csgam = -(any*bnv(1) - anx*bnv(2))/ (anxy*anpr) ! Λ = [i(R-L)/2 (R+L)/2 - N² 0 ]
! [NN 0 P - N²]
ff = 0.5_wp_*yg*(dnl - sox*del0) !
ff2 = ff**2 ! where P = 1 - X
den = ff2 + anpl2 ! L = 1 - X/(1+Y)
if (den>zero) then ! R = 1 - X/(1-Y)
ext = (ff*csgam - ui*anpl*sngam)/sqrt(den) ! X = (ω_p/ω)²
eyt = (-ff*sngam - ui*anpl*csgam)/sqrt(den) ! Y = ω_c/ω
den = sqrt(abs(ext)**2+abs(eyt)**2) !
ext = ext/den ! To compute the polarisation (the ratio / in the wave
eyt = eyt/den ! transverse plane) we switch to the polarisation basis.
else ! only for XM (sox=+1) when N//=0 ! The relations between the new and old unit vectors are:
ext = -ui*sngam !
eyt = -ui*csgam ! ' =
! ' = /N = ( + )/N = (N/N) + (N/N)
! ' = y̅'×' = y̅×z̅' = (N/N) - (N/N)
!
! so the change of basis matrix is:
!
! [ N/N 0 N/N]
! M = [ 0 1 0 ]
! [-N/N 0 N/N]
!
! which is equivalent to a clockwise rotation of the
! plane around by the pitch angle θ: = Ncosθ.
!
! Consequently the tensor Λ in this basis is given by:
!
! Λ' = M¹ Λ M
!
! Substituting the solution of the dispersion relation
! N=N(X, Y, N, ±) into Λ' and taking lim X0 yields:
!
! [ ½XY²(N²-1Δ) -iXYN XY²N(1-N²)]
! Λ' = [ iXYN ½XY²(1-N²Δ) iXY(1-N²)] + o(X²)
! [XY²N(1-N²) -iXY(1-N²) -XY²N²+X+Y²-1]
!
! where Δ = [4N²/Y² + (1 - N²)²]
!
! At exactly X=0, Λ' reduces to diag(0,0,1), so for Λ'E=0 we must
! have E=0, meaning we can effectively ignore the third column.
!
! The polarisation is determined by the ratio
!
! / = -Λ/Λ = -i Y[N² -1 Δ(X=0)]/(2N)
! = i [Y(N²-1) ± Δ']/(2N)
! i f±
!
! where Δ' = (X=0) = [4N² + Y²(1 - N²)²]
!
if (sox == -1 .and. Npl == 0) then
! If =0, the direction of the electric field is = (1, 0).
! This happens for O mode at N=0, the polarisation here is
! linear with .
! This case is handled separately to avoid a division by zero.
e = [1, 0]
else
! In general, if 0, the direction of the electric field is
!
! (, ) ~ (/, 1) ~ (iẼ/, i) = (f±, i)
!
! so, the polarisation is elliptical and the Jones vector is:
!
! = (f±, i) / (1 + f±²)
!
delta = sqrt(4*Npl**2 + Y**2*(1 - Npl**2)**2)
f = (Y*(Npl**2 - 1) + sox * delta) / (2*Npl)
e = [f, im] / sqrt(1 + f**2)
end if end if
! gam = atan2(sngam,csgam)/degree ! To obtain the polarisation in the beam basis we must compute the
! angle γ such that a rotation of γ around =/N aligns the axis
! of the wave transverse plane to the equatorial plane of the
! tokamak, that is:
!
! R(γ,)() = 0
!
! where R(γ,) is given by Rodrigues' rotation formula;
! = -/B (x axis in polarisation basis);
! = /N is (z axis in polarization basis)
! is the vertical direction (standard basis).
!
! Since the rotation is a linear operation,
!
! R(γ,)(-/B) = 0 R(γ,) = 0
!
! and the condition simplifies to:
!
! R(γ,)
! = [cosγ + ×sinγ + ()(1-cosγ)]
! = (cosγ + ×sinγ)
! = Bcosγ + (×)sinγ
! = 0
!
! By definition = ×(×)=-(), so:
!
! B = - ()
!
! (×) = [×(×(×))]
! = [-(×(×))×]
! = -(×)
! = (zB-zB)
!
! Substituting, we obtain:
!
! [ - ()]cosγ + (zB-zB)sinγ = 0
!
! γ = atan2(()-, zB-zB)
!
z = N / norm2(N)
gamma = atan2(dot_product(B, z) * z(3) - B(3), z(1)*B(2) - z(2)*B(1))
! Apply the rotation R(γ,) to the Jones vector
!
! Note: Jones vectors transform as normal vectors under rotations
! in physical space (SO(3) group); but as spinors on the Poincaré
! sphere (SU(2) group). For example, a rotation by γ around
! changes the longitude φ=2ψ by 2γ.
R = reshape([cos(gamma), -sin(gamma), sin(gamma), cos(gamma)], [2, 2])
e = matmul(R, e)
e_x = e(1)
e_y = e(2)
end subroutine pol_limit end subroutine pol_limit
subroutine polarcold(anpl,anpr,xg,yg,sox,exf,eyif,ezf,elf,etf)
use const_and_precisions, only : wp_,zero,one
implicit none
! arguments
real(wp_), intent(in) :: anpl,anpr,xg,yg,sox
real(wp_), intent(out) :: exf,eyif,ezf,elf,etf
! local variables
real(wp_) :: anpl2,anpr2,an2,yg2,dy2,aa,e3,qq,p
if(xg <= zero) then
exf = zero
if(sox < zero) then
ezf = one
eyif = zero
else
ezf = zero
eyif = one
end if
elf = zero
etf = one
else
anpl2 = anpl**2
anpr2 = anpr**2
an2 = anpl2 + anpr2
yg2=yg**2
aa=1.0_wp_-xg-yg2
dy2 = one - yg2
qq = xg*yg/(an2*dy2 - aa)
if (anpl == zero) then
if(sox < zero) then
exf = zero
eyif = zero
ezf = one
else
qq = -aa/(xg*yg)
exf = one/sqrt(one + qq**2)
eyif = qq*exf
ezf = zero
end if
else
e3 = one - xg
p = (anpr2 - e3)/(anpl*anpr) ! undef for anpr==0
exf = p*ezf
eyif = qq*exf
ezf = one/sqrt(one + p**2*(one + qq**2))
end if
elf = (anpl*ezf + anpr*exf)/sqrt(an2)
etf = sqrt(one - elf**2)
end if
end subroutine polarcold
end module polarization end module polarization

View File

@ -129,6 +129,47 @@ contains
y=aa*y1+bb*y2 y=aa*y1+bb*y2
end subroutine intlin end subroutine intlin
pure function parabola_vertex(x, y) result(v)
! Computes the vertex of a parabola passing by three points
! (x, y), (x, y), (x, y)
!
! The solution is obtained by solving the system
!
! p(x) = y
! p(x) = y
! p(x) = y
!
! where p(x) = ax² + bx + c. The vertex is then
! given by the usual formula (-b/2a, c - b²/4a).
implicit none
! function arguments
real(wp_), dimension(3), intent(in) :: x, y ! x,y of the three points
real(wp_), dimension(2) :: v ! vertex
! local variables
real(wp_) :: denom, a, b, c
denom = (x(1) - x(2))*(x(1) - x(3))*(x(2) - x(3))
a = ( x(3)*(y(2) - y(1)) &
+ x(2)*(y(1) - y(3)) &
+ x(1)*(y(3) - y(2))) / denom
b = ( x(3)**2 * (y(1) - y(2)) &
+ x(2)**2 * (y(3) - y(1)) &
+ x(1)**2 * (y(2) - y(3))) / denom
c = ( x(2)*x(3)*(x(2) - x(3))*y(1) &
+ x(3)*x(1)*(x(3) - x(1))*y(2) &
+ x(1)*x(2)*(x(1) - x(2))*y(3)) / denom
v = [-b/(2*a), c - b**2/(4*a)]
end function
subroutine vmax(x,n,xmax,imx) subroutine vmax(x,n,xmax,imx)
implicit none implicit none
integer, intent(in) :: n integer, intent(in) :: n
@ -299,6 +340,7 @@ contains
end if end if
end function dirname end function dirname
function isrelative(filepath) function isrelative(filepath)
! Check if `filepath` is a relative or an absolute path ! Check if `filepath` is a relative or an absolute path
@ -309,4 +351,30 @@ contains
isrelative = (filepath(1:1) /= '/') isrelative = (filepath(1:1) /= '/')
end function isrelative end function isrelative
subroutine getline(unit, line, error)
! Reads a line into a deferred length string
! subroutine arguments
integer, intent(in) :: unit
character(len=:), allocatable, intent(out) :: line
integer, intent(out) :: error
integer, parameter :: bufsize = 512
character(len=bufsize) :: buffer
integer :: chunk
allocate(character(len=0) :: line)
do
read(unit, '(a)', advance='no', iostat=error, size=chunk) buffer
if (error > 0) exit
line = line // buffer(:chunk)
if (error < 0) then
if (is_iostat_eor(error)) error = 0
exit
end if
end do
end subroutine getline
end module utils end module utils