Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed-Pitch Torque Control in Region 3 #347

Open
wants to merge 183 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 158 commits
Commits
Show all changes
183 commits
Select commit Hold shift + click to select a range
ae7b267
Update example 05 units
dzalkind Sep 12, 2022
778822b
Add generator efficiency to power output of simple simulation
dzalkind Sep 12, 2022
86c8acf
Update Windows install instructions
dzalkind Sep 12, 2022
b933b3b
Add rotor speed tracking, test case
dzalkind Sep 13, 2022
34ca985
Update discons
dzalkind Sep 14, 2022
2efac84
Adding pitch actuator fault (#163)
mayankchetan Sep 26, 2022
decd694
Various Bug Fixes (#167)
dzalkind Sep 28, 2022
9384f03
Added feature to read AeroDyn 14 files also for the case without towe…
verlivkra Oct 14, 2022
602332e
Various Bug Fixes (#188)
dzalkind Dec 12, 2022
827b281
Update sim.py (#196)
aclerc Dec 19, 2022
5ad1d41
Doc fix (#200)
dzalkind Dec 22, 2022
9d27a33
OpenFAST v3.3.0 (#202)
dzalkind Dec 23, 2022
75a648c
AWC First Version, collected changes
ndevelder Jan 17, 2023
05d7b3b
Compatibility with Numpy v1.24 (#208)
gbarter Jan 18, 2023
f5428de
Merge remote-tracking branch 'upstream/develop' into rosco_awc_merge
dzalkind Jan 18, 2023
0be88d4
Add AWC parameters to registry, regenerate types
dzalkind Jan 23, 2023
1e80263
Apply DbKi to COMPLEX
dzalkind Jan 23, 2023
0575d75
Re-organize AWC pitch contribution, before actuator
dzalkind Jan 23, 2023
974e271
Separate contribution to PitCom from mode calculation
dzalkind Jan 23, 2023
515da17
Make AWC_complexangle a LocalVar for logging
dzalkind Jan 23, 2023
be28641
Allow PA_Mode 1 (#213)
dzalkind Jan 25, 2023
e554c1d
IPC Saturation Fix [RAAW] (#210)
dzalkind Jan 26, 2023
c51ed30
Removed duplicate pitch assignment and removed MinPitch mods for AWC
ndevelder Jan 27, 2023
3155b63
Add script for updating DISCON versions (#214)
dzalkind Feb 2, 2023
0c0e466
Fixes to readsetparams and awc location
ndevelder Feb 3, 2023
20c9c9d
Adding NREL 2.8 127 for AWC testing
ndevelder Feb 3, 2023
a1cf97b
Rename examples (#215)
dzalkind Feb 7, 2023
42525a9
V270 prep (#218)
dzalkind Feb 10, 2023
f5c3c1e
Add case generation updates
dzalkind Feb 10, 2023
a471783
Add initial AWC example, needs OF3.4
dzalkind Feb 10, 2023
2f941e3
Merge remote-tracking branch 'upstream/main' into develop
dzalkind Feb 10, 2023
d05ef6c
Merge branch 'develop' into rosco_awc_merge
dzalkind Feb 10, 2023
80bd691
Add AWC_Mode and move AWC into subroutine
dzalkind Feb 10, 2023
b102b34
Update example to point to correct inputs
dzalkind Feb 10, 2023
5c5333b
Remove LocalVar%PC_MinPit = CntrPar%PC_MinPit, breaking setpoint smoo…
dzalkind Feb 10, 2023
da46fac
Set min pitch for AWC
dzalkind Feb 10, 2023
cc4080d
Tidy up input additions
dzalkind Feb 10, 2023
1201a66
Update other DISCONs
dzalkind Feb 10, 2023
1693602
Add AWC to toolbox schema
dzalkind Feb 10, 2023
2bb0176
Tidy example
dzalkind Feb 10, 2023
d93d443
Update AWC example with instructions/theory
ndevelder Feb 14, 2023
3c40565
Formatting fixes
ndevelder Feb 14, 2023
83022e5
Prep for more modes
dzalkind Feb 15, 2023
a7d3303
Merge remote-tracking branch 'upstream/main' into develop
dzalkind Feb 15, 2023
f6d061f
Update 20_active_wake_control.py
kbrown1snl Feb 16, 2023
1824f99
Fix units in schema
dzalkind Feb 16, 2023
cabbb2a
Merge pull request #1 from kbrown1snl/patch-1
ndevelder Feb 17, 2023
de16ecd
Test all AWC cases in example 20
dzalkind Feb 17, 2023
de3a6fe
Tidy up DISCON file writing
dzalkind Feb 17, 2023
87b3f09
Revert setup directory
dzalkind Feb 17, 2023
46e7168
Update 20_active_wake_control.py
kbrown1snl Feb 22, 2023
32dc9fd
Update NREL-2p8-127_DISCON.IN
kbrown1snl Feb 24, 2023
ae5090b
Update Controllers.f90
kbrown1snl Feb 24, 2023
5c878ad
Update ROSCO_Types.f90
kbrown1snl Feb 24, 2023
baaa8db
Update ReadSetParameters.f90
kbrown1snl Feb 24, 2023
b141c4e
Update 20_active_wake_control.py
kbrown1snl Feb 24, 2023
826ca01
Update toolbox_schema.yaml
kbrown1snl Feb 24, 2023
797e554
Update utilities.py
kbrown1snl Feb 24, 2023
ff0ce39
Update rosco_types.yaml
kbrown1snl Feb 24, 2023
3bc2185
Added NREL-developed AWC-implementation
jfrederik-nrel Feb 27, 2023
687b760
Undo unintentional changes to wrie_registry.py
jfrederik-nrel Feb 28, 2023
70d5771
Fix file writing in AWC section
dzalkind Feb 28, 2023
b24f07b
Merge remote-tracking branch 'upstream/develop' into awc
dzalkind Feb 28, 2023
a9ec14e
Update all DISCONs
dzalkind Feb 28, 2023
4604ebb
Add 20_awc to test_examples
dzalkind Feb 28, 2023
b17f350
Add 2.8 to update_discons, regenerate DISCON
dzalkind Feb 28, 2023
b2fdfbc
Update AWC_Mode descriptions
dzalkind Feb 28, 2023
e899600
Updated Coleman Transformation based AWC
jfrederik-nrel Mar 7, 2023
1ccc1b3
Platform control and Optional Inputs (#227)
dzalkind Mar 7, 2023
87cde8c
Merge remote-tracking branch 'upstream/develop' into awc
dzalkind Mar 7, 2023
8ea0a4c
Merge remote-tracking branch 'jfred/AWC_NREL' into awc
dzalkind Mar 7, 2023
daf77e9
Merge remote-tracking branch 'ndev/rosco_awc_merge' into awc
dzalkind Mar 7, 2023
ca7c44d
Tidy print statements, file writing
dzalkind Mar 7, 2023
4e2a778
Remove duplicate PF_Offsets input read
dzalkind Mar 7, 2023
74c7fcb
Rename methods in readme
dzalkind Mar 7, 2023
e4d7ec2
Tidy input writing, remove `future` references
dzalkind Mar 7, 2023
4194da4
Force AWC_n into int
dzalkind Mar 8, 2023
c1e4be7
Force AWC_n into int better
dzalkind Mar 8, 2023
5e75601
Make AWC_n a list, too
dzalkind Mar 8, 2023
de8d228
Fix input file writing, force into int in write_array
dzalkind Mar 8, 2023
e1379de
Run ROSCO_testing from anywhere
dzalkind Mar 8, 2023
2947b4f
Dylib -> so in Test_Cases
dzalkind Mar 8, 2023
cae3f17
Updated AWC input parameters.
jfrederik-nrel Mar 15, 2023
bd4d7d5
Added checks for AWC inputs.
jfrederik-nrel Mar 16, 2023
1e25c88
Fixed bug in added AWC input checks.
jfrederik-nrel Mar 16, 2023
50f4191
Update error message
dzalkind Mar 20, 2023
50bd08c
Tidy up IPC, allow AWC and IPC with warning
dzalkind Mar 20, 2023
e02379d
Remove AWC references from IPC
dzalkind Mar 20, 2023
3851a6b
Remove lingering comment
dzalkind Mar 20, 2023
9d7e18d
Tidy file writing
dzalkind Mar 20, 2023
7f12c9c
Clean up comments
dzalkind Mar 20, 2023
8e4cf8b
Allow more than 99 local variables in dbg2
dzalkind Mar 20, 2023
bc33417
Update api_change.rst
jfrederik-nrel Mar 20, 2023
17ce1a5
Merge remote-tracking branch 'jfred/patch-1' into awc
dzalkind Mar 20, 2023
728c61d
Update 20_active_wake_control.py
kbrown1snl Mar 27, 2023
820aa66
Merge pull request #2 from kbrown1snl/patch-2
dzalkind Mar 27, 2023
90c4041
Add optimized NREL2p8 controller input
dzalkind Mar 30, 2023
5afb385
Parallelize output processing
dzalkind Apr 3, 2023
fbb44c4
Add IPC gain to NREL2p8
dzalkind Apr 3, 2023
fe24704
Merge remote-tracking branch 'upstream/develop' into power_ref_tracking
dzalkind Apr 3, 2023
52e3708
Finish merge with inputs and registry
dzalkind Apr 3, 2023
1e38c90
Update IPC example for testing sat modes
dzalkind Apr 3, 2023
e49f383
Add latest plot_FAST notebook
dzalkind Apr 3, 2023
9e5fd58
Add PRC example
dzalkind Apr 3, 2023
f1037ec
Merge remote-tracking branch 'origin/awc' into power_ref_tracking
dzalkind Apr 3, 2023
099532b
Finish merge with awc inputs and registry
dzalkind Apr 3, 2023
5a7046f
Active Wake Control (#230)
dzalkind Apr 3, 2023
8a39f3c
Update example with ramp, reference
dzalkind Apr 3, 2023
7669419
Merge remote-tracking branch 'upstream/develop' into power_ref_tracking
dzalkind Apr 3, 2023
de15e52
Various bug fixes (#233)
dzalkind Apr 4, 2023
ac14b17
Init PC_RefSpeed if no PRC
dzalkind Apr 5, 2023
60b366d
Revert openfast changes
dzalkind Apr 5, 2023
24bded0
Add note about offset
dzalkind Apr 5, 2023
585e2c8
Open loop platform control (#236)
dzalkind Apr 10, 2023
339ad53
Tidy example output
dzalkind Apr 10, 2023
79426f7
Increment version number
dzalkind Apr 10, 2023
90357a2
Merge remote-tracking branch 'upstream/develop' into power_ref_tracking
dzalkind Apr 20, 2023
12f8fdb
Merge remote-tracking branch 'upstream/main' into develop
dzalkind Jun 8, 2023
5fd97e2
Increment version number
dzalkind Jun 8, 2023
e5b1af5
Yaw Rate Bug Fix (#239)
dzalkind Jun 9, 2023
c701f67
OpenFAST 3.5.0 (#246)
dzalkind Jul 10, 2023
2f069da
Floating Feedback Gain Scheduling (#241)
alandwright Jul 20, 2023
9de385b
Merge remote-tracking branch 'upstream/develop' into power_ref_tracking
dzalkind Jul 24, 2023
d9547dd
Fix relative Cp filepaths
dzalkind Jul 24, 2023
178217b
Regenerate registry, inputs
dzalkind Jul 24, 2023
c641b54
Rotor Position Control (#255)
dzalkind Aug 4, 2023
31332d9
Update .readthedocs.yaml to remove use of 'system_packages' as it is …
abhineet-gupta Aug 9, 2023
63bcb0d
Extend ROSCO for MHK (#257)
AthulKrishnaSundarrajan Sep 19, 2023
716b2e4
Merge remote-tracking branch 'upstream/develop' into power_ref_tracking
dzalkind Sep 22, 2023
b27629b
Rename power ref example
dzalkind Sep 22, 2023
ea55560
Shorten PRC example
dzalkind Sep 22, 2023
b5eb5c0
Use updated DISCON writing functions for PRC inputs
dzalkind Sep 22, 2023
24052dc
Revert run_FAST cases
dzalkind Sep 25, 2023
3092e38
Tidy example documentation, output
dzalkind Sep 25, 2023
b817a5c
Bring back new VS_ControlMode that merge lost
dzalkind Sep 25, 2023
38f27de
Add LPF on WSE for speed selection, use gen speed rather than rotor
dzalkind Sep 26, 2023
d9a31fb
Document API changes
dzalkind Sep 26, 2023
32292e5
Bring back saturation of torque reference speed
dzalkind Sep 26, 2023
3b0bde0
Update PRC example with PRC_GenSpeeds
dzalkind Sep 26, 2023
e75baa2
Remove pCrunch notebook
dzalkind Sep 27, 2023
989ce5b
Merge pull request #170 from dzalkind/power_ref_tracking
abhineet-gupta Sep 27, 2023
2c76747
Increase max file unit (#253)
dzalkind Oct 6, 2023
b66cd11
Add types to scalars (#264)
rthedin Oct 17, 2023
0e80094
Update api_change.rst formatting
dzalkind Oct 17, 2023
f2a624d
Update .readthedocs.yaml with build.os
dzalkind Oct 17, 2023
6f1ccfa
Update .readthedocs.yaml with other build options
dzalkind Oct 17, 2023
80973fe
Update .readthedocs.yaml with python 3.9
dzalkind Oct 17, 2023
04d3f52
Update .readthedocs.yaml with new python version
dzalkind Oct 17, 2023
c479034
Update .readthedocs.yaml with another python version
dzalkind Oct 17, 2023
328d29e
Update .readthedocs.yaml with version key
dzalkind Oct 17, 2023
8693d4b
Update .readthedocs.yaml
dzalkind Oct 17, 2023
dd01047
Update .readthedocs.yaml remove old python version
dzalkind Oct 17, 2023
a610e55
Better Open Loop Control Error Catching (#273)
dzalkind Oct 27, 2023
c75738e
Modified ZeroMQ interface to include pitch offsets (#261)
mvanv Nov 6, 2023
1961f95
Merged upstream/develop
Mar 27, 2024
0ddbf0d
Merge remote-tracking branch 'upstream/develop' into develop
May 8, 2024
f846f17
Initial implementation of fixed blade pitch control for MHK turbines.…
May 9, 2024
748d975
Remove extra test_cases
dzalkind May 10, 2024
2787ff9
Expanded test script and made cc-blade Cp surface generation extend t…
May 10, 2024
c15e869
Merged and regenerated rotor performance in the right place
May 10, 2024
32ecfc8
updated DISCONs
May 10, 2024
8c57a31
Remove extra RefSpd localvars
dzalkind May 10, 2024
4c1202c
Merge remote-tracking branch 'ds/r3-fixed-pitch' into r3-fixed-pitch
dzalkind May 10, 2024
de4f6a7
Added overspeed config option and expanded Cp surface again
May 10, 2024
ae07303
Add constants for various VS_Control modes
dzalkind May 10, 2024
2df9e54
Regen registry
dzalkind May 10, 2024
8eab998
Cleaned up fixed pitch example script
May 10, 2024
38e28cf
Merge remote-tracking branch 'ds/r3-fixed-pitch' into r3-fixed-pitch
dzalkind May 10, 2024
1008cc6
Added comments to fixed pitch controller tuning, rearranged torque co…
May 13, 2024
25001e0
Finished renaming FBP variables and VS ref speed filter
May 13, 2024
822b731
Regenerated DISCONs
May 13, 2024
e639706
Merge remote-tracking branch 'ds/r3-fixed-pitch' into r3-fixed-pitch
dzalkind May 15, 2024
7726f0d
Disable the pitch controller at the DISCON level
dzalkind May 15, 2024
01121e2
Working on overspeed operating schedule, still not yet giving stable …
May 15, 2024
be58bbb
Merge branch 'r3-fixed-pitch' of https://github.com/dstockhouse/ROSCO…
May 15, 2024
102286d
Considerable cahnges to fixed-blade-pitch (FBP) operation for marine …
Jul 25, 2024
ead419d
Merge remote-tracking branch 'upstream/develop' into develop
Aug 15, 2024
f0debea
Merged branch upstream/develop
Aug 15, 2024
6216972
Fixed bug in FBP control with VS_RefSpd turning to NaN if GenTq ever …
Aug 21, 2024
ce1b0eb
Revised usage of generator and gearbox efficiencies in toolbox contro…
Aug 22, 2024
44703b6
Modified comments related to GBoxEff in rng2K calculation
Sep 5, 2024
d77ba20
Restructured some controller code related to saturation, attempted to…
Sep 18, 2024
6d79062
Added more precise calculation of Cp-optimizing pitch and updated the…
Sep 18, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
139 changes: 139 additions & 0 deletions Examples/29_marine_hydro_fbp.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,139 @@
'''
----------- 26_marine_hydro ------------------------
Run openfast with ROSCO and a MHK turbine
-----------------------------------------------


'''

import os
from rosco.toolbox.ofTools.case_gen.run_FAST import run_FAST_ROSCO
from rosco.toolbox.ofTools.case_gen import CaseLibrary as cl
from rosco.toolbox.ofTools.fast_io import output_processing
from rosco.toolbox import controller as ROSCO_controller
from rosco.toolbox import turbine as ROSCO_turbine
from rosco.toolbox.utilities import write_DISCON
from rosco.toolbox.inputs.validation import load_rosco_yaml
import matplotlib.pyplot as plt

'''
Run MHK turbine in OpenFAST with ROSCO torque controller


'''


#directories
this_dir = os.path.dirname(os.path.abspath(__file__))
rosco_dir = os.path.dirname(this_dir)
example_out_dir = os.path.join(this_dir,'examples_out')
os.makedirs(example_out_dir,exist_ok=True)

def main():

# Input yaml and output directory
parameter_filename = os.path.join(this_dir,'Tune_Cases/RM1_MHK_FBP.yaml')
run_dir = os.path.join(example_out_dir,'29_MHK/0_baseline')
os.makedirs(run_dir,exist_ok=True)

inps = load_rosco_yaml(parameter_filename)
path_params = inps['path_params']
turbine_params = inps['turbine_params']
controller_params = inps['controller_params']

# Instantiate turbine, controller, and file processing classes
turbine = ROSCO_turbine.Turbine(turbine_params)
controller = ROSCO_controller.Controller(controller_params)

# Load turbine data from OpenFAST and rotor performance text file
cp_filename = os.path.join(this_dir,path_params['rotor_performance_filename'])
turbine.load_from_fast(
path_params['FAST_InputFile'],
os.path.join(this_dir,path_params['FAST_directory']),
rot_source='txt',txt_filename= cp_filename
)

# Tune controller
controller.tune_controller(turbine)

# Write parameter input file
param_file = os.path.join(run_dir,'DISCON.IN')
write_DISCON(turbine,
controller,
param_file=param_file,
txt_filename=cp_filename
)

# # Plot operating schedule
# fig, ax = plt.subplots(2,2,constrained_layout=True,sharex=True)
# ax = ax.flatten()
# ax[0].plot(controller.v[len(controller.v_below_rated)+1:], controller.omega_pc_U)
# ax[0].set_ylabel('omega_pc')

# ax[1].plot(controller.v[len(controller.v_below_rated)+1:], controller.zeta_pc_U)
# ax[1].set_ylabel('zeta_pc')

# ax[2].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Kp)
# ax[2].set_xlabel('Wind Speed')
# ax[2].set_ylabel('Proportional Gain')

# ax[3].plot(controller.v[len(controller.v_below_rated)+1:], controller.pc_gain_schedule.Ki)
# ax[3].set_xlabel('Wind Speed')
# ax[3].set_ylabel('Integral Gain')

# plt.suptitle('Pitch Controller Gains')


# simulation set up
r = run_FAST_ROSCO()
r.tuning_yaml = parameter_filename
# r.wind_case_fcn = cl.simp_step # single step wind input
r.wind_case_fcn = cl.power_curve
r.wind_case_opts = {
'U': [3.5],
'TMax': 100.0,
}
r.case_inputs = {}
# r.fst_vt = reader.fst_vt
# r.controller_params = controller_params
r.save_dir = run_dir
r.rosco_dir = rosco_dir

r.run_FAST()

op = output_processing.output_processing()
fast_out = op.load_fast_out([os.path.join(run_dir,'RM1_MHK_FBP/power_curve/base/RM1_MHK_FBP_0.out')], tmin=0)
fig, axs = plt.subplots(4,1)
axs[0].plot(fast_out[0]['Time'],fast_out[0]['Wind1VelX'],label='Flow Speed')
axs[1].plot(fast_out[0]['Time'],fast_out[0]['GenSpeed'],label='Gen Speed')
axs[2].plot(fast_out[0]['Time'],fast_out[0]['GenTq'],label='Gen Torque')
axs[3].plot(fast_out[0]['Time'],fast_out[0]['GenPwr'],label='Gen Power')


# op = output_processing.output_processing()
# op2 = output_processing.output_processing()

# md_out = op.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.MD.Line1.out')], tmin=0)
# local_vars = op2.load_fast_out([os.path.join(run_dir,'IEA15MW_cable/power_curve/base/IEA15MW_cable_0.RO.dbg2')], tmin=0)

# fig, axs = plt.subplots(4,1)
# axs[0].plot(local_vars[0]['Time'],local_vars[0]['CC_DesiredL'],label='CC_DesiredL')
# axs[1].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedL'],label='CC_ActuatedL')
# axs[2].plot(local_vars[0]['Time'],local_vars[0]['CC_ActuatedDL'],label='CC_ActuatedDL')
# axs[3].plot(md_out[0]['Time'],md_out[0]['Seg20Lst'],label='Seg20Lst')

# [a.legend() for a in axs]
# [a.grid() for a in axs]

# if False:
# plt.show()
# else:
# plt.savefig(os.path.join(example_out_dir,'22_cable_control.png'))

# # Check that the last segment of line 1 shrinks by 10 m
# # np.testing.assert_almost_equal(md_out[0]['Seg20Lst'][-1] - md_out[0]['Seg20Lst'][0], line_ends[0], 2)



if __name__=="__main__":
main()
13 changes: 13 additions & 0 deletions Examples/ROSCO_walkthrough.ipynb
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
{
"cells": [
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -61,6 +62,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -133,6 +135,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand All @@ -153,6 +156,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -197,6 +201,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -250,6 +255,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -287,6 +293,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -362,6 +369,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -423,6 +431,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -593,6 +602,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand All @@ -604,6 +614,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -686,6 +697,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down Expand Up @@ -724,6 +736,7 @@
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"slideshow": {
Expand Down
6 changes: 3 additions & 3 deletions Examples/Test_Cases/MHK_RM1/MHK_RM1_Floating_ElastoDyn.dat
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ True PtfmYDOF - Platform yaw rotation DOF (flag)
---------------------- INITIAL CONDITIONS --------------------------------------
0 OoPDefl - Initial out-of-plane blade-tip displacement (meters)
0 IPDefl - Initial in-plane blade-tip deflection (meters)
10 BlPitch(1) - Blade 1 initial pitch (degrees)
10 BlPitch(2) - Blade 2 initial pitch (degrees)
10 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades]
0 BlPitch(1) - Blade 1 initial pitch (degrees)
0 BlPitch(2) - Blade 2 initial pitch (degrees)
0 BlPitch(3) - Blade 3 initial pitch (degrees) [unused for 2 blades]
0 TeetDefl - Initial or fixed teeter angle (degrees) [unused for 3 blades]
0 Azimuth - Initial azimuth angle for blade 1 (degrees)
11.50 RotSpeed - Initial or fixed rotor speed (rpm)
Expand Down
73 changes: 73 additions & 0 deletions Examples/Tune_Cases/RM1_MHK_FBP.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
--- # ---------------------NREL Generic controller tuning input file -------------------
# Written for use with ROSCO_Toolbox tuning procedures
# Turbine: RM1 Marine Turbine
# ------------------------------ OpenFAST PATH DEFINITIONS ------------------------------
path_params:
FAST_InputFile: 'MHK_RM1_Floating.fst' # Name of *.fst file
FAST_directory: '../Test_Cases/MHK_RM1' # Main OpenFAST model directory, where the *.fst lives
# Optional
rotor_performance_filename: '../Test_Cases/MHK_RM1/MHK_RM1_Cp_Ct_Cq.txt' # Filename for rotor performance text file (if it has been generated by ccblade already)

# -------------------------------- TURBINE PARAMETERS -----------------------------------
turbine_params:
rotor_inertia: 92169 # Rotor inertia [kg m^2], {Available in Elastodyn .sum file}
rated_rotor_speed: 1.204 # 11.5 rpm # Rated rotor speed [rad/s]
v_min: 0.5 # Cut-in wind speed [m/s]
v_rated: 2.0 # Rated wind speed [m/s]
v_max: 4.0 # Cut-out wind speed [m/s], -- Does not need to be exact (JUST ASSUME FOR NOW)
max_pitch_rate: 0.1745 # Maximum blade pitch rate [rad/s]
max_torque_rate: 1500000. # Maximum torque rate [Nm/s], {~1/4 VS_RtTq/s}
rated_power: 500000 # Rated Power [W]
bld_edgewise_freq: 60.2831853 # Blade edgewise first natural frequency [rad/s]
bld_flapwise_freq: 0.0 # Blade flapwise first natural frequency [rad/s]
reynolds_ref: 8e6
# Optional
# TSR_operational: # None # Desired below-rated operational tip speed ratio (Cp-maximizing TSR is used if not defined)
#------------------------------- CONTROLLER PARAMETERS ----------------------------------
controller_params:
# Controller flags
LoggingLevel: 2 # {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file
F_LPFType: 1 # {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals)
F_NotchType: 1 # Notch filter on generator speed and/or tower fore-aft motion (for floating) {0: disable, 1: generator speed, 2: tower-top fore-aft motion, 3: generator speed and tower-top fore-aft motion}
IPC_ControlMode: 0 # Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions}
VS_ControlMode: 4 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control}
VS_ConstPower: 0 # Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control}
PC_ControlMode: 0 # Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control}
Y_ControlMode: 0 # Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}
SS_Mode: 1 # Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing}
WE_Mode: 0 # Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Immersion and Invariance Estimator (Ortega et al.)}
PS_Mode: 0 # Pitch saturation mode {0: no pitch saturation, 1: peak shaving, 2: Cp-maximizing pitch saturation, 3: peak shaving and Cp-maximizing pitch saturation}
SD_Mode: 0 # Shutdown mode {0: no shutdown procedure, 1: pitch to max pitch at shutdown}
Fl_Mode: 1 # Floating specific feedback mode {0: no nacelle velocity feedback, 1: nacelle velocity feedback}
Flp_Mode: 0 # Flap control mode {0: no flap control, 1: steady state flap angle, 2: Proportional flap control}
# Controller parameters
U_pc: [2.3,2.5]
interp_type: sigma
zeta_pc: [0.7,0.7] # Pitch controller desired damping ratio [-]
omega_pc: [0.9,0.9] # Pitch controller desired natural frequency [rad/s]
zeta_vs: 1.0 # Torque controller desired damping ratio [-]
omega_vs: 0.8 # Torque controller desired natural frequency [rad/s]
twr_freq: 3.3404 # Tower natural frequency [rad/s] # 0.4499 (old value) 3.3404(new value)
# twr_freq: 0.061009 # 2P
ptfm_freq: 0.6613 # Platform natural frequency [rad/s] (OC4Hywind Parameters, here) 0.2325 (old value) 0.6613879263 (new value)
# Optional
ps_percent: 0.80 # Percent peak shaving [%, <= 1 ], {default = 80%}
sd_maxpit: 0.4363 # Maximum blade pitch angle to initiate shutdown [rad], {default = bld pitch at v_max}
Kp_float: -0.3897
max_torque_factor: 5
FBP_ref_mode: 1
FBP_P_mode: 0
FBP_U: [2.0, 4.0]
FBP_P: [1.0, 1.0]
DISCON:
F_NumNotchFilts: 0
F_NotchFreqs: [1.0, 2.4200] # 2P
F_NotchBetaNum: [0.0, 0.0]
F_NotchBetaDen: [0.25, 0.25]
F_GenSpdNotch_N: 0
F_GenSpdNotch_Ind: [1,2]
F_TwrTopNotch_N: 0
F_TwrTopNotch_Ind: [1,2]
F_NotchCornerFreq_GS: [2.42]
F_FlHighPassFreq: 1.5
VS_PwrFiltF: 0.05
6 changes: 6 additions & 0 deletions rosco/controller/rosco_registry/rosco_types.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1037,6 +1037,12 @@ LocalVariables:
RotSpeedF:
<<: *real
description: Filtered LSS (generator) speed [rad/s].
VS_RefSpd:
<<: *real
description: Generator speed set point of torque controller [rad/s]
PC_RefSpd:
<<: *real
description: Generator speed set point of pitch controller [rad/s]
GenSpeedF:
<<: *real
description: Filtered HSS (generator) speed [rad/s].
Expand Down
21 changes: 18 additions & 3 deletions rosco/controller/src/ControllerBlocks.f90
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa
TYPE(DebugVariables), INTENT(INOUT) :: DebugVar
TYPE(ErrorVariables), INTENT(INOUT) :: ErrVar

REAL(DbKi) :: VS_RefSpdRaw ! Temporary variable for applying LPF to the reference speed after it is generated

! ----- Pitch controller speed and power error -----

Expand Down Expand Up @@ -62,8 +63,22 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa
IF (CntrPar%VS_ControlMode == 2) THEN
LocalVar%VS_RefSpd_TSR = (CntrPar%VS_TSRopt * LocalVar%We_Vw_F / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio
ELSEIF (CntrPar%VS_ControlMode == 3) THEN
LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT,CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF)
LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesnt depend on wind speed estimate (https://doi.org/10.2172/1259805)
LocalVar%VS_GenPwrF = LPFilter(LocalVar%VS_GenPwr, LocalVar%DT, CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF)
LocalVar%VS_RefSpd_TSR = (LocalVar%VS_GenPwrF/CntrPar%VS_Rgn2K)**(1./3.) ! Genspeed reference that doesn't depend on wind speed estimate (https://doi.org/10.2172/1259805)
ELSEIF (CntrPar%VS_ControlMode == 4) THEN
IF (CntrPar%FBP_RefMode == 0) THEN
! Use WSE to look up speed reference
VS_RefSpdRaw = interp1d(CntrPar%FBP_U, CntrPar%FBP_Omega, LocalVar%WE_Vw, ErrVar)
ELSEIF (CntrPar%FBP_RefMode == 1) THEN
! Use LocalVar%GenTq or LocalVar%GenTqMeas, Omega must be expressed as a function of Tau
VS_RefSpdRaw = interp1d(CntrPar%FBP_Tau, CntrPar%FBP_Omega, LocalVar%GenTq, ErrVar)
ENDIF

! VS_RefSpdRaw = (LocalVar%GenTq/CntrPar%VS_Rgn2K)**(1./2.) ! WSE-independent below-rated generator speed reference based on torque instead of power
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What's happening with these commented pieces of code?

! VS_RefSpdRaw = min(VS_RefSpdRaw, (CntrPar%VS_RtPwr/(CntrPar%VS_GenEff/100.0))/LocalVar%GenTq) ! Above-rated underspeed reference
! VS_RefSpdRaw = min(VS_RefSpdRaw, CntrPar%VS_RefSpd) ! Saturate to rated speed

LocalVar%VS_RefSpd_TSR = LPFilter(VS_RefSpdRaw, LocalVar%DT, CntrPar%VS_PwrFiltF, LocalVar%FP, LocalVar%iStatus, LocalVar%restart, objInst%instLPF)
ELSE
LocalVar%VS_RefSpd_TSR = CntrPar%VS_RefSpd
ENDIF
Expand Down Expand Up @@ -97,7 +112,7 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst, DebugVar, ErrVa
LocalVar%VS_RefSpd = max(LocalVar%VS_RefSpd, CntrPar%VS_MinOmSpd)

! Reference error
IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3)) THEN
IF ((CntrPar%VS_ControlMode == 2) .OR. (CntrPar%VS_ControlMode == 3) .OR. (CntrPar%VS_ControlMode == 4)) THEN
LocalVar%VS_SpdErr = LocalVar%VS_RefSpd - LocalVar%GenSpeedF
ENDIF

Expand Down
Loading
Loading