stop re-exporting gray parameters as globals
This is a first step in removing all the global variables from gray.
This commit is contained in:
parent
281f32f221
commit
a4d44933e2
127
src/beamdata.f90
127
src/beamdata.f90
@ -3,119 +3,66 @@ module beamdata
|
||||
|
||||
implicit none
|
||||
|
||||
integer, save :: nray,nrayr,nrayth,nstep,jkray1
|
||||
real(wp_), save :: dst,h,hh,h6,rwmax,twodr2
|
||||
|
||||
contains
|
||||
|
||||
subroutine init_btr(rtrparam)
|
||||
subroutine pweight(params, p0, p0jk)
|
||||
! Power associated to jk-th ray p0jk(j) for total beam power p0
|
||||
use const_and_precisions, only : half
|
||||
use gray_params, only : raytracing_parameters
|
||||
use const_and_precisions, only : half,two
|
||||
type(raytracing_parameters), intent(in) :: rtrparam
|
||||
|
||||
integer :: jray1
|
||||
|
||||
dst = rtrparam%dst
|
||||
h = dst
|
||||
hh = h*half
|
||||
h6 = h/6.0_wp_
|
||||
|
||||
nrayr = rtrparam%nrayr
|
||||
nrayth = rtrparam%nrayth
|
||||
rwmax = rtrparam%rwmax
|
||||
|
||||
if (nrayr==1) then
|
||||
nrayth = 1
|
||||
jray1 = 1
|
||||
else
|
||||
jray1 = 1 + max(nint((nrayr-1)/rwmax),1)
|
||||
rwmax = dble(nrayr-1)/dble(jray1-1)
|
||||
end if
|
||||
nray = (nrayr-1)*nrayth + 1
|
||||
jkray1 = (jray1-2)*nrayth + 2
|
||||
|
||||
if(nrayr>1) then
|
||||
twodr2 = two*(rwmax/(nrayr-1))**2
|
||||
else
|
||||
twodr2 = two
|
||||
end if
|
||||
|
||||
nstep=rtrparam%nstep
|
||||
end subroutine init_btr
|
||||
|
||||
|
||||
|
||||
subroutine pweight(p0,p0jk)
|
||||
! power associated to jk-th ray p0jk(j) for total beam power p0
|
||||
use const_and_precisions, only : wp_, zero, one, half, two
|
||||
! arguments
|
||||
! subroutine arguments
|
||||
type(raytracing_parameters), intent(in) :: params
|
||||
real(wp_), intent(in) :: p0
|
||||
real(wp_), dimension(:), intent(out) :: p0jk
|
||||
! local variables
|
||||
integer :: j,jk,jkn
|
||||
real(wp_) :: dr,r,w,r0,w0,summ
|
||||
real(wp_), dimension(nrayr) :: q
|
||||
real(wp_), intent(out) :: p0jk(:)
|
||||
|
||||
if(nray==1) then
|
||||
q(1) = one
|
||||
! local variables
|
||||
integer :: j, jk, jkn
|
||||
real(wp_) :: dr, r, w, r0, w0, summ
|
||||
real(wp_) :: q(params%nrayr)
|
||||
|
||||
if (params%nray == 1) then
|
||||
q(1) = 1
|
||||
else
|
||||
dr = rwmax/dble(nrayr - 1)
|
||||
summ = zero
|
||||
w0 = one
|
||||
do j = 1, nrayr
|
||||
dr = params%rwmax / dble(params%nrayr - 1)
|
||||
summ = 0
|
||||
w0 = 1
|
||||
do j = 1, params%nrayr
|
||||
r = (dble(j) - half)*dr
|
||||
w = exp(-two*r**2)
|
||||
w = exp(-2*r**2)
|
||||
q(j) = w - w0
|
||||
summ = summ + q(j)
|
||||
r0 = r
|
||||
w0 = w
|
||||
end do
|
||||
q = q/summ
|
||||
q(2:) = q(2:)/nrayth
|
||||
q(2:) = q(2:) / params%nrayth
|
||||
end if
|
||||
|
||||
p0jk(1)=q(1)*p0
|
||||
jk=2
|
||||
do j=2,nrayr
|
||||
jkn=jk+nrayth
|
||||
p0jk(jk:jkn-1)=q(j)*p0
|
||||
jk=jkn
|
||||
p0jk(1) = q(1)*p0
|
||||
jk = 2
|
||||
do j = 2, params%nrayr
|
||||
jkn = jk + params%nrayth
|
||||
p0jk(jk:jkn - 1) = q(j)*p0
|
||||
jk = jkn
|
||||
end do
|
||||
end subroutine pweight
|
||||
|
||||
|
||||
pure function unfold_index(params, jk)
|
||||
! Maps the ray index jk=1,nray to a pair
|
||||
! (j, k) of radial (j) and azimuthal (k) indices.
|
||||
use gray_params, only : raytracing_parameters
|
||||
|
||||
! Functions to map radial (j), poloidal (k) ray
|
||||
! indices to a single global index (i)
|
||||
type(raytracing_parameters), intent(in) :: params
|
||||
integer, intent(in) :: jk
|
||||
integer :: unfold_index(2)
|
||||
|
||||
function rayi2jk(i) result(jk)
|
||||
integer, intent(in) :: i
|
||||
integer, dimension(2) :: jk
|
||||
integer :: ioff
|
||||
|
||||
if (i>1) then
|
||||
ioff = i - 2
|
||||
jk(1) = ioff/nrayth ! jr-2
|
||||
jk(2) = ioff - jk(1)*nrayth + 1 ! kt
|
||||
! jk(2) = mod(ioff,nrayth) + 1 ! kt
|
||||
jk(1) = jk(1) + 2 ! jr
|
||||
if (jk == 1) then
|
||||
unfold_index = [1, 1]
|
||||
else
|
||||
jk = 1
|
||||
unfold_index(1) = 2 + (jk - 2) / params%nrayth ! j
|
||||
unfold_index(2) = 1 + mod(jk - 2, params%nrayth) ! k
|
||||
end if
|
||||
end function rayi2jk
|
||||
|
||||
|
||||
|
||||
function rayi2j(i) result(jr)
|
||||
integer, intent(in) :: i
|
||||
integer :: jr
|
||||
|
||||
! jr = max(1, (i-2)/nrayth + 2)
|
||||
if (i>1) then
|
||||
jr = (i-2)/nrayth + 2
|
||||
else
|
||||
jr = 1
|
||||
end if
|
||||
end function rayi2j
|
||||
end function unfold_index
|
||||
|
||||
end module beamdata
|
||||
|
@ -35,6 +35,8 @@ module coreprofiles
|
||||
type(density_tail), save :: tail
|
||||
type(analytic_model), save :: model
|
||||
|
||||
integer, save :: iprof
|
||||
|
||||
private
|
||||
public read_profiles, read_profiles_an ! Reading data files
|
||||
public scale_profiles ! Applying rescaling
|
||||
@ -49,7 +51,6 @@ contains
|
||||
! normalised poloidal flux.
|
||||
!
|
||||
! Note: density has units of 10¹⁹ m⁻³.
|
||||
use gray_params, only : iprof
|
||||
use logger, only : log_error
|
||||
|
||||
! subroutine arguments
|
||||
@ -141,7 +142,6 @@ contains
|
||||
! normalised poloidal flux.
|
||||
!
|
||||
! Note: temperature has units of keV.
|
||||
use gray_params, only : iprof
|
||||
|
||||
! subroutine arguments
|
||||
real(wp_), intent(in) :: psin
|
||||
@ -169,7 +169,6 @@ contains
|
||||
function fzeff(psin)
|
||||
! Computes the effective charge Zeff as a
|
||||
! function of the normalised poloidal flux.
|
||||
use gray_params, only : iprof
|
||||
|
||||
! subroutine arguments
|
||||
real(wp_), intent(in) :: psin
|
||||
@ -195,7 +194,7 @@ contains
|
||||
! radial coordinate, temperature, density, effective charge.
|
||||
! 2. The first line is a header specifying the number of rows.
|
||||
use utils, only : get_free_unit
|
||||
use gray_params, only : profiles_data
|
||||
use gray_params, only : profiles_data, PROF_NUMERIC
|
||||
use logger, only : log_error
|
||||
|
||||
! subroutine arguments
|
||||
@ -207,6 +206,8 @@ contains
|
||||
! local variables
|
||||
integer :: u, i, nrows
|
||||
|
||||
iprof = PROF_NUMERIC
|
||||
|
||||
! Free the arrays when already allocated
|
||||
if (allocated(data%psrad)) deallocate(data%psrad)
|
||||
if (allocated(data%terad)) deallocate(data%terad)
|
||||
@ -253,7 +254,7 @@ contains
|
||||
!
|
||||
! See `density`, `temp`, `fzeff` subroutines for the meaning
|
||||
! of the parameters (i.e. the formulae for n,T,Zeff).
|
||||
use gray_params, only : profiles_data
|
||||
use gray_params, only : profiles_data, PROF_ANALYTIC
|
||||
use utils, only : get_free_unit
|
||||
use logger, only : log_error
|
||||
|
||||
@ -268,6 +269,8 @@ contains
|
||||
|
||||
u = get_free_unit(unit)
|
||||
|
||||
iprof = PROF_ANALYTIC
|
||||
|
||||
if (allocated(data%terad)) deallocate(data%terad)
|
||||
if (allocated(data%derad)) deallocate(data%derad)
|
||||
if (allocated(data%zfc)) deallocate(data%zfc)
|
||||
|
@ -62,6 +62,8 @@ module equilibrium
|
||||
real(wp_), save :: zmnm, zmxm ! z interval of the equilibrium grid
|
||||
real(wp_), save :: zbinf, zbsup ! z interval of the plasma boundary
|
||||
|
||||
integer, save :: iequil
|
||||
|
||||
private
|
||||
public read_eqdsk, read_equil_an ! Reading data files
|
||||
public scale_equil, change_cocos ! Transforming data
|
||||
@ -350,7 +352,6 @@ contains
|
||||
|
||||
use const_and_precisions, only : one
|
||||
use gray_params, only : equilibrium_parameters, equilibrium_data
|
||||
use gray_params, only : iequil
|
||||
|
||||
! subroutine arguments
|
||||
type(equilibrium_parameters), intent(inout) :: params
|
||||
@ -362,6 +363,8 @@ contains
|
||||
! 3. q = 1/2π ∂Φ/∂ψ ~ ∂Φ/∂r⋅∂r/∂ψ < 0.
|
||||
! 4. In general, sgn(q) = -sgn(I_p)⋅sgn(B_φ).
|
||||
|
||||
iequil = params%iequil
|
||||
|
||||
select case(iequil)
|
||||
case (EQ_ANALYTICAL) ! Analytical model
|
||||
! Apply signs
|
||||
@ -398,7 +401,7 @@ contains
|
||||
! in their respective global variables, see the top of this file.
|
||||
use const_and_precisions, only : zero, one
|
||||
use gray_params, only : equilibrium_parameters, equilibrium_data
|
||||
use gray_params, only : iequil, X_AT_TOP, X_AT_BOTTOM, X_IS_MISSING
|
||||
use gray_params, only : X_AT_TOP, X_AT_BOTTOM, X_IS_MISSING
|
||||
use utils, only : vmaxmin, vmaxmini, inside
|
||||
use logger, only : log_info
|
||||
|
||||
@ -877,7 +880,6 @@ contains
|
||||
! derivatives wrt (R, z) up to the second order.
|
||||
!
|
||||
! Note: all output arguments are optional.
|
||||
use gray_params, only : iequil
|
||||
use utils, only : inside
|
||||
use const_and_precisions, only : pi
|
||||
|
||||
@ -1030,7 +1032,6 @@ contains
|
||||
subroutine pol_curr(psi_n, fpol, dfpol)
|
||||
! Computes the poloidal current function F(ψ_n)
|
||||
! and (optionally) its derivative dF/dψ_n given ψ_n.
|
||||
use gray_params, only : iequil
|
||||
|
||||
! function arguments
|
||||
real(wp_), intent(in) :: psi_n ! normalised poloidal flux
|
||||
@ -1064,7 +1065,6 @@ contains
|
||||
|
||||
function frhotor(rho_p)
|
||||
! Converts from poloidal (ρ_p) to toroidal (ρ_t) normalised radius
|
||||
use gray_params, only : iequil
|
||||
|
||||
! function arguments
|
||||
real(wp_), intent(in) :: rho_p
|
||||
@ -1103,7 +1103,6 @@ contains
|
||||
|
||||
function frhopol(rho_t)
|
||||
! Converts from toroidal (ρ_t) to poloidal (ρ_p) normalised radius
|
||||
use gray_params, only : iequil
|
||||
use const_and_precisions, only : comp_eps
|
||||
|
||||
! function arguments
|
||||
@ -1172,7 +1171,6 @@ contains
|
||||
! poloidal flux ψ.
|
||||
!
|
||||
! Note: this returns the absolute value of q.
|
||||
use gray_params, only : iequil
|
||||
|
||||
! function arguments
|
||||
real(wp_), intent(in) :: psin
|
||||
@ -1211,7 +1209,6 @@ contains
|
||||
! (R, z) in cylindrical coordinates
|
||||
!
|
||||
! Note: all output arguments are optional.
|
||||
use gray_params, only : iequil
|
||||
|
||||
! subroutine arguments
|
||||
real(wp_), intent(in) :: R, z
|
||||
|
@ -19,9 +19,8 @@ contains
|
||||
kinetic_profiles, ec_resonance, inputs_maps
|
||||
use gray_errors, only : is_critical, print_err_raytracing, print_err_ecrh_cd
|
||||
use beams, only : xgygcoeff, launchangles2n
|
||||
use beamdata, only : pweight, rayi2jk
|
||||
use beamdata, only : pweight
|
||||
use magsurf_data, only : compute_flux_averages, dealloc_surfvec
|
||||
use beamdata, only : init_btr
|
||||
use pec, only : pec_init, spec, postproc_profiles, dealloc_pec, &
|
||||
rhop_tab, rhot_tab
|
||||
use utils, only : vmaxmin, inside
|
||||
@ -52,7 +51,7 @@ contains
|
||||
real(wp_) :: rhotp,drhotp,rhotj,drhotj,dpdvmx,jphimx,ratjamx,ratjbmx
|
||||
real(wp_) :: pabs_beam,icd_beam,cpl_beam1,cpl_beam2,cpl_cbeam1,cpl_cbeam2
|
||||
|
||||
integer :: iox,nharm,nhf,nnd,iokhawa,ierrn,ierrhcd, index_rt, parent_index_rt
|
||||
integer :: iox,nharm,nhf,iokhawa,ierrn,ierrhcd, index_rt, parent_index_rt
|
||||
integer :: ip,ib,iopmin,ipar,child_index_rt
|
||||
integer :: igrad_b,istop_pass,nbeam_pass,nlim
|
||||
logical :: ins_pl,ins_wl,ent_pl,ext_pl,ent_wl,ext_wl,iboff
|
||||
@ -70,6 +69,7 @@ contains
|
||||
nrayr => params%raytracing%nrayr, &
|
||||
nrayth => params%raytracing%nrayth, &
|
||||
nstep => params%raytracing%nstep, &
|
||||
npass => params%raytracing%ipass, &
|
||||
nbeam_tot => 2**(params%raytracing%ipass+1)-2, &
|
||||
nbeam_max => 2**(params%raytracing%ipass))
|
||||
block
|
||||
@ -116,19 +116,15 @@ contains
|
||||
! from launch angles α,β and the position
|
||||
call launchangles2n(params%antenna, anv0)
|
||||
|
||||
! Initialise the ray variables (beamtracing)
|
||||
call init_btr(params%raytracing)
|
||||
|
||||
! Initialise the dispersion module
|
||||
if(params%ecrh_cd%iwarm > 1) call expinit
|
||||
|
||||
if (params%equilibrium%iequil /= EQ_VACUUM) then
|
||||
! Initialise the magsurf_data module
|
||||
call compute_flux_averages(results%tables)
|
||||
call compute_flux_averages(params%equilibrium, results%tables)
|
||||
|
||||
! Initialise the output profiles
|
||||
call pec_init(params%output%ipec, rhout)
|
||||
nnd = size(rhop_tab) ! number of radial profile points
|
||||
call pec_init(params%output, rhout)
|
||||
end if
|
||||
|
||||
! Allocate memory for the results...
|
||||
@ -148,7 +144,9 @@ contains
|
||||
results%tables%inputs_maps = inputs_maps(params, bres, xgcn)
|
||||
|
||||
! print ψ surface for q=3/2 and q=2/1
|
||||
call find_flux_surfaces([1.5_wp_, 2.0_wp_], results%tables%flux_surfaces)
|
||||
call find_flux_surfaces( &
|
||||
qvals=[1.5_wp_, 2.0_wp_], params=params%equilibrium, &
|
||||
tbl=results%tables%flux_surfaces)
|
||||
|
||||
! print initial position
|
||||
write (msg, '("initial position:",3(x,g0.3))') params%antenna%pos
|
||||
@ -159,14 +157,14 @@ contains
|
||||
call log_info(msg, mod='gray_core', proc='gray_main')
|
||||
|
||||
! =========== main loop BEGIN ===========
|
||||
call initmultipass(params%raytracing%ipol, params%antenna%iox, &
|
||||
iroff,yynext,yypnext,yw0,ypw0, &
|
||||
stnext,p0ray,taus,tau1,etau1,cpls,cpl1,lgcpl1,psipv,chipv)
|
||||
call initmultipass(params, iroff, yynext, yypnext, yw0, ypw0, &
|
||||
stnext, p0ray, taus, tau1, etau1, cpls, &
|
||||
cpl1, lgcpl1, psipv, chipv)
|
||||
|
||||
sox=1 ! mode inverted for each beam
|
||||
iox=2 ! start with O: sox=-1, iox=1
|
||||
|
||||
call pweight(params%antenna%power, p0jk)
|
||||
call pweight(params%raytracing, params%antenna%power, p0jk)
|
||||
|
||||
! Set original polarisation
|
||||
psipv(0) = params%antenna%psi
|
||||
@ -267,10 +265,11 @@ contains
|
||||
do jk=1,params%raytracing%nray
|
||||
if(iwait(jk)) cycle ! jk ray is waiting for next pass
|
||||
stv(jk) = stv(jk) + params%raytracing%dst ! current ray step
|
||||
call rkstep(sox,bres,xgcn,yw(:,jk),ypw(:,jk),gri(:,jk),ggri(:,:,jk),igrad_b)
|
||||
call rkstep(params, sox, bres, xgcn, yw(:,jk), ypw(:,jk), &
|
||||
gri(:,jk), ggri(:,:,jk), igrad_b)
|
||||
end do
|
||||
! update position and grad
|
||||
if(igrad_b == 1) call gradi_upd(yw,ak0,xc,du1,gri,ggri)
|
||||
if(igrad_b == 1) call gradi_upd(params%raytracing, yw, ak0, xc, du1, gri, ggri)
|
||||
|
||||
error = 0
|
||||
iopmin = 10
|
||||
@ -282,9 +281,9 @@ contains
|
||||
! compute derivatives with updated gradient and local plasma values
|
||||
xv = yw(1:3,jk)
|
||||
anv = yw(4:6,jk)
|
||||
call ywppla_upd(xv,anv,gri(:,jk),ggri(:,:,jk),sox,bres,xgcn,ypw(:,jk), &
|
||||
psinv,dens,btot,bv,xg,yg,derxg,anpl,anpr,ddr,ddi,dersdst,derdnm, &
|
||||
ierrn,igrad_b)
|
||||
call ywppla_upd(params, xv, anv, gri(:,jk), ggri(:,:,jk), sox, bres, &
|
||||
xgcn,ypw(:,jk), psinv, dens, btot, bv, xg, yg, derxg, &
|
||||
anpl, anpr, ddr, ddi, dersdst, derdnm, ierrn, igrad_b)
|
||||
! update global error code and print message
|
||||
if(ierrn/=0) then
|
||||
error = ior(error,ierrn)
|
||||
@ -316,7 +315,7 @@ contains
|
||||
if(iop(jk) == 1 .and. ip==1) then ! * 1st entrance on 1st pass (ray hasn't entered in plasma yet) => continue current pass
|
||||
|
||||
if(cpl(iox) < etaucr) then ! + 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,npass,2*ib+2-iox,iroff)
|
||||
iwait(jk) = .true. ! . stop advancement and H&CD computation for current ray
|
||||
if(cpl(iox).le.comp_tiny) cpl(iox)=etaucr
|
||||
else ! + ELSE assign coupled power to current ray
|
||||
@ -345,11 +344,11 @@ contains
|
||||
stnext(jk,index_rt) = stv(jk) - params%raytracing%dst ! . starting step for next pass = last step
|
||||
|
||||
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,npass,2*ib-1,iroff)
|
||||
if(cpl(1).le.comp_tiny) cpl(1)=etaucr
|
||||
end if
|
||||
if(cpl(2) < etaucr) then ! . low coupled power for X-mode => de-activate derived rays
|
||||
call turnoffray(jk,ip+1,2*ib,iroff)
|
||||
call turnoffray(jk,ip+1,npass,2*ib,iroff)
|
||||
if(cpl(2).le.comp_tiny) cpl(2)=etaucr
|
||||
end if
|
||||
|
||||
@ -376,13 +375,15 @@ contains
|
||||
iow(jk)=iow(jk)+1 ! * out->in
|
||||
|
||||
else if(ext_wl) then ! ray exit vessel
|
||||
call wall_out(jk,ins_pl,xv,anv,bres,sox,psipol,chipol,iow,iop,ext,eyt)
|
||||
call wall_out(jk, ins_pl, xv, anv, params%raytracing%dst, &
|
||||
bres, sox, psipol, chipol, iow, iop, ext, eyt)
|
||||
yw(:,jk) = [xv, anv] ! * updated coordinates (reflected)
|
||||
igrad_b = 0 ! * switch to ray-tracing
|
||||
|
||||
call ywppla_upd(xv,anv,gri(:,jk),ggri(:,:,jk),sox,bres,xgcn,ypw(:,jk), &
|
||||
psinv,dens,btot,bv,xg,yg,derxg,anpl,anpr,ddr,ddi,dersdst,derdnm, &
|
||||
ierrn,igrad_b) ! * update derivatives after reflection
|
||||
call ywppla_upd(params, xv, anv, gri(:,jk), ggri(:,:,jk), sox, &
|
||||
bres, xgcn, ypw(:,jk), psinv, dens, btot, bv, &
|
||||
xg, yg, derxg, anpl, anpr, ddr, ddi, dersdst, &
|
||||
derdnm, ierrn, igrad_b) ! * update derivatives after reflection
|
||||
if(ierrn/=0) then ! * update global error code and print message
|
||||
error = ior(error,ierrn)
|
||||
call print_err_raytracing(ierrn, i, anpl)
|
||||
@ -405,11 +406,11 @@ contains
|
||||
iop, ext, eyt, perfect=.false.)
|
||||
|
||||
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,npass,2*ib-1,iroff)
|
||||
if(cpl(1).le.comp_tiny) cpl(1)=etaucr
|
||||
end if
|
||||
if(cpl(2) < etaucr) then ! . low coupled power for X-mode? => de-activate derived rays
|
||||
call turnoffray(jk,ip+1,2*ib,iroff)
|
||||
call turnoffray(jk,ip+1,npass,2*ib,iroff)
|
||||
if(cpl(2).le.comp_tiny) cpl(2)=etaucr
|
||||
end if
|
||||
|
||||
@ -485,7 +486,7 @@ contains
|
||||
ccci(jk,i:params%raytracing%nstep) = ccci(jk,i-1)
|
||||
psjki(jk,i:params%raytracing%nstep) = psjki(jk,i-1)
|
||||
else
|
||||
call store_ray_data(results%tables, &
|
||||
call store_ray_data(params, results%tables, &
|
||||
i, jk, stv(jk), p0ray(jk), xv, psinv, btot, bv, ak0, &
|
||||
anpl, anpr, anv, anprim, dens, tekev, alpha, tau, dids, &
|
||||
nharm, nhf, iokhawa, index_rt, ddr, ddi, xg, yg, derxg) ! p0ray/etau1 [dids normalization] = fraction of p0 coupled to this ray (not including absorption from previous passes)
|
||||
@ -496,7 +497,7 @@ contains
|
||||
|
||||
if(i==params%raytracing%nstep) then ! step limit reached?
|
||||
do jk=1,params%raytracing%nray
|
||||
if(iop(jk)<3) call turnoffray(jk,ip,ib,iroff) ! * ray hasn't exited+reentered the plasma by last step => stop ray
|
||||
if(iop(jk)<3) call turnoffray(jk,ip,npass,ib,iroff) ! * ray hasn't exited+reentered the plasma by last step => stop ray
|
||||
end do
|
||||
end if
|
||||
|
||||
@ -511,7 +512,7 @@ contains
|
||||
|
||||
if(is_critical(error)) then ! stop propagation for current beam
|
||||
istop_pass = istop_pass +1 ! * +1 non propagating beam
|
||||
if(ip < params%raytracing%ipass) call turnoffray(0,ip,ib,iroff) ! * de-activate derived beams
|
||||
if(ip < params%raytracing%ipass) call turnoffray(0,ip,npass,ib,iroff) ! * de-activate derived beams
|
||||
exit
|
||||
else if(all(iwait)) then ! all rays in current beam are waiting for next pass => do not increase istop_pass
|
||||
exit
|
||||
@ -534,8 +535,9 @@ contains
|
||||
|
||||
if (params%equilibrium%iequil /= EQ_VACUUM) then
|
||||
! compute power and current density profiles for all rays
|
||||
call spec(psjki,ppabs,ccci,iiv,pabs_beam,icd_beam,dpdv_beam, &
|
||||
jphi_beam,jcd_beam,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
|
||||
@ -668,7 +670,6 @@ contains
|
||||
end subroutine vectinit
|
||||
|
||||
|
||||
|
||||
subroutine ic_gb(params, anv0c, ak0, ywrk0, ypwrk0, &
|
||||
stv, xc0, du10, gri, ggri, index_rt, &
|
||||
tables)
|
||||
@ -676,7 +677,6 @@ contains
|
||||
! !!!!!! check ray tracing initial conditions igrad=0 !!!!!!
|
||||
use const_and_precisions, only : zero,one,pi,half,two,degree,ui=>im
|
||||
use gray_params, only : gray_parameters, gray_tables
|
||||
use beamdata, only : nray,nrayr,nrayth,rwmax
|
||||
use types, only : table
|
||||
use gray_tables, only : store_ray_data
|
||||
|
||||
@ -684,11 +684,11 @@ contains
|
||||
type(gray_parameters), intent(in) :: params
|
||||
real(wp_), dimension(3), intent(in) :: anv0c
|
||||
real(wp_), intent(in) :: ak0
|
||||
real(wp_), dimension(6, nray), intent(out) :: ywrk0, ypwrk0
|
||||
real(wp_), dimension(nrayth * nrayr), intent(out) :: stv
|
||||
real(wp_), dimension(3, nrayth, nrayr), intent(out) :: xc0, du10
|
||||
real(wp_), dimension(3, nray), intent(out) :: gri
|
||||
real(wp_), dimension(3, 3, nray), intent(out) :: ggri
|
||||
real(wp_), dimension(6, params%raytracing%nray), intent(out) :: ywrk0, ypwrk0
|
||||
real(wp_), dimension(params%raytracing%nrayth * params%raytracing%nrayr), intent(out) :: stv
|
||||
real(wp_), dimension(3, params%raytracing%nrayth, params%raytracing%nrayr), intent(out) :: xc0, du10
|
||||
real(wp_), dimension(3, params%raytracing%nray), intent(out) :: gri
|
||||
real(wp_), dimension(3, 3, params%raytracing%nray), intent(out) :: ggri
|
||||
integer, intent(in) :: index_rt
|
||||
|
||||
! tables for storing initial rays data
|
||||
@ -707,8 +707,8 @@ contains
|
||||
real(wp_) :: dgr2x,dgr2y,dgr2z,pppx,pppy,denpp,ppx,ppy
|
||||
real(wp_) :: anzt,anxt,anyt,anx,any,anz,an20,an0
|
||||
real(wp_) :: du1tx,du1ty,du1tz,denom,ddr,ddi
|
||||
real(wp_), dimension(nrayr) :: uj
|
||||
real(wp_), dimension(nrayth) :: sna,csa
|
||||
real(wp_), dimension(params%raytracing%nrayr) :: uj
|
||||
real(wp_), dimension(params%raytracing%nrayth) :: sna,csa
|
||||
complex(wp_) :: sss,ddd,phic,qi1,qi2,tc,ts,qqxx,qqxy,qqyy,dqi1,dqi2
|
||||
complex(wp_) :: dqqxx,dqqyy,dqqxy,d2qi1,d2qi2,d2qqxx,d2qqyy,d2qqxy
|
||||
|
||||
@ -811,18 +811,18 @@ contains
|
||||
drciyy = real(dqqyy)
|
||||
drcixy = real(dqqxy)
|
||||
|
||||
if(nrayr > 1) then
|
||||
dr = rwmax/(nrayr-1)
|
||||
if(params%raytracing%nrayr > 1) then
|
||||
dr = params%raytracing%rwmax / (params%raytracing%nrayr - 1)
|
||||
else
|
||||
dr = one
|
||||
dr = 1
|
||||
end if
|
||||
ddfu = two*dr**2/ak0 ! twodr2 = 2*dr**2 = 2*rwmax/real(nrayr-1)
|
||||
do j = 1, nrayr
|
||||
ddfu = 2*dr**2/ak0
|
||||
do j = 1, params%raytracing%nrayr
|
||||
uj(j) = real(j-1, wp_)
|
||||
end do
|
||||
|
||||
da=2*pi/nrayth
|
||||
do k=1,nrayth
|
||||
da=2*pi/params%raytracing%nrayth
|
||||
do k=1,params%raytracing%nrayth
|
||||
alfak = (k-1)*da
|
||||
sna(k) = sin(alfak)
|
||||
csa(k) = cos(alfak)
|
||||
@ -838,7 +838,7 @@ contains
|
||||
ypwrk0(1:3,1) = anv0c
|
||||
ypwrk0(4:6,1) = zero
|
||||
|
||||
do k=1,nrayth
|
||||
do k=1,params%raytracing%nrayth
|
||||
dcsiw = dr*csa(k)*wcsi
|
||||
detaw = dr*sna(k)*weta
|
||||
dx0t = dcsiw*csphiw - detaw*snphiw
|
||||
@ -857,9 +857,9 @@ contains
|
||||
! loop on rays jk>1
|
||||
j=2
|
||||
k=0
|
||||
do jk=2,nray
|
||||
do jk = 2, params%raytracing%nray
|
||||
k=k+1
|
||||
if(k > nrayth) then
|
||||
if(k > params%raytracing%nrayth) then
|
||||
j=j+1
|
||||
k=1
|
||||
end if
|
||||
@ -989,7 +989,7 @@ contains
|
||||
|
||||
! save step "zero" data
|
||||
if (present(tables)) &
|
||||
call store_ray_data(tables, &
|
||||
call store_ray_data(params, tables, &
|
||||
i=0, jk=jk, s=stv(jk), P0=one, pos=xc0(:,k,j), &
|
||||
psi_n=-one, B=zero, b_n=[zero,zero,zero], k0=ak0, &
|
||||
N_pl=zero, N_pr=zero, N=ywrk0(:, jk), N_pr_im=zero, &
|
||||
@ -1003,80 +1003,99 @@ contains
|
||||
|
||||
|
||||
|
||||
subroutine rkstep(sox,bres,xgcn,y,yp,dgr,ddgr,igrad)
|
||||
! Runge-Kutta integrator
|
||||
! use gray_params, only : igrad
|
||||
use beamdata, only : h,hh,h6
|
||||
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
|
||||
subroutine rkstep(params, sox, bres, xgcn, y, yp, dgr, ddgr, igrad)
|
||||
! Runge-Kutta integrator
|
||||
use gray_params, only : gray_parameters
|
||||
|
||||
! subroutine arguments
|
||||
type(gray_parameters), intent(in) :: params
|
||||
real(wp_), intent(in) :: bres, xgcn
|
||||
real(wp_), intent(inout) :: y(6)
|
||||
real(wp_), intent(in) :: yp(6)
|
||||
real(wp_), intent(in) :: dgr(3)
|
||||
real(wp_), intent(in) :: ddgr(3,3)
|
||||
integer, intent(in) :: igrad,sox
|
||||
|
||||
real(wp_), dimension(6) :: yy,fk1,fk2,fk3,fk4
|
||||
! local variables
|
||||
real(wp_), dimension(6) :: k1, k2, k3, k4
|
||||
|
||||
fk1 = yp
|
||||
yy = y + fk1*hh
|
||||
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)
|
||||
associate (h => params%raytracing%dst)
|
||||
k1 = yp
|
||||
k2 = f(y + k1*h/2)
|
||||
k3 = f(y + k2*h/2)
|
||||
k4 = f(y + k3*h)
|
||||
y = y + h * (k1/6 + k2/3 + k3/3 + k4/6)
|
||||
end associate
|
||||
|
||||
y = y + h6*(fk1 + 2*fk2 + 2*fk3 + fk4)
|
||||
contains
|
||||
|
||||
function f(y)
|
||||
real(wp_), intent(in) :: y(6)
|
||||
real(wp_) :: f(6)
|
||||
call rhs(params, sox, bres, xgcn, y, dgr, ddgr, f, igrad)
|
||||
end function
|
||||
end subroutine rkstep
|
||||
|
||||
|
||||
subroutine rhs(params, sox, bres, xgcn, y, dgr, ddgr, dery, igrad)
|
||||
! Compute right-hand side terms of the ray equations (dery)
|
||||
! used in R-K integrator
|
||||
use gray_params, only : gray_parameters
|
||||
|
||||
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
|
||||
! 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
|
||||
! subroutine arguments
|
||||
type(gray_parameters), intent(in) :: params
|
||||
real(wp_), intent(in) :: y(6)
|
||||
real(wp_), intent(in) :: bres, xgcn
|
||||
real(wp_), intent(in) :: dgr(3)
|
||||
real(wp_), intent(in) :: ddgr(3,3)
|
||||
real(wp_), intent(out) :: dery(6)
|
||||
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)
|
||||
call plas_deriv(xv,bres,xgcn,dens,btot,bv,derbv,xg,yg,derxg,deryg)
|
||||
call plas_deriv(params, xv, bres, xgcn, dens, btot, &
|
||||
bv, derbv, xg, yg, derxg, deryg)
|
||||
anv = y(4:6)
|
||||
call disp_deriv(anv,sox,xg,yg,derxg,deryg,bv,derbv,dgr,ddgr,igrad,dery)
|
||||
call disp_deriv(params, anv, sox, xg, yg, derxg, deryg, &
|
||||
bv, derbv, dgr, ddgr, igrad, dery)
|
||||
end subroutine rhs
|
||||
|
||||
|
||||
|
||||
subroutine ywppla_upd(xv,anv,dgr,ddgr,sox,bres,xgcn,dery,psinv,dens,btot, &
|
||||
bv,xg,yg,derxg,anpl,anpr,ddr,ddi,dersdst,derdnm,error,igrad)
|
||||
! Compute right-hand side terms of the ray equations (dery)
|
||||
! used after full R-K step and grad(S_I) update
|
||||
subroutine ywppla_upd(params, xv, anv, dgr, ddgr, sox, bres, xgcn, dery, &
|
||||
psinv, dens, btot, bv, xg, yg, derxg, anpl, anpr, &
|
||||
ddr, ddi, dersdst, derdnm, error, igrad)
|
||||
! Compute right-hand side terms of the ray equations (dery)
|
||||
! used after full R-K step and grad(S_I) update
|
||||
use gray_errors, only : raise_error, large_npl
|
||||
! arguments
|
||||
real(wp_), dimension(3), intent(in) :: xv,anv
|
||||
real(wp_), dimension(3), intent(in) :: dgr
|
||||
real(wp_), dimension(3,3), intent(in) :: ddgr
|
||||
use gray_params, only : gray_parameters
|
||||
|
||||
! subroutine rguments
|
||||
type(gray_parameters), intent(in) :: params
|
||||
|
||||
real(wp_), intent(in) :: xv(3), anv(3)
|
||||
real(wp_), intent(in) :: dgr(3)
|
||||
real(wp_), intent(in) :: ddgr(3,3)
|
||||
integer, intent(in) :: sox
|
||||
real(wp_), intent(in) :: bres,xgcn
|
||||
real(wp_), dimension(6), intent(out) :: dery
|
||||
real(wp_), intent(out) :: psinv,dens,btot,xg,yg,anpl,anpr
|
||||
real(wp_), intent(out) :: ddr,ddi,dersdst,derdnm
|
||||
real(wp_), dimension(3), intent(out) :: bv
|
||||
real(wp_), intent(out) :: dery(6)
|
||||
real(wp_), intent(out) :: psinv, dens, btot, xg, yg, anpl, anpr
|
||||
real(wp_), intent(out) :: ddr, ddi, dersdst, derdnm
|
||||
real(wp_), intent(out) :: bv(3)
|
||||
integer, intent(out) :: error
|
||||
real(wp_), dimension(3), intent(out) :: derxg
|
||||
real(wp_), intent(out) :: derxg(3)
|
||||
integer, intent(in) :: igrad
|
||||
! local variables
|
||||
|
||||
! local variables
|
||||
real(wp_), dimension(3) :: deryg
|
||||
real(wp_), dimension(3,3) :: derbv
|
||||
real(wp_), parameter :: anplth1 = 0.99_wp_, anplth2 = 1.05_wp_
|
||||
|
||||
call plas_deriv(xv,bres,xgcn,dens,btot,bv,derbv,xg,yg,derxg,deryg,psinv)
|
||||
call disp_deriv(anv,sox,xg,yg,derxg,deryg,bv,derbv,dgr,ddgr,igrad, &
|
||||
call plas_deriv(params, xv,bres,xgcn,dens,btot,bv,derbv,xg,yg,derxg,deryg,psinv)
|
||||
call disp_deriv(params, anv,sox,xg,yg,derxg,deryg,bv,derbv,dgr,ddgr,igrad, &
|
||||
dery,anpl,anpr,ddr,ddi,dersdst,derdnm)
|
||||
|
||||
if (abs(anpl) > anplth2) then
|
||||
@ -1089,45 +1108,48 @@ contains
|
||||
end subroutine ywppla_upd
|
||||
|
||||
|
||||
subroutine gradi_upd(params, ywrk,ak0,xc,du1,gri,ggri)
|
||||
use const_and_precisions, only : zero, half
|
||||
use gray_params, only : raytracing_parameters
|
||||
|
||||
subroutine gradi_upd(ywrk,ak0,xc,du1,gri,ggri)
|
||||
use const_and_precisions, only : zero,half
|
||||
use beamdata, only : nray,nrayr,nrayth,twodr2
|
||||
! subroutine parameters
|
||||
type(raytracing_parameters), intent(in) :: params
|
||||
real(wp_), intent(in) :: ak0
|
||||
real(wp_), dimension(6,nray), intent(in) :: ywrk
|
||||
real(wp_), dimension(3,nrayth,nrayr), intent(inout) :: xc,du1
|
||||
real(wp_), dimension(3,nray), intent(out) :: gri
|
||||
real(wp_), dimension(3,3,nray), intent(out) :: ggri
|
||||
! local variables
|
||||
real(wp_), dimension(3,nrayth,nrayr) :: xco,du1o
|
||||
integer :: jk,j,jm,jp,k,km,kp
|
||||
real(wp_) :: ux,uxx,uxy,uxz,uy,uyy,uyz,uz,uzz
|
||||
real(wp_) :: dfuu,dffiu,gx,gxx,gxy,gxz,gy,gyy,gyz,gz,gzz
|
||||
real(wp_), dimension(3) :: dxv1,dxv2,dxv3,dgu
|
||||
real(wp_), dimension(3,3) :: dgg,dff
|
||||
real(wp_), dimension(6,params%nray), intent(in) :: ywrk
|
||||
real(wp_), dimension(3,params%nrayth,params%nrayr), intent(inout) :: xc, du1
|
||||
real(wp_), dimension(3,params%nray), intent(out) :: gri
|
||||
real(wp_), dimension(3,3,params%nray), intent(out) :: ggri
|
||||
|
||||
! update position and du1 vectors
|
||||
! local variables
|
||||
real(wp_), dimension(3,params%nrayth,params%nrayr) :: xco, du1o
|
||||
integer :: jk, j, jm, jp, k, km, kp
|
||||
real(wp_) :: ux, uxx, uxy, uxz, uy, uyy, uyz, uz, uzz
|
||||
real(wp_) :: dr, dfuu, dffiu, gx, gxx, gxy, gxz, gy, gyy, gyz, gz, gzz
|
||||
real(wp_), dimension(3) :: dxv1, dxv2, dxv3, dgu
|
||||
real(wp_), dimension(3,3) :: dgg, dff
|
||||
|
||||
! update position and du1 vectors
|
||||
xco = xc
|
||||
du1o = du1
|
||||
|
||||
jk = 1
|
||||
do j=1,nrayr
|
||||
do k=1,nrayth
|
||||
do j=1,params%nrayr
|
||||
do k=1,params%nrayth
|
||||
if(j>1) jk=jk+1
|
||||
xc(1:3,k,j)=ywrk(1:3,jk)
|
||||
end do
|
||||
end do
|
||||
|
||||
! compute grad u1 for central ray
|
||||
! compute grad u1 for central ray
|
||||
j = 1
|
||||
jp = 2
|
||||
do k=1,nrayth
|
||||
do k=1,params%nrayth
|
||||
if(k == 1) then
|
||||
km = nrayth
|
||||
km = params%nrayth
|
||||
else
|
||||
km = k-1
|
||||
end if
|
||||
if(k == nrayth) then
|
||||
if(k == params%nrayth) then
|
||||
kp = 1
|
||||
else
|
||||
kp = k+1
|
||||
@ -1140,15 +1162,20 @@ contains
|
||||
end do
|
||||
gri(:,1) = zero
|
||||
|
||||
! compute grad u1 and grad(S_I) for all the other rays
|
||||
dfuu=twodr2/ak0 ! twodr2 = 2*dr**2 = 2*(rwmax/(nrayr-1))**2
|
||||
! compute grad u1 and grad(S_I) for all the other rays
|
||||
if (params%nrayr > 1) then
|
||||
dr = params%rwmax / (params%nrayr - 1)
|
||||
else
|
||||
dr = 1
|
||||
end if
|
||||
dfuu=2*dr**2/ak0
|
||||
jm=1
|
||||
j=2
|
||||
k=0
|
||||
dffiu = dfuu
|
||||
do jk=2,nray
|
||||
do jk=2,params%nray
|
||||
k=k+1
|
||||
if(k > nrayth) then
|
||||
if(k > params%nrayth) then
|
||||
jm = j
|
||||
j = j+1
|
||||
k = 1
|
||||
@ -1157,8 +1184,8 @@ contains
|
||||
kp = k+1
|
||||
km = k-1
|
||||
if (k == 1) then
|
||||
km=nrayth
|
||||
else if (k == nrayth) then
|
||||
km=params%nrayth
|
||||
else if (k == params%nrayth) then
|
||||
kp=1
|
||||
end if
|
||||
dxv1 = xc(:,k ,j) - xc(:,k ,jm)
|
||||
@ -1169,15 +1196,15 @@ contains
|
||||
gri(:,jk) = dgu(:)*dffiu
|
||||
end do
|
||||
|
||||
! compute derivatives of grad u and grad(S_I) for rays jk>1
|
||||
! compute derivatives of grad u and grad(S_I) for rays jk>1
|
||||
ggri(:,:,1) = zero
|
||||
jm=1
|
||||
j=2
|
||||
k=0
|
||||
dffiu = dfuu
|
||||
do jk=2,nray
|
||||
do jk=2,params%nray
|
||||
k=k+1
|
||||
if(k > nrayth) then
|
||||
if(k > params%nrayth) then
|
||||
jm=j
|
||||
j=j+1
|
||||
k=1
|
||||
@ -1186,8 +1213,8 @@ contains
|
||||
kp=k+1
|
||||
km=k-1
|
||||
if (k == 1) then
|
||||
km=nrayth
|
||||
else if (k == nrayth) then
|
||||
km=params%nrayth
|
||||
else if (k == params%nrayth) then
|
||||
kp=1
|
||||
end if
|
||||
dxv1 = xc(:,k ,j) - xc(:,k ,jm)
|
||||
@ -1198,7 +1225,7 @@ contains
|
||||
dff(:,3) = du1(:,k ,j) - du1o(:,k ,j)
|
||||
call solg3(dxv1,dxv2,dxv3,dff,dgg)
|
||||
|
||||
! derivatives of u
|
||||
! derivatives of u
|
||||
ux = du1(1,k,j)
|
||||
uy = du1(2,k,j)
|
||||
uz = du1(3,k,j)
|
||||
@ -1209,7 +1236,7 @@ contains
|
||||
uxz = (dgg(1,3) + dgg(3,1))*half
|
||||
uyz = (dgg(2,3) + dgg(3,2))*half
|
||||
|
||||
! derivatives of S_I and Grad(S_I)
|
||||
! derivatives of S_I and Grad(S_I)
|
||||
gx = ux*dffiu
|
||||
gy = uy*dffiu
|
||||
gz = uz*dffiu
|
||||
@ -1286,15 +1313,15 @@ contains
|
||||
end subroutine solg3
|
||||
|
||||
|
||||
|
||||
subroutine plas_deriv(xv, bres, xgcn, dens, btot, bv, derbv, &
|
||||
xg, yg, derxg, deryg, psinv_opt)
|
||||
subroutine plas_deriv(params, xv, bres, xgcn, dens, btot, bv, &
|
||||
derbv, xg, yg, derxg, deryg, psinv_opt)
|
||||
use const_and_precisions, only : zero, cm
|
||||
use gray_params, only : iequil
|
||||
use gray_params, only : gray_parameters, EQ_VACUUM
|
||||
use equilibrium, only : psia, pol_flux, pol_curr, sgnbphi
|
||||
use coreprofiles, only : density
|
||||
|
||||
! subroutine arguments
|
||||
type(gray_parameters), intent(in) :: params
|
||||
real(wp_), dimension(3), intent(in) :: xv
|
||||
real(wp_), intent(in) :: xgcn, bres
|
||||
real(wp_), intent(out) :: dens, btot, xg, yg
|
||||
@ -1322,7 +1349,7 @@ contains
|
||||
bv = zero
|
||||
derbv = zero
|
||||
|
||||
if(iequil==0) then
|
||||
if (params%equilibrium%iequil == EQ_VACUUM) then
|
||||
! copy optional output
|
||||
if (present(psinv_opt)) psinv_opt = psinv
|
||||
return
|
||||
@ -1437,7 +1464,7 @@ contains
|
||||
|
||||
|
||||
|
||||
subroutine disp_deriv(anv, sox, xg, yg, derxg, deryg, bv, derbv, &
|
||||
subroutine disp_deriv(params, anv, sox, xg, yg, derxg, deryg, bv, derbv, &
|
||||
dgr, ddgr, igrad, dery, anpl_, anpr, ddr, ddi, &
|
||||
dersdst, derdnm_)
|
||||
! Computes the dispersion relation, derivatives and other
|
||||
@ -1449,12 +1476,14 @@ contains
|
||||
! computing the absoprtion and current drive.
|
||||
|
||||
use const_and_precisions, only : zero, one, half, two
|
||||
use gray_params, only : idst
|
||||
use gray_params, only : gray_parameters, STEP_ARCLEN, &
|
||||
STEP_TIME, STEP_PHASE
|
||||
|
||||
! subroutine arguments
|
||||
|
||||
! Inputs
|
||||
|
||||
type(gray_parameters), intent(in) :: params
|
||||
! refractive index N̅ vector, b̅ = B̅/B magnetic field direction
|
||||
real(wp_), dimension(3), intent(in) :: anv, bv
|
||||
! sign of polarisation mode: -1 ⇒ O, +1 ⇒ X
|
||||
@ -1631,13 +1660,13 @@ contains
|
||||
! dx̅/dσ = + ∂Λ/∂N̅ / denom
|
||||
! dN̅/dσ = - ∂Λ/∂x̅ / denom
|
||||
!
|
||||
select case (idst)
|
||||
case (0) ! σ=s, arclength
|
||||
select case (params%raytracing%idst)
|
||||
case (STEP_ARCLEN) ! σ=s, arclength
|
||||
! denom = |∂Λ/∂N̅|
|
||||
! Proof: Normalising ∂Λ/∂N̅ (∥ to the group velocity)
|
||||
! simply makes σ the arclength parameter s.
|
||||
denom = derdnm
|
||||
case (1) ! σ=ct, time
|
||||
case (STEP_TIME) ! σ=ct, time
|
||||
! denom = -ω⋅∂Λ/∂ω
|
||||
! Proof: The Hamilton equations are
|
||||
!
|
||||
@ -1656,7 +1685,7 @@ contains
|
||||
! dN̅/d(ct) = - ∂Λ/∂x̅ / (-ω⋅∂Λ/∂ω)
|
||||
!
|
||||
denom = -derdom
|
||||
case (2) ! s=S_R, phase
|
||||
case (STEP_PHASE) ! s=S_R, phase
|
||||
! denom = N̅⋅∂Λ/∂N̅
|
||||
! Note: This parametrises the curve by the value
|
||||
! of the (real) phase, with the wave frozen in time.
|
||||
|
@ -30,7 +30,7 @@ subroutine gray_jetto1beam(ijetto, mr, mz, r, z, psin, psia, rax, zax, &
|
||||
|
||||
! Read parameters from external file
|
||||
init_params: block
|
||||
use gray_params, only : read_gray_params, set_globals
|
||||
use gray_params, only : read_gray_params
|
||||
call read_gray_params('gray.data', params, err)
|
||||
if (err /= 0) return
|
||||
|
||||
@ -44,9 +44,6 @@ subroutine gray_jetto1beam(ijetto, mr, mz, r, z, psin, psia, rax, zax, &
|
||||
params%profiles%iprof = 1
|
||||
params%output%ipec = 1
|
||||
params%output%nrho = nrho
|
||||
|
||||
! Set the global variables of `gray_params`
|
||||
call set_globals(params)
|
||||
end block init_params
|
||||
|
||||
! Set a simple limiter following the boundary of the data grid
|
||||
|
@ -255,14 +255,6 @@ module gray_params
|
||||
type(gray_tables) :: tables ! Extra outputs
|
||||
end type
|
||||
|
||||
|
||||
! Global variables exposed for gray_core
|
||||
integer, save :: iequil, iprof
|
||||
integer, save :: iwarm, ilarm, imx, ieccd
|
||||
integer, save :: igrad, idst, ipass
|
||||
integer, save :: istpr0, istpl0
|
||||
integer, save :: ipec, nnd
|
||||
|
||||
contains
|
||||
|
||||
function make_gray_header(params) result(header)
|
||||
@ -563,38 +555,4 @@ contains
|
||||
params%raytracing%nray = 1 + (params%raytracing%nrayr-1) * params%raytracing%nrayth
|
||||
end subroutine read_gray_params
|
||||
|
||||
|
||||
subroutine set_globals(params)
|
||||
! Set global variables exposed by this module.
|
||||
|
||||
use logger, only : log_warning
|
||||
|
||||
! subroutine arguments
|
||||
type(gray_parameters), intent(inout) :: params
|
||||
|
||||
iequil = params%equilibrium%iequil
|
||||
iprof = params%profiles%iprof
|
||||
|
||||
ipec = params%output%ipec
|
||||
nnd = params%output%nrho
|
||||
istpr0 = params%output%istpr
|
||||
istpl0 = params%output%istpl
|
||||
|
||||
if (params%raytracing%nrayr < 5) then
|
||||
params%raytracing%igrad = 0
|
||||
call log_warning('nrayr < 5 ⇒ optical case only', &
|
||||
mod="gray_params", proc="set_globals")
|
||||
end if
|
||||
|
||||
igrad = params%raytracing%igrad
|
||||
idst = params%raytracing%idst
|
||||
ipass = params%raytracing%ipass
|
||||
|
||||
iwarm = params%ecrh_cd%iwarm
|
||||
ilarm = params%ecrh_cd%ilarm
|
||||
imx = params%ecrh_cd%imx
|
||||
ieccd = params%ecrh_cd%ieccd
|
||||
|
||||
end subroutine set_globals
|
||||
|
||||
end module gray_params
|
||||
|
@ -284,10 +284,11 @@ contains
|
||||
end function inputs_maps
|
||||
|
||||
|
||||
subroutine find_flux_surfaces(qvals, tbl)
|
||||
subroutine find_flux_surfaces(qvals, params, tbl)
|
||||
! Finds the ψ for a set of values of q and stores the
|
||||
! associated surfaces to the flux surface table
|
||||
|
||||
use gray_params, only : equilibrium_parameters
|
||||
use equilibrium, only : fq, frhotor, rmaxis, zmaxis, zbsup, zbinf
|
||||
use magsurf_data, only : contours_psi, npoints
|
||||
use logger, only : log_info
|
||||
@ -296,6 +297,7 @@ contains
|
||||
|
||||
! subroutine arguments
|
||||
real(wp_), intent(in) :: qvals(:)
|
||||
type(equilibrium_parameters), intent(in) :: params
|
||||
type(table), intent(inout) :: tbl
|
||||
|
||||
! local variables
|
||||
@ -336,7 +338,7 @@ contains
|
||||
R_lo = rmaxis
|
||||
z_lo = (zbinf + zmaxis)/2
|
||||
|
||||
call contours_psi(psi_n, R_cont, z_cont, R_hi, z_hi, R_lo, z_lo)
|
||||
call contours_psi(params, psi_n, R_cont, z_cont, R_hi, z_hi, R_lo, z_lo)
|
||||
call store_flux_surface(tbl, psi_n, R_cont, z_cont)
|
||||
end block
|
||||
|
||||
@ -398,7 +400,7 @@ contains
|
||||
end subroutine store_flux_surface
|
||||
|
||||
|
||||
subroutine store_ray_data(tables, &
|
||||
subroutine store_ray_data(params, tables, &
|
||||
i, jk, s, P0, pos, psi_n, B, b_n, k0, &
|
||||
N_pl, N_pr, N, N_pr_im, n_e, T_e, &
|
||||
alpha, tau, dIds, nhm, nhf, iokhawa, &
|
||||
@ -407,12 +409,13 @@ contains
|
||||
|
||||
use const_and_precisions, only : degree, cm
|
||||
use equilibrium, only : frhotor
|
||||
use gray_params, only : gray_tables, istpl0
|
||||
use beamdata, only : nray,nrayth,jkray1
|
||||
use gray_params, only : gray_parameters, gray_tables
|
||||
use beamdata, only : unfold_index
|
||||
|
||||
! subroutine arguments
|
||||
|
||||
! tables where to store the data
|
||||
type(gray_parameters), intent(in) :: params
|
||||
type(gray_tables), intent(inout) :: tables
|
||||
|
||||
integer, intent(in) :: i, jk ! step, ray index
|
||||
@ -438,7 +441,7 @@ contains
|
||||
! local variables
|
||||
real(wp_) :: s_m, pos_m(3), R_m, phi_deg ! coordinates in SI units
|
||||
real(wp_) :: rho_t, k_im, Pt, dIds_n
|
||||
integer :: k
|
||||
integer :: jkv(2)
|
||||
|
||||
s_m = s * cm
|
||||
pos_m = pos * cm
|
||||
@ -467,18 +470,18 @@ contains
|
||||
end if
|
||||
|
||||
! Store outer rays data
|
||||
if (mod(i, istpl0) == 0) then
|
||||
k = jk - jkray1 + 1
|
||||
if(k > 0 .and. k <= nrayth .and. tables%outer_rays%active) then
|
||||
if (mod(i, params%output%istpl) == 0) then
|
||||
jkv = unfold_index(params%raytracing, jk) ! (j,k)
|
||||
if(jkv(1) == params%raytracing%nrayr .and. tables%outer_rays%active) then
|
||||
call tables%outer_rays%append([ &
|
||||
wrap(i), wrap(k), wrap(s_m), wrap(pos_m(1)), wrap(pos_m(2)), &
|
||||
wrap(i), wrap(jkv(2)), wrap(s_m), wrap(pos_m(1)), wrap(pos_m(2)), &
|
||||
wrap(R_m), wrap(pos_m(3)), wrap(psi_n), wrap(tau), wrap(N_pl), &
|
||||
wrap(alpha), wrap(index_rt)])
|
||||
end if
|
||||
end if
|
||||
|
||||
! Store dispersion relation data
|
||||
if (jk == nray .and. tables%dispersion%active) then
|
||||
if (jk == params%raytracing%nray .and. tables%dispersion%active) then
|
||||
call tables%dispersion%append([s, lambda_r, lambda_i])
|
||||
end if
|
||||
|
||||
@ -515,7 +518,7 @@ contains
|
||||
use const_and_precisions, only : zero, one, comp_huge
|
||||
use types, only : table, wrap
|
||||
use gray_params, only : raytracing_parameters, gray_tables
|
||||
use beamdata, only : rayi2jk
|
||||
use beamdata, only : unfold_index
|
||||
|
||||
! subroutine arguments
|
||||
type(raytracing_parameters), intent(in) :: params
|
||||
@ -593,7 +596,7 @@ contains
|
||||
dx = y(1:3, jk) - y(1:3, 1) ! distance from the central ray
|
||||
dx_loc = matmul(M, dx) ! local ray position
|
||||
r = norm2(dx_loc(1:2)) ! cross-section radius
|
||||
jkv = rayi2jk(jk) ! [j, k] vector
|
||||
jkv = unfold_index(params, jk) ! (j, k)
|
||||
|
||||
if (full_ .or. jk /= 1) &
|
||||
call beam_shape%append([ &
|
||||
|
@ -95,15 +95,16 @@ contains
|
||||
end subroutine dealloc_surfvec
|
||||
|
||||
|
||||
subroutine compute_flux_averages(tables)
|
||||
subroutine compute_flux_averages(params, tables)
|
||||
use const_and_precisions, only : wp_,zero,one,pi,ccj=>mu0inv
|
||||
use equilibrium, only : btrcen,btaxis,rmaxis,zmaxis,phitedge,zbsup,zbinf, &
|
||||
bfield,frhotor,fq,tor_curr,psia,pol_flux
|
||||
use dierckx, only : regrid,coeff_parder
|
||||
use types, only : table, wrap
|
||||
use gray_params, only : gray_tables
|
||||
use gray_params, only : equilibrium_parameters, gray_tables
|
||||
|
||||
! subroutine arguments
|
||||
type(equilibrium_parameters), intent(in) :: params
|
||||
type(gray_tables), intent(inout), optional :: tables
|
||||
|
||||
! local constants
|
||||
@ -209,7 +210,7 @@ contains
|
||||
if (rhotjp /= rhotjp) print *, 'Nan!!!!!!!!!!'
|
||||
psicon(jp)=height
|
||||
|
||||
call contours_psi(psinjp,rctemp,zctemp,rup,zup,rlw,zlw)
|
||||
call contours_psi(params,psinjp,rctemp,zctemp,rup,zup,rlw,zlw)
|
||||
rcon(:,jp) = rctemp
|
||||
zcon(:,jp) = zctemp
|
||||
|
||||
@ -445,9 +446,9 @@ contains
|
||||
|
||||
|
||||
|
||||
subroutine contours_psi(h,rcn,zcn,rup,zup,rlw,zlw)
|
||||
subroutine contours_psi(params, h,rcn,zcn,rup,zup,rlw,zlw)
|
||||
use const_and_precisions, only : wp_,pi
|
||||
use gray_params, only : iequil
|
||||
use gray_params, only : equilibrium_parameters
|
||||
use logger, only : log_warning
|
||||
use dierckx, only : profil, sproota
|
||||
use equilibrium, only : model, frhotor, psi_spline, &
|
||||
@ -458,9 +459,10 @@ contains
|
||||
integer, parameter :: mest=4
|
||||
|
||||
! subroutine arguments
|
||||
type(equilibrium_parameters), intent(in) :: params
|
||||
real(wp_), intent(in) :: h
|
||||
real(wp_), dimension(:), intent(out) :: rcn,zcn
|
||||
real(wp_), intent(inout) :: rup,zup,rlw,zlw
|
||||
real(wp_), intent(out) :: rcn(:), zcn(:)
|
||||
real(wp_), intent(inout) :: rup, zup, rlw, zlw
|
||||
|
||||
! local variables
|
||||
integer :: npoints,np,info,ic,ier,iopt,m
|
||||
@ -472,7 +474,7 @@ contains
|
||||
np=(npoints-1)/2
|
||||
th=pi/dble(np)
|
||||
|
||||
if (iequil<2) then
|
||||
if (params%iequil<2) then
|
||||
block
|
||||
real(wp_) :: r_p ! poloidal radius
|
||||
r_p = sqrt(h) * model%a
|
||||
|
25
src/main.f90
25
src/main.f90
@ -1,14 +1,13 @@
|
||||
program main
|
||||
use const_and_precisions, only : wp_
|
||||
use logger, only : INFO, ERROR, set_log_level, log_message
|
||||
use logger, only : INFO, ERROR, WARNING, set_log_level, log_message
|
||||
use utils, only : dirname
|
||||
use gray_cli, only : cli_options, parse_cli_options, &
|
||||
parse_param_overrides
|
||||
use gray_core, only : gray_main
|
||||
use gray_params, only : gray_parameters, gray_data, gray_results, &
|
||||
read_gray_params, read_gray_config, &
|
||||
make_gray_header, &
|
||||
params_set_globals => set_globals
|
||||
make_gray_header
|
||||
implicit none
|
||||
|
||||
no_save: block
|
||||
@ -63,9 +62,19 @@ program main
|
||||
! Apply CLI overrides to the parameters
|
||||
call parse_param_overrides(params)
|
||||
|
||||
! Copy the parameters into global variables
|
||||
! exported by the gray_params module
|
||||
call params_set_globals(params)
|
||||
! Do some checks on the inputs
|
||||
associate (p => params%raytracing)
|
||||
if (p%nrayr < 5) then
|
||||
p%igrad = 0
|
||||
call log_message(level=WARNING, mod='main', proc='main', &
|
||||
msg='nrayr < 5 ⇒ optical case only')
|
||||
end if
|
||||
if (p%nrayr == 1) p%nrayth = 1
|
||||
|
||||
if (p%nrayr > 1) then
|
||||
p%rwmax = real(p%nrayr - 1) / max(nint((p%nrayr - 1)/p%rwmax), 1)
|
||||
end if
|
||||
end associate
|
||||
|
||||
! Read the input data and set the global variables
|
||||
! of the respective module. Note: order matters.
|
||||
@ -384,10 +393,10 @@ contains
|
||||
integer, allocatable :: beams(:)
|
||||
|
||||
! Initialise the magsurf_data module
|
||||
call compute_flux_averages
|
||||
call compute_flux_averages(params%equilibrium)
|
||||
|
||||
! Initialise the output profiles
|
||||
call pec_init(params%output%ipec)
|
||||
call pec_init(params%output)
|
||||
|
||||
associate(nrho =>params%output%nrho)
|
||||
allocate(jphi(nrho), currins(nrho), pins(nrho), rtin(nrho), rpin(nrho))
|
||||
|
@ -1,7 +1,5 @@
|
||||
module multipass
|
||||
use const_and_precisions, only : wp_, zero, half, one, degree, czero
|
||||
use beamdata, only : dst, nray
|
||||
use gray_params, only : ipass
|
||||
use const_and_precisions, only : wp_
|
||||
use polarization, only : pol_limit, field_to_ellipse
|
||||
use reflections, only : wall_refl
|
||||
use equilibrium, only : bfield
|
||||
@ -12,7 +10,7 @@ contains
|
||||
|
||||
subroutine plasma_in(i, x, N, Bres, sox, cpl, psi, chi, iop, ext, eyt, perfect)
|
||||
! Computes the ray polarisation and power couplings when it enteres the plasma
|
||||
use const_and_precisions, only: cm
|
||||
use const_and_precisions, only : cm
|
||||
|
||||
! subroutine arguments
|
||||
integer, intent(in) :: i ! ray index
|
||||
@ -101,16 +99,18 @@ contains
|
||||
end subroutine plasma_out
|
||||
|
||||
|
||||
subroutine wall_out(i, ins, xv, anv, bres, sox, psipol1, chipol1, iow, iop, ext, eyt)
|
||||
subroutine wall_out(i, ins, xv, anv, dst, bres, sox, &
|
||||
psipol1, chipol1, iow, iop, ext, eyt)
|
||||
! Ray exits vessel
|
||||
|
||||
! subroutine arguments
|
||||
integer, intent(in) :: i ! ray index
|
||||
logical, intent(in) :: ins ! inside plasma? (ins=1 plasma/wall overlap)
|
||||
real(wp_), intent(inout) :: xv(3), anv(3)
|
||||
real(wp_), intent(in) :: dst ! step size
|
||||
real(wp_), intent(in) :: bres
|
||||
integer, intent(in) :: sox
|
||||
real(wp_), intent(out) :: psipol1,chipol1
|
||||
real(wp_), intent(out) :: psipol1, chipol1
|
||||
integer, intent(inout) :: iow(:) ! in/out vessel and plasma flags
|
||||
integer, intent(inout) :: iop(:) ! in/out vessel and plasma flags
|
||||
complex(wp_), intent(inout) :: ext(:), eyt(:)
|
||||
@ -128,11 +128,11 @@ contains
|
||||
xv = xvrfl
|
||||
anv = anvrfl
|
||||
|
||||
if(i == 1) then ! polarization angles at wall reflection for central ray
|
||||
if(i == 1) then
|
||||
call field_to_ellipse(ext1, eyt1, psipol1, chipol1)
|
||||
else
|
||||
psipol1 = zero
|
||||
chipol1 = zero
|
||||
psipol1 = 0
|
||||
chipol1 = 0
|
||||
end if
|
||||
|
||||
end subroutine wall_out
|
||||
@ -163,22 +163,22 @@ contains
|
||||
call log_warning(msg, mod='multipass', proc='initbeam')
|
||||
end if
|
||||
|
||||
stv = zero ! starting step
|
||||
jphi_beam = zero ! 1D beam profiles
|
||||
pins_beam = zero
|
||||
currins_beam = zero
|
||||
dpdv_beam = zero
|
||||
jcd_beam = zero
|
||||
stv = 0 ! starting step
|
||||
jphi_beam = 0 ! 1D beam profiles
|
||||
pins_beam = 0
|
||||
currins_beam = 0
|
||||
dpdv_beam = 0
|
||||
jcd_beam = 0
|
||||
end subroutine initbeam
|
||||
|
||||
|
||||
subroutine initmultipass(i, iox, iroff, yynext, yypnext, yw0, ypw0, stnext, p0ray, &
|
||||
taus, tau1, etau1, cpls, cpl1, lgcpl1, psipv, chipv)
|
||||
subroutine initmultipass(params, iroff, yynext, yypnext, yw0, ypw0, stnext, &
|
||||
p0ray, taus, tau1, etau1, cpls, cpl1, lgcpl1, psipv, chipv)
|
||||
! Initialization before pass loop
|
||||
use gray_params, only : gray_parameters
|
||||
|
||||
! subroutine arguments
|
||||
logical, intent(in) :: i ! ipol
|
||||
integer, intent(in) :: iox ! mode active on 1st pass
|
||||
type(gray_parameters), intent(in) :: params
|
||||
logical, dimension(:,:), intent(out) :: iroff ! global ray status (F = active, T = inactive)
|
||||
real(wp_), dimension(:), intent(out) :: p0ray, tau1, etau1, cpl1
|
||||
real(wp_), dimension(:), intent(out) :: lgcpl1, psipv, chipv
|
||||
@ -186,42 +186,48 @@ contains
|
||||
real(wp_), dimension(:,:,:), intent(out) :: yynext, yypnext
|
||||
|
||||
iroff = .false. ! global ray status (F = active, T = inactive)
|
||||
if(.not. i) call turnoffray(0,1,3-iox,iroff) ! !ipol => stop other mode (iox=1/2 -> stop ib=2/1 at first pass)
|
||||
yynext = zero ! starting beam coordinates (1)
|
||||
yypnext = zero ! starting beam coordinates (2)
|
||||
yw0 = zero ! temporary beam coordinates (1)
|
||||
ypw0 = zero ! temporary beam coordinates (2)
|
||||
stnext = zero ! starting beam step
|
||||
p0ray = zero ! starting beam power
|
||||
taus = zero ! beam tau from previous passes
|
||||
tau1 = zero
|
||||
etau1 = one
|
||||
cpls = one ! beam coupling from previous passes
|
||||
cpl1 = one
|
||||
lgcpl1 = zero
|
||||
psipv = zero ! psi polarization angle at vacuum-plasma boundary
|
||||
chipv = zero ! chi polarization angle at vacuum-plasma boundary
|
||||
|
||||
if(.not. params%raytracing%ipol) then
|
||||
! stop other mode (iox=1/2 -> stop ib=2/1 at first pass)
|
||||
call turnoffray(0, 1, params%raytracing%ipass, 3-params%antenna%iox, iroff)
|
||||
end if
|
||||
|
||||
yynext = 0 ! starting beam coordinates (1)
|
||||
yypnext = 0 ! starting beam coordinates (2)
|
||||
yw0 = 0 ! temporary beam coordinates (1)
|
||||
ypw0 = 0 ! temporary beam coordinates (2)
|
||||
stnext = 0 ! starting beam step
|
||||
p0ray = 0 ! starting beam power
|
||||
taus = 0 ! beam tau from previous passes
|
||||
tau1 = 0
|
||||
etau1 = 1
|
||||
cpls = 1 ! beam coupling from previous passes
|
||||
cpl1 = 1
|
||||
lgcpl1 = 0
|
||||
psipv = 0 ! psi polarization angle at vacuum-plasma boundary
|
||||
chipv = 0 ! chi polarization angle at vacuum-plasma boundary
|
||||
end subroutine initmultipass
|
||||
|
||||
|
||||
subroutine turnoffray(jk, ip, ib, iroff)
|
||||
subroutine turnoffray(jk, ip, npass, ib, iroff)
|
||||
! Turn off ray propagation
|
||||
|
||||
! subroutine arguments
|
||||
integer, intent(in) :: jk, ip, ib ! ray (0=all rays), pass, beam indexes
|
||||
integer, intent(in) :: npass ! total number of passes
|
||||
logical, dimension(:,:), intent(out) :: iroff ! global ray status (F = active, T = inactive)
|
||||
|
||||
! local variables
|
||||
integer :: ipx, i1, i2
|
||||
|
||||
if(jk==0) then ! stop all rays
|
||||
do ipx=ip,ipass ! from pass ip to last pass
|
||||
do ipx=ip,npass ! from pass ip to last pass
|
||||
i1 = 2**ipx-2+2**(ipx-ip)*(ib-1)+1 ! first derived beam at pass ipx
|
||||
i2 = 2**ipx-2+2**(ipx-ip)*ib ! last derived beam at pass ipx (i1=i2 for ipx=ip)
|
||||
iroff(:,i1:i2) = .true.
|
||||
end do
|
||||
else ! only stop ray jk
|
||||
do ipx=ip,ipass
|
||||
do ipx=ip,npass
|
||||
i1 = 2**ipx-2+2**(ipx-ip)*(ib-1)+1
|
||||
i2 = 2**ipx-2+2**(ipx-ip)*ib
|
||||
iroff(jk,i1:i2) = .true.
|
||||
|
331
src/pec.f90
331
src/pec.f90
@ -1,5 +1,5 @@
|
||||
module pec
|
||||
use const_and_precisions, only : wp_,zero,one
|
||||
use const_and_precisions, only : wp_
|
||||
|
||||
implicit none
|
||||
|
||||
@ -10,51 +10,55 @@ module pec
|
||||
|
||||
contains
|
||||
|
||||
subroutine pec_init(ipec,rt_in)
|
||||
use equilibrium, only : frhotor,frhopol
|
||||
use gray_params, only : nnd
|
||||
subroutine pec_init(params, rt_in)
|
||||
use gray_params, only : output_parameters, RHO_POL
|
||||
use equilibrium, only : frhotor, frhopol
|
||||
use magsurf_data, only : fluxval
|
||||
! arguments
|
||||
integer, intent(in) :: ipec
|
||||
real(wp_), dimension(nnd), intent(in), optional :: rt_in
|
||||
! local variables
|
||||
|
||||
! subroutine arguments
|
||||
type(output_parameters), intent(in) :: params
|
||||
real(wp_), intent(in), optional :: rt_in(params%nrho)
|
||||
|
||||
! local variables
|
||||
integer :: it
|
||||
real(wp_) :: drt,rt,rt1,rhop1
|
||||
real(wp_) :: ratjai,ratjbi,ratjpli
|
||||
real(wp_) :: voli0,voli1,areai0,areai1
|
||||
real(wp_) :: drt, rt, rt1, rhop1
|
||||
real(wp_) :: ratjai, ratjbi, ratjpli
|
||||
real(wp_) :: voli0, voli1, areai0, areai1
|
||||
|
||||
! rt_in present: read input grid
|
||||
! else: build equidistant grid dimension nnd
|
||||
associate(n => params%nrho)
|
||||
|
||||
! ipec=0 rho_tor grid
|
||||
! ipec=1 rho_pol grid
|
||||
! rt_in present: read input grid
|
||||
! else: build equidistant grid dimension n
|
||||
|
||||
! ipec=0 ρ_t grid
|
||||
! ipec=1 ρ_p grid
|
||||
call dealloc_pec
|
||||
allocate(rhop_tab(nnd),rhot_tab(nnd),rtabpsi1(0:nnd),dvol(nnd),darea(nnd), &
|
||||
ratjav(nnd),ratjbv(nnd),ratjplv(nnd))
|
||||
allocate(rhop_tab(n), rhot_tab(n), rtabpsi1(0:n))
|
||||
allocate(dvol(n), darea(n), ratjav(n), ratjbv(n), ratjplv(n))
|
||||
|
||||
voli0 = zero
|
||||
areai0 = zero
|
||||
rtabpsi1(0) = zero
|
||||
voli0 = 0
|
||||
areai0 = 0
|
||||
rtabpsi1(0) = 0
|
||||
|
||||
do it=1,nnd
|
||||
do it = 1, n
|
||||
if(present(rt_in)) then
|
||||
! read radial grid from input
|
||||
! read radial grid from input
|
||||
rt = rt_in(it)
|
||||
if(it<nnd) then
|
||||
if (it < n) then
|
||||
drt = rt_in(it+1)-rt
|
||||
end if
|
||||
else
|
||||
! build equidistant radial grid
|
||||
drt = one/dble(nnd-1)
|
||||
rt = dble(it-1)*drt
|
||||
! build equidistant radial grid
|
||||
drt = 1/dble(n - 1)
|
||||
rt = (it - 1)*drt
|
||||
end if
|
||||
! radial coordinate of i-(i+1) interval mid point
|
||||
if(it < nnd) then
|
||||
rt1 = rt + drt/2.0_wp_
|
||||
! radial coordinate of i-(i+1) interval mid point
|
||||
if (it < n) then
|
||||
rt1 = rt + drt/2
|
||||
else
|
||||
rt1 = one
|
||||
rt1 = 1
|
||||
end if
|
||||
if (ipec == 1) then
|
||||
if (params%ipec == RHO_POL) then
|
||||
rhop_tab(it) = rt
|
||||
rhot_tab(it) = frhotor(rt)
|
||||
rhop1 = rt1
|
||||
@ -63,7 +67,8 @@ contains
|
||||
rhop_tab(it) = frhopol(rt)
|
||||
rhop1 = frhopol(rt1)
|
||||
end if
|
||||
! psi grid at mid points, dimension nnd+1, for use in pec_tab
|
||||
|
||||
! psi grid at mid points, size n+1, for use in pec_tab
|
||||
rtabpsi1(it) = rhop1**2
|
||||
|
||||
call fluxval(rhop1,area=areai1,vol=voli1)
|
||||
@ -77,100 +82,100 @@ contains
|
||||
ratjbv(it) = ratjbi
|
||||
ratjplv(it) = ratjpli
|
||||
end do
|
||||
|
||||
end associate
|
||||
end subroutine pec_init
|
||||
|
||||
|
||||
subroutine spec(psjki,ppabs,ccci,iiv,pabs,currt,dpdv,ajphiv,ajcd,pins,currins)
|
||||
use gray_params, only : nnd
|
||||
use beamdata, only : nray,nstep
|
||||
! arguments
|
||||
real(wp_), dimension(nray,nstep), intent(in) :: psjki,ppabs,ccci
|
||||
integer, dimension(nray), intent(in) :: iiv
|
||||
real(wp_), intent(in) :: pabs,currt
|
||||
real(wp_), dimension(nnd), intent(out) :: dpdv,ajphiv,ajcd,pins,currins
|
||||
! local variables
|
||||
integer :: i,ii,jk
|
||||
real(wp_) :: spds,sccs,facpds,facjs
|
||||
real(wp_), dimension(nstep):: xxi,ypt,yamp
|
||||
real(wp_), dimension(nnd) :: wdpdv,wajphiv
|
||||
subroutine spec(psjki, ppabs, ccci, iiv, pabs, &
|
||||
currt, dpdv, ajphiv, ajcd, pins, currins)
|
||||
! subroutine arguments
|
||||
real(wp_), dimension(:, :), intent(in) :: psjki, ppabs, ccci
|
||||
integer, intent(in) :: iiv(:)
|
||||
real(wp_), intent(in) :: pabs, currt
|
||||
real(wp_), dimension(:), intent(out) :: dpdv, ajphiv, ajcd, pins, currins
|
||||
|
||||
! calculation of dP and dI over radial grid
|
||||
dpdv=zero
|
||||
ajphiv=zero
|
||||
do jk=1,nray
|
||||
ii=iiv(jk)
|
||||
if (ii < nstep ) then
|
||||
if(psjki(jk,ii+1) /= zero) ii=ii+1 !!! CHECK
|
||||
! local variables
|
||||
integer :: i, ii, jk
|
||||
real(wp_) :: spds, sccs, facpds, facjs
|
||||
real(wp_), dimension(size(psjki, dim=2)) :: xxi, ypt, yamp
|
||||
real(wp_), dimension(size(dpdv)) :: wdpdv, wajphiv
|
||||
|
||||
! calculation of dP and dI over radial grid
|
||||
dpdv = 0
|
||||
ajphiv = 0
|
||||
do jk = 1, size(iiv)
|
||||
ii = iiv(jk)
|
||||
if (ii < size(psjki, dim=2)) then
|
||||
if (psjki(jk,ii+1) /= 0) ii = ii + 1 !!! CHECK
|
||||
end if
|
||||
xxi=zero
|
||||
ypt=zero
|
||||
yamp=zero
|
||||
do i=1,ii
|
||||
xxi = 0
|
||||
ypt = 0
|
||||
yamp = 0
|
||||
do i = 1, ii
|
||||
xxi(i)=abs(psjki(jk,i))
|
||||
if(xxi(i) <= one) then
|
||||
ypt(i)=ppabs(jk,i)
|
||||
yamp(i)=ccci(jk,i)
|
||||
if(xxi(i) <= 1) then
|
||||
ypt(i) = ppabs(jk,i)
|
||||
yamp(i) = ccci(jk,i)
|
||||
end if
|
||||
end do
|
||||
call pec_tab(xxi,ypt,yamp,ii,rtabpsi1,wdpdv,wajphiv)
|
||||
call pec_tab(xxi, ypt, yamp, ii, rtabpsi1, wdpdv, wajphiv)
|
||||
dpdv = dpdv + wdpdv
|
||||
ajphiv = ajphiv + wajphiv
|
||||
end do
|
||||
|
||||
! here dpdv is still dP (not divided yet by dV)
|
||||
! here ajphiv is still dI (not divided yet by dA)
|
||||
spds=zero
|
||||
sccs=zero
|
||||
do i=1,nnd
|
||||
spds=spds+dpdv(i)
|
||||
sccs=sccs+ajphiv(i)
|
||||
pins(i)=spds
|
||||
currins(i)=sccs
|
||||
! here dpdv is still dP (not divided yet by dV)
|
||||
! here ajphiv is still dI (not divided yet by dA)
|
||||
spds = 0
|
||||
sccs = 0
|
||||
do i = 1, size(dpdv)
|
||||
spds = spds + dpdv(i)
|
||||
sccs = sccs + ajphiv(i)
|
||||
pins(i) = spds
|
||||
currins(i) = sccs
|
||||
end do
|
||||
|
||||
facpds=one
|
||||
facjs=one
|
||||
if(spds > zero) facpds=pabs/spds
|
||||
if(sccs /= zero) facjs=currt/sccs
|
||||
facpds = 1
|
||||
facjs = 1
|
||||
if(spds > 0) facpds = pabs / spds
|
||||
if(sccs /= 0) facjs = currt / sccs
|
||||
|
||||
dpdv=facpds*(dpdv/dvol)
|
||||
ajphiv=facjs*(ajphiv/darea)
|
||||
ajcd=ajphiv*ratjbv
|
||||
pins=facpds*pins
|
||||
currins=facjs*currins
|
||||
dpdv = facpds * (dpdv / dvol)
|
||||
ajphiv = facjs * (ajphiv / darea)
|
||||
ajcd = ajphiv * ratjbv
|
||||
pins = facpds * pins
|
||||
currins = facjs * currins
|
||||
|
||||
! now dpdv is dP/dV [MW/m^3]
|
||||
! now ajphiv is J_phi=dI/dA [MA/m^2]
|
||||
! now dpdv is dP/dV [MW/m^3]
|
||||
! now ajphiv is J_phi=dI/dA [MA/m^2]
|
||||
end subroutine spec
|
||||
|
||||
|
||||
subroutine pec_tab(xxi, ypt, yamp, ii, xtab1, wdpdv, wajphiv)
|
||||
! Power and current projected on ψ grid - mid points
|
||||
use utils, only : locatex, intlin
|
||||
|
||||
subroutine pec_tab(xxi,ypt,yamp,ii,xtab1,wdpdv,wajphiv)
|
||||
! Power and current projected on psi grid - mid points
|
||||
use const_and_precisions, only : wp_,one,zero
|
||||
use gray_params, only : nnd
|
||||
use utils, only : locatex,intlin
|
||||
! arguments
|
||||
! subroutine arguments
|
||||
real(wp_), dimension(:), intent(in) :: xxi, ypt, yamp
|
||||
integer, intent(in) :: ii
|
||||
real(wp_), dimension(ii), intent(in) :: xxi,ypt,yamp
|
||||
real(wp_), dimension(0:nnd), intent(in) :: xtab1
|
||||
real(wp_), dimension(nnd), intent(out) :: wdpdv,wajphiv
|
||||
! local variables
|
||||
integer, parameter :: llmx = 21
|
||||
integer, dimension(llmx) ::isev
|
||||
real(wp_) :: ppa1,ppa2,cci1,cci2,dppa,didst,rt1
|
||||
integer :: i,is,ise0,idecr,iise0,iise,iis,iis1
|
||||
integer :: ind1,ind2,iind,ind,indi,itb1
|
||||
real(wp_), dimension(0:), intent(in) :: xtab1
|
||||
real(wp_), dimension(ubound(xtab1, 1)), intent(out) :: wdpdv, wajphiv
|
||||
|
||||
! local variables
|
||||
integer :: isev(21)
|
||||
real(wp_) :: ppa1, ppa2, cci1, cci2, dppa, didst, rt1
|
||||
integer :: i, is, ise0, idecr, iise0, iise, iis, iis1
|
||||
integer :: ind1, ind2, iind, ind, indi, itb1
|
||||
|
||||
isev = 0
|
||||
ise0 = 0
|
||||
idecr = -1
|
||||
is = 1
|
||||
wdpdv = zero
|
||||
wajphiv = zero
|
||||
wdpdv = 0
|
||||
wajphiv = 0
|
||||
do i=1,ii
|
||||
if(ise0 == 0) then
|
||||
if(xxi(i) < one) then
|
||||
if(xxi(i) < 1) then
|
||||
ise0 = i
|
||||
isev(is) = max(i - 1, 1)
|
||||
is = is + 1
|
||||
@ -183,7 +188,7 @@ contains
|
||||
idecr = 1
|
||||
end if
|
||||
else
|
||||
if(xxi(i) > one) exit
|
||||
if(xxi(i) > 1) exit
|
||||
if(xxi(i) < xxi(i-1)) then
|
||||
isev(is) = i - 1
|
||||
is = is + 1
|
||||
@ -194,30 +199,30 @@ contains
|
||||
end do
|
||||
|
||||
isev(is) = i-1
|
||||
ppa1 = zero
|
||||
cci1 = zero
|
||||
ppa1 = 0
|
||||
cci1 = 0
|
||||
|
||||
do iis=1,is-1
|
||||
do iis = 1, is-1
|
||||
iis1 = iis + 1
|
||||
iise0 = isev(iis)
|
||||
iise = isev(iis1)
|
||||
if (mod(iis,2) /= 0) then
|
||||
idecr = -1
|
||||
ind1 = nnd
|
||||
ind1 = size(wdpdv)
|
||||
ind2 = 2
|
||||
iind = -1
|
||||
else
|
||||
idecr = 1
|
||||
ind1 = 1
|
||||
ind2 = nnd
|
||||
ind2 = size(wdpdv)
|
||||
iind = 1
|
||||
end if
|
||||
do ind=ind1,ind2,iind
|
||||
do ind = ind1, ind2, iind
|
||||
indi = ind
|
||||
if (idecr == -1) indi = ind - 1
|
||||
rt1 = xtab1(indi)
|
||||
call locatex(xxi,iise,iise0,iise,rt1,itb1)
|
||||
if(itb1 >= iise0 .and. itb1 <= iise) then
|
||||
if (itb1 >= iise0 .and. itb1 <= iise) then
|
||||
if(itb1 == iise) then
|
||||
ppa2=ypt(itb1)
|
||||
cci2=yamp(itb1)
|
||||
@ -240,93 +245,93 @@ contains
|
||||
subroutine postproc_profiles(pabs,currt,rhot_tab,dpdv,ajphiv, &
|
||||
rhotpav,drhotpav,rhotjava,drhotjava,dpdvp, ajphip, &
|
||||
rhotp, drhotp, rhotjfi, drhotjfi, dpdvmx,ajmxfi, ratjamx, ratjbmx)
|
||||
! radial average values over power and current density profile
|
||||
|
||||
! Radial average values over power and current density profile
|
||||
use const_and_precisions, only : pi, comp_eps
|
||||
use gray_params, only : nnd
|
||||
use equilibrium, only : frhopol
|
||||
use magsurf_data, only : fluxval
|
||||
|
||||
real(wp_), intent(in) :: pabs,currt
|
||||
real(wp_), dimension(nnd), intent(in) :: rhot_tab
|
||||
real(wp_), dimension(nnd), intent(in) :: dpdv,ajphiv
|
||||
real(wp_), intent(out) :: rhotpav,drhotpav,dpdvp
|
||||
real(wp_), intent(out) :: rhotjava,drhotjava,ajphip
|
||||
real(wp_), intent(in) :: rhot_tab(:)
|
||||
real(wp_), intent(in) :: dpdv(:), ajphiv(:)
|
||||
real(wp_), intent(out) :: rhotpav, drhotpav, dpdvp
|
||||
real(wp_), intent(out) :: rhotjava, drhotjava, ajphip
|
||||
real(wp_), intent(out) :: rhotp, drhotp, dpdvmx
|
||||
real(wp_), intent(out) :: rhotjfi, drhotjfi, ajmxfi
|
||||
real(wp_), intent(out) :: ratjamx, ratjbmx
|
||||
|
||||
real(wp_), intent(out) :: rhotp,drhotp,dpdvmx
|
||||
real(wp_), intent(out) :: rhotjfi,drhotjfi,ajmxfi
|
||||
real(wp_), intent(out) :: ratjamx,ratjbmx
|
||||
real(wp_) :: sccsa, ratjplmx, rhopjava, rhoppav
|
||||
real(wp_) :: rhotjav, rhot2pav, rhot2java, dvdrhotav, dadrhotava
|
||||
|
||||
real(wp_) :: sccsa,ratjplmx,rhopjava,rhoppav
|
||||
real(wp_) :: rhotjav,rhot2pav,rhot2java,dvdrhotav,dadrhotava
|
||||
rhotpav = 0
|
||||
rhot2pav = 0
|
||||
rhotjav = 0
|
||||
rhotjava = 0
|
||||
rhot2java = 0
|
||||
|
||||
rhotpav=zero
|
||||
rhot2pav=zero
|
||||
rhotjav=zero
|
||||
rhotjava=zero
|
||||
rhot2java=zero
|
||||
|
||||
if (pabs > zero) then
|
||||
if (pabs > 0) then
|
||||
rhotpav = sum(rhot_tab *dpdv*dvol)/pabs
|
||||
rhot2pav = sum(rhot_tab**2*dpdv*dvol)/pabs
|
||||
end if
|
||||
|
||||
if (abs(currt) > zero) then
|
||||
if (abs(currt) > 0) then
|
||||
rhotjav = sum(rhot_tab*ajphiv*darea)/currt
|
||||
end if
|
||||
sccsa = sum(abs(ajphiv)*darea)
|
||||
if (sccsa > zero) then
|
||||
if (sccsa > 0) then
|
||||
rhotjava = sum(rhot_tab *abs(ajphiv)*darea)/sccsa
|
||||
rhot2java = sum(rhot_tab**2*abs(ajphiv)*darea)/sccsa
|
||||
end if
|
||||
|
||||
! factor sqrt(8) = 2sqrt(2) to match full width of gaussian profile
|
||||
! factor sqrt(8) = 2sqrt(2) to match full width of gaussian profile
|
||||
drhotpav = sqrt(8._wp_*(max(rhot2pav -rhotpav**2,comp_eps)))
|
||||
drhotjava = sqrt(8._wp_*(max(rhot2java-rhotjava**2,comp_eps)))
|
||||
|
||||
rhoppav = frhopol(rhotpav)
|
||||
rhopjava = frhopol(rhotjava)
|
||||
|
||||
if (pabs > zero) then
|
||||
if (pabs > 0) then
|
||||
call fluxval(rhoppav,dvdrhot=dvdrhotav)
|
||||
dpdvp = pabs*2.0_wp_/(sqrt(pi)*drhotpav*dvdrhotav)
|
||||
call profwidth(nnd,rhot_tab,dpdv,rhotp,dpdvmx,drhotp)
|
||||
call profwidth(rhot_tab,dpdv,rhotp,dpdvmx,drhotp)
|
||||
else
|
||||
dpdvp = zero
|
||||
rhotp = zero
|
||||
dpdvmx = zero
|
||||
drhotp = zero
|
||||
dpdvp = 0
|
||||
rhotp = 0
|
||||
dpdvmx = 0
|
||||
drhotp = 0
|
||||
end if
|
||||
|
||||
if (sccsa > zero) then
|
||||
if (sccsa > 0) then
|
||||
call fluxval(rhopjava,dadrhot=dadrhotava,ratja=ratjamx,ratjb=ratjbmx, &
|
||||
ratjpl=ratjplmx)
|
||||
ajphip = currt*2.0_wp_/(sqrt(pi)*drhotjava*dadrhotava)
|
||||
call profwidth(nnd,rhot_tab,ajphiv,rhotjfi,ajmxfi,drhotjfi)
|
||||
call profwidth(rhot_tab,ajphiv,rhotjfi,ajmxfi,drhotjfi)
|
||||
else
|
||||
ajphip = zero
|
||||
rhotjfi = zero
|
||||
ajmxfi = zero
|
||||
drhotjfi = zero
|
||||
ratjamx = zero
|
||||
ratjbmx = zero
|
||||
ajphip = 0
|
||||
rhotjfi = 0
|
||||
ajmxfi = 0
|
||||
drhotjfi = 0
|
||||
ratjamx = 0
|
||||
ratjbmx = 0
|
||||
end if
|
||||
end subroutine postproc_profiles
|
||||
|
||||
|
||||
|
||||
subroutine profwidth(nd,xx,yy,xpk,ypk,dxxe)
|
||||
use const_and_precisions, only : wp_,emn1
|
||||
subroutine profwidth(xx,yy,xpk,ypk,dxxe)
|
||||
use const_and_precisions, only : emn1
|
||||
use utils, only : locatex, locate, intlin, vmaxmini
|
||||
! arguments
|
||||
integer :: nd
|
||||
real(wp_), dimension(nd) :: xx,yy
|
||||
real(wp_), intent(out) :: xpk,ypk,dxxe
|
||||
! local variables
|
||||
|
||||
! subroutine arguments
|
||||
real(wp_), intent(in) :: xx(:), yy(:)
|
||||
real(wp_), intent(out) :: xpk, ypk, dxxe
|
||||
|
||||
! local variables
|
||||
integer :: imn,imx,ipk,ie
|
||||
real(wp_) :: xmn,xmx,ymn,ymx,xpkp,xpkm,yye,rte1,rte2
|
||||
real(wp_) :: ypkp,ypkm
|
||||
|
||||
call vmaxmini(yy,nd,ymn,ymx,imn,imx)
|
||||
ypk = zero
|
||||
call vmaxmini(yy,size(yy),ymn,ymx,imn,imx)
|
||||
ypk = 0
|
||||
xmx = xx(imx)
|
||||
xmn = xx(imn)
|
||||
if (abs(ymx) > abs(ymn)) then
|
||||
@ -344,21 +349,21 @@ contains
|
||||
ypkm = ymx
|
||||
xpkm = xmx
|
||||
end if
|
||||
if(xpkp > zero) then
|
||||
if(xpkp > 0) then
|
||||
xpk = xpkp
|
||||
ypk = ypkp
|
||||
yye = ypk*emn1
|
||||
call locatex(yy,nd,1,ipk,yye,ie)
|
||||
if(ie > 0 .and. ie < nd) then
|
||||
call locatex(yy,size(yy),1,ipk,yye,ie)
|
||||
if(ie > 0 .and. ie < size(yy)) then
|
||||
call intlin(yy(ie),xx(ie),yy(ie+1),xx(ie+1),yye,rte1)
|
||||
else
|
||||
rte1 = zero
|
||||
rte1 = 0
|
||||
end if
|
||||
call locatex(yy,nd,ipk,nd,yye,ie)
|
||||
if(ie > 0 .and. ie < nd) then
|
||||
call locatex(yy,size(yy),ipk,size(yy),yye,ie)
|
||||
if(ie > 0 .and. ie < size(yy)) then
|
||||
call intlin(yy(ie),xx(ie),yy(ie+1),xx(ie+1),yye,rte2)
|
||||
else
|
||||
rte2 = zero
|
||||
rte2 = 0
|
||||
end if
|
||||
else
|
||||
ipk=2
|
||||
@ -366,19 +371,19 @@ contains
|
||||
ypk=yy(2)
|
||||
rte1=0.0_wp_
|
||||
yye=ypk*emn1
|
||||
call locate(yy,nd,yye,ie)
|
||||
if(ie > 0 .and. ie < nd) then
|
||||
call locate(yy,size(yy),yye,ie)
|
||||
if(ie > 0 .and. ie < size(yy)) then
|
||||
call intlin(yy(ie),xx(ie),yy(ie+1),xx(ie+1),yye,rte2)
|
||||
else
|
||||
rte2 = zero
|
||||
rte2 = 0
|
||||
end if
|
||||
end if
|
||||
dxxe = rte2 - rte1
|
||||
if(ymx /= zero .and. ymn /= zero) dxxe = -dxxe
|
||||
if(ymx /= 0 .and. ymn /= 0) dxxe = -dxxe
|
||||
end subroutine profwidth
|
||||
|
||||
subroutine dealloc_pec
|
||||
|
||||
subroutine dealloc_pec
|
||||
if (allocated(rhop_tab)) deallocate(rhop_tab)
|
||||
if (allocated(rhot_tab)) deallocate(rhot_tab)
|
||||
if (allocated(rtabpsi1)) deallocate(rtabpsi1)
|
||||
|
Loading…
Reference in New Issue
Block a user