From 1129adc92dc847afb15cc81ef842a9a1137c879b Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Tue, 22 Jun 2021 16:26:33 -0600 Subject: [PATCH 1/4] trap nans in low/stopped rotor speeds --- src/ControllerBlocks.f90 | 8 +++++--- src/Functions.f90 | 6 +++--- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/ControllerBlocks.f90 b/src/ControllerBlocks.f90 index 4a580c2f..1de24456 100644 --- a/src/ControllerBlocks.f90 +++ b/src/ControllerBlocks.f90 @@ -131,6 +131,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar) REAL(8) :: Tau_r ! Estimated rotor torque [Nm] REAL(8) :: a ! wind variance REAL(8) :: lambda ! tip-speed-ratio [rad] + REAL(8) :: RotSpeed ! Rotor Speed [rad], locally + ! - Covariance matrices REAL(8), DIMENSION(3,3) :: F ! First order system jacobian REAL(8), DIMENSION(3,3), SAVE :: P ! Covariance estiamte @@ -168,11 +170,11 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar) Q = RESHAPE((/0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0/),(/3,3/)) IF (LocalVar%iStatus == 0) THEN ! Initialize recurring values - om_r = LocalVar%RotSpeedF + om_r = max(LocalVar%RotSpeedF, CntrPar%VS_MinOMSpd) v_t = 0.0 v_m = LocalVar%HorWindV v_h = LocalVar%HorWindV - lambda = LocalVar%RotSpeed * CntrPar%WE_BladeRadius/v_h + lambda = max(LocalVar%RotSpeed, CntrPar%VS_MinOMSpd) * CntrPar%WE_BladeRadius/v_h xh = RESHAPE((/om_r, v_t, v_m/),(/3,1/)) P = RESHAPE((/0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 1.0/),(/3,3/)) K = RESHAPE((/0.0,0.0,0.0/),(/3,1/)) @@ -183,7 +185,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar) A_op = interp1d(CntrPar%WE_FOPoles_v,CntrPar%WE_FOPoles,v_h) ! TEST INTERP2D - lambda = LocalVar%RotSpeed * CntrPar%WE_BladeRadius/v_h + lambda = max(LocalVar%RotSpeed, CntrPar%VS_MinOMSpd) * CntrPar%WE_BladeRadius/v_h Cp_op = interp2d(PerfData%Beta_vec,PerfData%TSR_vec,PerfData%Cp_mat, LocalVar%BlPitch(1)*R2D, lambda ) Cp_op = max(0.0,Cp_op) diff --git a/src/Functions.f90 b/src/Functions.f90 index 9d0c330d..b4799905 100644 --- a/src/Functions.f90 +++ b/src/Functions.f90 @@ -195,7 +195,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq) ! 4| a b c ! 5| d e f ! 6| g H i - + USE ieee_arithmetic IMPLICIT NONE ! Inputs REAL(8), DIMENSION(:), INTENT(IN) :: xData ! Provided x data (vector), to find query point (should be monotonically increasing) @@ -215,7 +215,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq) ! ---- Find corner indices surrounding desired interpolation point ----- ! x-direction - IF (xq <= MINVAL(xData)) THEN ! On lower x-bound, just need to find zData(yq) + IF (xq <= MINVAL(xData) .OR. (ieee_is_nan(xq))) THEN ! On lower x-bound, just need to find zData(yq) j = 1 jj = 1 interp2d = interp1d(yData,zData(:,j),yq) @@ -241,7 +241,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq) ENDIF j = j-1 ! Move j back one ! y-direction - IF (yq <= MINVAL(yData)) THEN ! On lower y-bound, just need to find zData(xq) + IF (yq <= MINVAL(yData) .OR. (ieee_is_nan(yq))) THEN ! On lower y-bound, just need to find zData(xq) i = 1 ii = 1 interp2d = interp1d(xData,zData(i,:),xq) From 4aca5b7c8e4615d6e5a8910511af1e47b44aca8e Mon Sep 17 00:00:00 2001 From: Nikhar Abbas Date: Tue, 22 Jun 2021 16:26:44 -0600 Subject: [PATCH 2/4] increment version --- CMakeLists.txt | 2 +- README.md | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a1ea89fd..784ab5f5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.6) -project(ROSCO VERSION 2.2.0 LANGUAGES Fortran) +project(ROSCO VERSION 2.3.0 LANGUAGES Fortran) set(CMAKE_Fortran_MODULE_DIRECTORY "${CMAKE_BINARY_DIR}/ftnmods") diff --git a/README.md b/README.md index 7b1af13a..69ecf648 100644 --- a/README.md +++ b/README.md @@ -27,14 +27,14 @@ If you want to use the controller with DNV GL Bladed v4.5 or earlier (which stil If ROSCO played a role in your research, please cite it. This software can be cited as: - ROSCO. Version 2.2.0 (2021). Available at https://github.com/nrel/rosco. + ROSCO. Version 2.3.0 (2021). Available at https://github.com/nrel/rosco. For LaTeX users: ``` @misc{ROSCO_2021, author = {NREL}, - title = {{ROSCO. Version 2.2.0}}, + title = {{ROSCO. Version 2.3.0}}, year = {2021}, publisher = {GitHub}, journal = {GitHub repository}, From d08ca3fd3d6f5c68b787978ae679f7086c079667 Mon Sep 17 00:00:00 2001 From: nikhar-abbas <40865984+nikhar-abbas@users.noreply.github.com> Date: Tue, 22 Jun 2021 16:40:42 -0600 Subject: [PATCH 3/4] Develop (#50) * trap nans in low/stopped rotor speeds * increment version --- CMakeLists.txt | 2 +- README.md | 4 ++-- src/ControllerBlocks.f90 | 8 +++++--- src/Functions.f90 | 6 +++--- 4 files changed, 11 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a1ea89fd..784ab5f5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.6) -project(ROSCO VERSION 2.2.0 LANGUAGES Fortran) +project(ROSCO VERSION 2.3.0 LANGUAGES Fortran) set(CMAKE_Fortran_MODULE_DIRECTORY "${CMAKE_BINARY_DIR}/ftnmods") diff --git a/README.md b/README.md index 7b1af13a..69ecf648 100644 --- a/README.md +++ b/README.md @@ -27,14 +27,14 @@ If you want to use the controller with DNV GL Bladed v4.5 or earlier (which stil If ROSCO played a role in your research, please cite it. This software can be cited as: - ROSCO. Version 2.2.0 (2021). Available at https://github.com/nrel/rosco. + ROSCO. Version 2.3.0 (2021). Available at https://github.com/nrel/rosco. For LaTeX users: ``` @misc{ROSCO_2021, author = {NREL}, - title = {{ROSCO. Version 2.2.0}}, + title = {{ROSCO. Version 2.3.0}}, year = {2021}, publisher = {GitHub}, journal = {GitHub repository}, diff --git a/src/ControllerBlocks.f90 b/src/ControllerBlocks.f90 index 4a580c2f..1de24456 100644 --- a/src/ControllerBlocks.f90 +++ b/src/ControllerBlocks.f90 @@ -131,6 +131,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar) REAL(8) :: Tau_r ! Estimated rotor torque [Nm] REAL(8) :: a ! wind variance REAL(8) :: lambda ! tip-speed-ratio [rad] + REAL(8) :: RotSpeed ! Rotor Speed [rad], locally + ! - Covariance matrices REAL(8), DIMENSION(3,3) :: F ! First order system jacobian REAL(8), DIMENSION(3,3), SAVE :: P ! Covariance estiamte @@ -168,11 +170,11 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar) Q = RESHAPE((/0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0/),(/3,3/)) IF (LocalVar%iStatus == 0) THEN ! Initialize recurring values - om_r = LocalVar%RotSpeedF + om_r = max(LocalVar%RotSpeedF, CntrPar%VS_MinOMSpd) v_t = 0.0 v_m = LocalVar%HorWindV v_h = LocalVar%HorWindV - lambda = LocalVar%RotSpeed * CntrPar%WE_BladeRadius/v_h + lambda = max(LocalVar%RotSpeed, CntrPar%VS_MinOMSpd) * CntrPar%WE_BladeRadius/v_h xh = RESHAPE((/om_r, v_t, v_m/),(/3,1/)) P = RESHAPE((/0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 1.0/),(/3,3/)) K = RESHAPE((/0.0,0.0,0.0/),(/3,1/)) @@ -183,7 +185,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar) A_op = interp1d(CntrPar%WE_FOPoles_v,CntrPar%WE_FOPoles,v_h) ! TEST INTERP2D - lambda = LocalVar%RotSpeed * CntrPar%WE_BladeRadius/v_h + lambda = max(LocalVar%RotSpeed, CntrPar%VS_MinOMSpd) * CntrPar%WE_BladeRadius/v_h Cp_op = interp2d(PerfData%Beta_vec,PerfData%TSR_vec,PerfData%Cp_mat, LocalVar%BlPitch(1)*R2D, lambda ) Cp_op = max(0.0,Cp_op) diff --git a/src/Functions.f90 b/src/Functions.f90 index 9d0c330d..b4799905 100644 --- a/src/Functions.f90 +++ b/src/Functions.f90 @@ -195,7 +195,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq) ! 4| a b c ! 5| d e f ! 6| g H i - + USE ieee_arithmetic IMPLICIT NONE ! Inputs REAL(8), DIMENSION(:), INTENT(IN) :: xData ! Provided x data (vector), to find query point (should be monotonically increasing) @@ -215,7 +215,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq) ! ---- Find corner indices surrounding desired interpolation point ----- ! x-direction - IF (xq <= MINVAL(xData)) THEN ! On lower x-bound, just need to find zData(yq) + IF (xq <= MINVAL(xData) .OR. (ieee_is_nan(xq))) THEN ! On lower x-bound, just need to find zData(yq) j = 1 jj = 1 interp2d = interp1d(yData,zData(:,j),yq) @@ -241,7 +241,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq) ENDIF j = j-1 ! Move j back one ! y-direction - IF (yq <= MINVAL(yData)) THEN ! On lower y-bound, just need to find zData(xq) + IF (yq <= MINVAL(yData) .OR. (ieee_is_nan(yq))) THEN ! On lower y-bound, just need to find zData(xq) i = 1 ii = 1 interp2d = interp1d(xData,zData(i,:),xq) From 2a847f7234d54d61d1967b30c02facf945bcdf14 Mon Sep 17 00:00:00 2001 From: dzalkind Date: Thu, 24 Jun 2021 12:45:23 -0600 Subject: [PATCH 4/4] Fix compilation --- src/ControllerBlocks.f90 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ControllerBlocks.f90 b/src/ControllerBlocks.f90 index 9f70353d..84ddad98 100644 --- a/src/ControllerBlocks.f90 +++ b/src/ControllerBlocks.f90 @@ -259,7 +259,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er ! TEST INTERP2D lambda = max(LocalVar%RotSpeed, CntrPar%VS_MinOMSpd) * CntrPar%WE_BladeRadius/v_h - Cp_op = interp2d(PerfData%Beta_vec,PerfData%TSR_vec,PerfData%Cp_mat, LocalVar%BlPitch(1)*R2D, lambda ) + Cp_op = interp2d(PerfData%Beta_vec,PerfData%TSR_vec,PerfData%Cp_mat, LocalVar%BlPitch(1)*R2D, lambda , ErrVar) Cp_op = max(0.0,Cp_op) ! Update Jacobian