Skip to content

Commit

Permalink
Merge pull request #51 from NREL/develop
Browse files Browse the repository at this point in the history
Version 2.3.0
  • Loading branch information
nikhar-abbas authored Jun 25, 2021
2 parents fe71ce4 + 2a847f7 commit 7e10015
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 12 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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")

Expand Down
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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},
Expand Down
12 changes: 6 additions & 6 deletions src/ControllerBlocks.f90
Original file line number Diff line number Diff line change
Expand Up @@ -198,6 +198,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er
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
Expand Down Expand Up @@ -241,11 +243,11 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er
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/))
Expand All @@ -256,10 +258,8 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData, DebugVar, Er
A_op = interp1d(CntrPar%WE_FOPoles_v,CntrPar%WE_FOPoles,v_h,ErrVar)

! TEST INTERP2D
lambda = LocalVar%RotSpeed * CntrPar%WE_BladeRadius/v_h

Cp_op = interp2d(PerfData%Beta_vec,PerfData%TSR_vec,PerfData%Cp_mat, LocalVar%BlPitch(1)*R2D, lambda, ErrVar)

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 , ErrVar)
Cp_op = max(0.0,Cp_op)

! Update Jacobian
Expand Down
7 changes: 4 additions & 3 deletions src/Functions.f90
Original file line number Diff line number Diff line change
Expand Up @@ -234,7 +234,8 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq, ErrVar)
! 6| g H i

USE ROSCO_Types, ONLY : ErrorVariables

USE ieee_arithmetic

IMPLICIT NONE

! Inputs
Expand Down Expand Up @@ -296,7 +297,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq, ErrVar)

! ---- 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,ErrVar)
Expand All @@ -322,7 +323,7 @@ REAL FUNCTION interp2d(xData, yData, zData, xq, yq, ErrVar)
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,ErrVar)
Expand Down

0 comments on commit 7e10015

Please sign in to comment.