/home/runner/work/kynema/kynema/kynema/src/utilities/aerodynamics/aerodyn_inflow.hpp Source File

Kynema API: /home/runner/work/kynema/kynema/kynema/src/utilities/aerodynamics/aerodyn_inflow.hpp Source File
Kynema API
A flexible multibody structural dynamics code for wind turbines
Loading...
Searching...
No Matches
aerodyn_inflow.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <array>
4#include <cmath>
5#include <numeric>
6#include <span>
7#include <stdexcept>
8#include <string>
9#include <utility>
10#include <vector>
11
13
14namespace kynema::util {
15
52 enum class ErrorLevel : uint8_t {
53 kNone = 0,
54 kInfo = 1,
55 kWarning = 2,
56 kSevereError = 3,
57 kFatalError = 4
58 };
59
60 static constexpr size_t kErrorMessagesLength{1025U}; //< Max error message length
62 static_cast<int>(ErrorLevel::kFatalError) //< Error level at which to abort
63 };
64 int error_status{0}; //< Error status
65 std::array<char, kErrorMessagesLength> error_message{}; //< Error message buffer
66
68 void CheckError() const {
70 throw std::runtime_error(error_message.data());
71 }
72 }
73};
74
77 float density{1.225F}; //< Air density (kg/m^3)
78 float kinematic_viscosity{1.464E-5F}; //< Kinematic viscosity (m^2/s)
79 float sound_speed{335.F}; //< Speed of sound in the working fluid (m/s)
80 float vapor_pressure{1700.F}; //< Vapor pressure of the working fluid (Pa)
81};
82
85 float gravity{9.81F}; //< Gravitational acceleration (m/s^2)
86 float atm_pressure{103500.F}; //< Atmospheric pressure (Pa)
87 float water_depth{30.F}; //< Water depth (m)
88 float msl_offset{0.F}; //< Mean sea level to still water level offset (m)
89};
90
106 std::array<double, 7> root_initial_position{
107 }; //< Initial root position of the blade (1 per blade)
108 std::vector<std::array<double, 7>>
109 node_initial_positions; //< Initial node positions of the blade
110
111 BladeInitialState(std::span<double, 7> root, std::span<const std::array<double, 7>> nodes) {
112 std::ranges::copy(root, std::begin(root_initial_position));
113 node_initial_positions.assign(std::begin(nodes), std::end(nodes));
114 }
115 };
116
117 bool is_horizontal_axis{true}; //< Is a horizontal axis turbine?
118 std::array<float, 3> reference_position{0.F, 0.F, 0.F}; //< Reference position of the turbine
119 std::array<double, 7> hub_initial_position{}; //< Initial hub position
120 std::array<double, 7> nacelle_initial_position{}; //< Initial nacelle position
121 std::vector<BladeInitialState>
122 blade_initial_states; //< Initial root and node positions of blades (size = n_blades)
123
125 bool is_hawt, std::span<const float, 3> ref_pos, std::span<const double, 7> hub_pos,
126 std::span<const double, 7> nacelle_pos, std::span<const BladeInitialState> blade_states
127 )
128 : is_horizontal_axis(is_hawt) {
129 std::ranges::copy(ref_pos, std::begin(reference_position));
130 std::ranges::copy(hub_pos, std::begin(hub_initial_position));
131 std::ranges::copy(nacelle_pos, std::begin(nacelle_initial_position));
132 blade_initial_states.assign(std::begin(blade_states), std::end(blade_states));
133 // Make sure the initial states are valid
134 Validate();
135 }
136
137 void Validate() const {
138 // Check if there are any blades defined
139 if (blade_initial_states.empty()) {
140 throw std::runtime_error("No blades defined. At least one blade is required.");
141 }
142
143 // Check if there are any nodes defined for each blade
144 if (std::ranges::any_of(blade_initial_states, [](auto& blade) {
145 return blade.node_initial_positions.empty();
146 })) {
147 throw std::runtime_error("No nodes defined for a blade. At least one node is required.");
148 }
149 }
150
152 [[nodiscard]] size_t NumberOfBlades() const { return blade_initial_states.size(); }
153};
154
163 std::span<const double, 7> data, std::span<float, 3> position,
164 std::array<std::array<double, 3>, 3>& orientation
165) {
166 // Set position (first 3 elements)
167 for (auto i : std::views::iota(0U, 3U)) {
168 position[i] = static_cast<float>(data[i]);
169 }
170
171 // Set orientation (converts last 4 elements i.e. quaternion -> 3x3 rotation matrix)
172 const auto om = Eigen::Quaternion<double>(data[3], data[4], data[5], data[6]).toRotationMatrix();
173 orientation = std::array{
174 std::array{om(0, 0), om(0, 1), om(0, 2)}, std::array{om(1, 0), om(1, 1), om(1, 2)},
175 std::array{om(2, 0), om(2, 1), om(2, 2)}
176 };
177}
178
187struct MeshData {
188 int32_t n_points; //< Number of mesh points (nodes)
189 std::vector<std::array<float, 3>> position; //< N x 3 array [x, y, z]
190 std::vector<std::array<std::array<double, 3>, 3>>
191 orientation; //< N x 9 array [r11, r12, ..., r33]
192 std::vector<std::array<float, 6>> velocity; //< N x 6 array [u, v, w, p, q, r]
193 std::vector<std::array<float, 6>>
194 acceleration; //< N x 6 array [u_dot, v_dot, w_dot, p_dot, q_dot, r_dot]
195 std::vector<std::array<float, 6>> load; //< N x 6 array [Fx, Fy, Fz, Mx, My, Mz]
196
198 explicit MeshData(size_t n_nodes)
199 : n_points(static_cast<int32_t>(n_nodes)),
200 position(n_nodes, std::array{0.F, 0.F, 0.F}),
202 n_nodes,
203 std::array{std::array{0., 0., 0.}, std::array{0., 0., 0.}, std::array{0., 0., 0.}}
204 ),
205 velocity(n_nodes, std::array{0.F, 0.F, 0.F, 0.F, 0.F, 0.F}),
206 acceleration(n_nodes, std::array{0.F, 0.F, 0.F, 0.F, 0.F, 0.F}),
207 load(n_nodes, std::array{0.F, 0.F, 0.F, 0.F, 0.F, 0.F}) {}
208
211 size_t n_mesh_pts, std::span<const std::array<double, 7>> pos,
212 std::span<const std::array<float, 6>> vel, std::span<const std::array<float, 6>> acc,
213 std::span<const std::array<float, 6>> ld
214 )
215 : n_points(static_cast<int32_t>(n_mesh_pts)),
216 position(n_mesh_pts, std::array{0.F, 0.F, 0.F}),
218 n_mesh_pts,
219 std::array{std::array{0., 0., 0.}, std::array{0., 0., 0.}, std::array{0., 0., 0.}}
220 ) {
221 velocity.assign(std::begin(vel), std::end(vel));
222 acceleration.assign(std::begin(acc), std::end(acc));
223 load.assign(std::begin(ld), std::end(ld));
224 // Set mesh position and orientation from 7x1 array [x, y, z, qw, qx, qy, qz]
225 for (auto i : std::views::iota(0U, NumberOfMeshPoints())) {
227 }
228
229 // Make sure the mesh data is valid
230 Validate();
231 }
232
233 void Validate() const {
234 // Check we have at least one node
235 if (n_points <= 0) {
236 throw std::invalid_argument("Number of mesh points must be at least 1");
237 }
238
239 // Check all vectors are the same size as the number of mesh points
240 auto check_vector_size = [](const auto& vec, size_t exp_size, const std::string& vec_name) {
241 if (vec.size() != exp_size) {
242 throw std::invalid_argument(vec_name + " vector size does not match n_mesh_points");
243 }
244 };
245
246 const auto expected_size = NumberOfMeshPoints();
247 check_vector_size(position, expected_size, "Position");
248 check_vector_size(orientation, expected_size, "Orientation");
249 check_vector_size(velocity, expected_size, "Velocity");
250 check_vector_size(acceleration, expected_size, "Acceleration");
251 check_vector_size(load, expected_size, "Loads");
252 }
253
255 [[nodiscard]] size_t NumberOfMeshPoints() const { return static_cast<size_t>(n_points); }
256
257 // Updates the values at the given point number
259 size_t point_number, std::span<const double, 7> pos, std::span<const double, 6> vel,
260 std::span<const double, 6> acc
261 ) {
262 if (std::cmp_greater_equal(point_number, n_points)) {
263 throw std::out_of_range("point number out of range.");
264 }
266 pos, this->position[point_number], this->orientation[point_number]
267 );
268 std::ranges::copy(vel, std::begin(velocity[point_number]));
269 std::ranges::copy(acc, std::begin(acceleration[point_number]));
270 }
271};
272
281 int32_t n_blades; //< Number of blades
282 MeshData hub; //< Hub data (1 point)
283 MeshData nacelle; //< Nacelle data (1 point)
284 MeshData blade_roots; //< Blade roots data (n_blades points)
285 MeshData blade_nodes; //< Blade nodes data (sum of nodes per blade)
286 std::array<float, 3> hh_vel; // Hub height wind velocity
287
296
305 std::vector<std::vector<size_t>> node_indices_by_blade;
306
315 explicit TurbineData(const TurbineConfig& tc)
316 : n_blades(static_cast<int32_t>(tc.NumberOfBlades())),
317 hub(1),
318 nacelle(1),
320 blade_nodes(CalculateTotalBladeNodes(tc)),
321 hh_vel({0.F, 0.F, 0.F}),
322 node_indices_by_blade(tc.NumberOfBlades()) {
323 // Initialize hub and nacelle data
324 InitializeHubAndNacelle(tc);
325
326 // Initialize blade data
327 InitializeBlades(tc);
328
329 // Make sure the turbine data is valid
330 Validate();
331 }
332
333 void Validate() const {
334 // Check if the number of blades is valid
335 if (n_blades < 1) {
336 throw std::runtime_error("Invalid number of blades. Must be at least 1.");
337 }
338
339 // Validate hub and nacelle data - should have exactly one mesh point each
340 if (hub.NumberOfMeshPoints() != 1 || nacelle.NumberOfMeshPoints() != 1) {
341 throw std::runtime_error("Hub and nacelle should have exactly one mesh point each.");
342 }
343
344 // Check if the number of blade roots matches the number of blades
346 throw std::runtime_error("Number of blade roots does not match number of blades.");
347 }
348
349 // Check if the blade nodes to blade number mapping is valid - should be the same size
351 throw std::runtime_error("Blade node to blade number mapping size mismatch.");
352 }
353
354 // Check if the node indices by blade are valid - should be same size as number of blades
355 if (node_indices_by_blade.size() != NumberOfBlades()) {
356 throw std::runtime_error("Node indices by blade size mismatch.");
357 }
358
359 // Check if the total number of blade nodes is valid - should be the same as the number of
360 // aggregrated blade nodes
361 const auto total_nodes = std::transform_reduce(
362 std::cbegin(node_indices_by_blade), std::cend(node_indices_by_blade), 0UL, std::plus{},
363 [](const auto& blade) {
364 return blade.size();
365 }
366 );
367 if (total_nodes != blade_nodes.NumberOfMeshPoints()) {
368 throw std::runtime_error("Total number of blade nodes mismatch.");
369 }
370 }
371
373 [[nodiscard]] size_t NumberOfBlades() const { return static_cast<size_t>(n_blades); }
374
390 size_t blade_number, size_t node_number, const std::array<double, 7>& position,
391 const std::array<double, 6>& velocity, const std::array<double, 6>& acceleration
392 ) {
393 // Check if the blade and node numbers are within the valid range
394 if (blade_number >= NumberOfBlades() ||
395 node_number >= node_indices_by_blade[blade_number].size()) {
396 throw std::out_of_range("Blade or node number out of range.");
397 }
398
399 // Rotation to convert blade orientation
400 const auto r_x2z = Eigen::Quaternion<double>(
401 Eigen::AngleAxis<double>(std::numbers::pi / 2., Eigen::Matrix<double, 3, 1>::Unit(1))
402 );
403
404 // Original orientation
405 const auto r = Eigen::Quaternion<double>(position[3], position[4], position[5], position[6]);
406
407 // Converted orientation
408 const auto r_adi = r * r_x2z;
409
410 // Position with new orientation
411 const std::array<double, 7> position_new{position[0], position[1], position[2], r_adi.w(),
412 r_adi.x(), r_adi.y(), r_adi.z()};
413
414 const size_t node_index = node_indices_by_blade[blade_number][node_number];
415 blade_nodes.SetValues(node_index, position_new, velocity, acceleration);
416 }
417
431 size_t blade_number, const std::array<double, 7>& position,
432 const std::array<double, 6>& velocity, const std::array<double, 6>& acceleration
433 ) {
434 if (std::cmp_greater_equal(blade_number, n_blades)) {
435 throw std::out_of_range("Blade number out of range.");
436 }
437
438 // Rotation to convert blade orientation
439 const auto r_x2z = Eigen::Quaternion<double>(
440 Eigen::AngleAxis<double>(std::numbers::pi / 2., Eigen::Matrix<double, 3, 1>::Unit(1))
441 );
442
443 // Original orientation
444 const auto r = Eigen::Quaternion<double>(position[3], position[4], position[5], position[6]);
445
446 // Converted orientation
447 const auto r_adi = r * r_x2z;
448
449 // Position with new orientation
450 const auto position_new = std::array{position[0], position[1], position[2], r_adi.w(),
451 r_adi.x(), r_adi.y(), r_adi.z()};
452
453 blade_roots.SetValues(blade_number, position_new, velocity, acceleration);
454 }
455
467 const std::array<double, 7>& position, const std::array<double, 6>& velocity,
468 const std::array<double, 6>& acceleration
469 ) {
470 this->hub.SetValues(0, position, velocity, acceleration);
471 }
472
484 const std::array<double, 7>& position, const std::array<double, 6>& velocity,
485 const std::array<double, 6>& acceleration
486 ) {
487 this->nacelle.SetValues(0, position, velocity, acceleration);
488 }
489
499 [[nodiscard]] std::array<double, 6> GetBladeNodeLoad(size_t blade_number, size_t node_number)
500 const {
501 if (std::cmp_greater_equal(blade_number, n_blades) ||
502 node_number >= node_indices_by_blade[blade_number].size()) {
503 throw std::out_of_range("Blade or node number out of range.");
504 }
505
506 // Get the loads for this blade and node
507 const size_t node_index = node_indices_by_blade[blade_number][node_number];
508 const auto loads = blade_nodes.load[node_index];
509
510 return std::array<double, 6>{
511 static_cast<double>(loads[0]), static_cast<double>(loads[1]),
512 static_cast<double>(loads[2]), static_cast<double>(loads[3]),
513 static_cast<double>(loads[4]), static_cast<double>(loads[5]),
514 };
515 }
516
517private:
519 static size_t CalculateTotalBladeNodes(const TurbineConfig& tc) {
520 return std::accumulate(
521 tc.blade_initial_states.begin(), tc.blade_initial_states.end(), size_t{0},
522 [](size_t sum, const auto& blade) {
523 return sum + blade.node_initial_positions.size();
524 }
525 );
526 }
527
529 void InitializeHubAndNacelle(const TurbineConfig& tc) {
530 SetPositionAndOrientation(tc.hub_initial_position, hub.position[0], hub.orientation[0]);
532 tc.nacelle_initial_position, nacelle.position[0], nacelle.orientation[0]
533 );
534 }
535
537 void InitializeBlades(const TurbineConfig& tc) {
538 size_t i_blade{0};
539 size_t i_node_total{0};
540
541 // Initialize blade roots and nodes
542 for (const auto& blade : tc.blade_initial_states) {
543 // Initialize blade root
544 this->SetBladeRootMotion(
545 i_blade, blade.root_initial_position, std::array<double, 6>{0., 0., 0., 0., 0., 0.},
546 std::array<double, 6>{0., 0., 0., 0., 0., 0.}
547 );
548
549 // Initialize blade nodes
550 size_t i_node{0};
551 for (const auto& position : blade.node_initial_positions) {
552 node_indices_by_blade[i_blade].emplace_back(i_node_total);
553 blade_nodes_to_blade_num_mapping.emplace_back(static_cast<int32_t>(i_blade + 1));
554
555 this->SetBladeNodeMotion(
556 i_blade, i_node, position,
557 std::array<double, 6>{0., 0., 0., 0., 0., 0.}, // velocity
558 std::array<double, 6>{0., 0., 0., 0., 0., 0.} // acceleration
559 );
560 ++i_node;
561 ++i_node_total;
562 }
563 ++i_blade;
564 }
565 }
566};
567
576 enum class DebugLevel : std::uint8_t {
577 kNone = 0, //< No debug output
578 kSummary = 1, //< Some summary info
579 kDetailed = 2, //< Above + all position/orientation info
580 kInputFiles = 3, //< Above + input files (if directly passed)
581 kAll = 4, //< Above + meshes
582 };
583
585 enum class OutputFormat : std::uint8_t {
586 kNone = 0, //< Disable write output
587 kText = 1, //< Write text file
588 kBinary = 2, //< Write binary file
589 kText_Binary = 3, //< Write text file and binary file
590 };
591
592 static constexpr size_t kDefaultStringLength{1025}; //< Max length for output filenames
593
594 // Input file handling
595 std::string aerodyn_input; //< Path to AeroDyn input file
596 std::string inflowwind_input; //< Path to InflowWind input file
597
598 // Interpolation order (must be either 1: linear, or 2: quadratic)
599 int interpolation_order{1}; //< Interpolation order - linear by default
600
601 // Initial time related variables
602 double time_step{0.1}; //< Simulation timestep (s)
603 double max_time{600.}; //< Maximum simulation time (s)
604 double total_elapsed_time{0.}; //< Total elapsed time (s)
605 int n_time_steps{0}; //< Number of time steps
606
607 // Flags
608 bool transpose_DCM{true}; //< Flag to transpose the direction cosine matrix
609 bool point_load_output{true}; //< Flag to output point loads
611
612 // Outputs
613 OutputFormat output_format{OutputFormat::kNone}; //< File format for writing outputs
614 std::string output_root_name{"ADI_out"}; //< Root name for output files
615 double output_time_step{0.1}; //< Time step for outputs to file
616 size_t n_channels{0}; //< Number of channels returned
617};
618
627 enum class WriteType : std::uint8_t {
628 kNone = 0, //< Disable VTK output
629 kInit = 1, //< Data at initialization
630 kAnimation = 2, //< Animation
631 };
632
634 enum class OutputType : std::uint8_t {
635 kSurface = 1, //< Surfaces
636 kLine = 2, //< Lines
637 kSurface_Line = 3, //< Both surfaces and lines
638 };
639
640 std::string output_dir_name{"ADI_vtk"}; //< VTK output directory name
641 WriteType write_vtk{WriteType::kNone}; //< Flag to write VTK output
642 OutputType vtk_type{OutputType::kLine}; //< Type of VTK output
643 double vtk_dt{0.}; //< VTK output time step
644 std::array<float, 6> vtk_nacelle_dimensions{//< Nacelle dimensions for VTK rendering
645 -2.5F, -2.5F, 0.F, 10.F, 5.F, 5.F
646 };
647 float vtk_hub_radius{1.5F}; //< Hub radius for VTK rendering
648};
649
670public:
682 const std::string& shared_lib_path = "aerodyn_inflow_c_binding.dll",
684 EnvironmentalConditions ec = EnvironmentalConditions{},
685 SimulationControls sc = SimulationControls{}, VTKSettings vtk = VTKSettings{}
686 )
687 : lib_{shared_lib_path, util::dylib::no_filename_decorations},
688 error_handling_{eh},
689 air_{fp},
690 env_conditions_{ec},
691 sim_controls_{std::move(sc)},
692 vtk_settings_{std::move(vtk)} {}
693
695 [[nodiscard]] const ErrorHandling& GetErrorHandling() const { return error_handling_; }
697 return env_conditions_;
698 }
699 [[nodiscard]] const FluidProperties& GetFluidProperties() const { return air_; }
700 [[nodiscard]] const SimulationControls& GetSimulationControls() const { return sim_controls_; }
701 [[nodiscard]] const VTKSettings& GetVTKSettings() const { return vtk_settings_; }
702
714 void Initialize(std::span<const TurbineConfig> turbine_configs) {
715 PreInitialize(turbine_configs.size());
716 SetupRotors(turbine_configs);
718 is_initialized_ = true;
719 }
720
726 void PreInitialize(size_t n_turbines) {
727 auto ADI_C_PreInit =
728 lib_.get_function<void(int*, int*, int*, int*, int*, char*)>("ADI_C_PreInit");
729
730 // Convert bool and other types to int32_t for Fortran compatibility
731 auto debug_level_int = static_cast<int32_t>(sim_controls_.debug_level);
732 auto transpose_dcm_int = sim_controls_.transpose_DCM ? 1 : 0;
733 auto n_turbines_int = static_cast<int32_t>(n_turbines);
734 auto point_load_output_int = sim_controls_.point_load_output ? 1 : 0;
735
736 ADI_C_PreInit(
737 &n_turbines_int, // input: Number of turbines
738 &transpose_dcm_int, // input: Transpose DCM?
739 &point_load_output_int, // input: output point loads?
740 &debug_level_int, // input: Debug level
741 &error_handling_.error_status, // output: Error status
742 error_handling_.error_message.data() // output: Error message
743 );
744
745 error_handling_.CheckError();
746 }
747
753 void SetupRotors(std::span<const TurbineConfig> turbine_configs) {
754 auto ADI_C_SetupRotor = lib_.get_function<
755 void(int*, int*, const float*, float*, double*, float*, double*, int*, float*, double*, int*, float*, double*, int*, int*, char*)>(
756 "ADI_C_SetupRotor"
757 );
758
759 // Loop through turbine configurations
760 int32_t turbine_number{0};
761 for (const auto& tc : turbine_configs) {
762 // Turbine number is 1 indexed i.e. 1, 2, 3, ...
763 ++turbine_number;
764
765 // Convert bool -> int32_t to pass to the Fortran routine
766 int32_t is_horizontal_axis_int = tc.is_horizontal_axis ? 1 : 0;
767
768 // Validate the turbine config
769 tc.Validate();
770
771 // Create new turbine data to store the updates
772 // Note: TurbineData and MeshData are validated during construction, so no need to
773 // perform additional checks here
774 turbines.emplace_back(tc);
775 auto& td = turbines.back();
776
777 // Call setup rotor for each turbine
778 ADI_C_SetupRotor(
779 &turbine_number, // input: current turbine number
780 &is_horizontal_axis_int, // input: 1: HAWT, 0: VAWT or cross-flow
781 tc.reference_position.data(), // input: turbine reference position
782 td.hub.position[0].data(), // input: initial hub position
783 td.hub.orientation[0][0].data(), // input: initial hub orientation
784 td.nacelle.position[0].data(), // input: initial nacelle position
785 td.nacelle.orientation[0][0].data(), // input: initial nacelle orientation
786 &td.n_blades, // input: number of blades
787 td.blade_roots.position[0].data(), // input: initial blade root positions
788 td.blade_roots.orientation[0].data()->data(
789 ), // input: initial blade root orientation
790 &td.blade_nodes.n_points, // input: number of mesh points
791 td.blade_nodes.position[0].data(), // input: initial node positions
792 td.blade_nodes.orientation[0][0].data(), // input: initial node orientation
793 td.blade_nodes_to_blade_num_mapping.data(
794 ), // input: blade node to blade number mapping
795 &error_handling_.error_status, // output: Error status
796 error_handling_.error_message.data() // output: Error message buffer
797 );
798
799 error_handling_.CheckError();
800 }
801 }
802
807 auto ADI_C_Init = lib_.get_function<
808 void(int*, char**, int*, int*, char**, int*, const char*, const char*, float*, float*, float*, float*, float*, float*, float*, float*, int*, double*, double*, int*, int*, int*, double*, float*, float*, int*, double*, int*, char*, char*, int*, char*)>(
809 "ADI_C_Init"
810 );
811
812 // Convert bool -> int32_t to pass to the Fortran routine
813 int32_t is_aerodyn_input_passed_as_string = 0; // AeroDyn input is path to file
814 int32_t is_inflowwind_input_passed_as_string = 0; // InflowWind input is path to file
815 int32_t store_HH_wind_speed_int = 1;
816
817 // Primary input file will be passed as path to the file
818 char* aerodyn_input_pointer{sim_controls_.aerodyn_input.data()};
819 auto aerodyn_input_length = static_cast<int32_t>(sim_controls_.aerodyn_input.size());
820
821 char* inflowwind_input_pointer{sim_controls_.inflowwind_input.data()};
822 auto inflowwind_input_length = static_cast<int32_t>(sim_controls_.inflowwind_input.size());
823
824 // Channel name and channel unit string arrays
825 std::string channel_names_c((20 * 8000) + 1, ' '); //< Output channel names
826 std::string channel_units_c((20 * 8000) + 1, ' '); //< Output channel units
827
828 // Number of output channels (set by ADI_C_Init)
829 int32_t n_channels{0};
830
831 // Write output format as integer for Fortran routine
832 auto output_format = static_cast<int32_t>(sim_controls_.output_format);
833
834 // VTK write type and output type as integers
835 auto write_vtk = static_cast<int32_t>(vtk_settings_.write_vtk);
836 auto vtk_type = static_cast<int32_t>(vtk_settings_.vtk_type);
837
838 ADI_C_Init(
839 &is_aerodyn_input_passed_as_string, // input: AD input is passed
840 &aerodyn_input_pointer, // input: AD input file as string
841 &aerodyn_input_length, // input: AD input file string length
842 &is_inflowwind_input_passed_as_string, // input: IfW input is passed
843 &inflowwind_input_pointer, // input: IfW input file as string
844 &inflowwind_input_length, // input: IfW input file string length
845 sim_controls_.output_root_name.c_str(), // input: rootname for ADI file writing
846 vtk_settings_.output_dir_name.c_str(), // input: VTK output directory name
847 &env_conditions_.gravity, // input: gravity
848 &air_.density, // input: air density
849 &air_.kinematic_viscosity, // input: kinematic viscosity
850 &air_.sound_speed, // input: speed of sound
851 &env_conditions_.atm_pressure, // input: atmospheric pressure
852 &air_.vapor_pressure, // input: vapor pressure
853 &env_conditions_.water_depth, // input: water depth
854 &env_conditions_.msl_offset, // input: MSL to SWL offset
855 &sim_controls_.interpolation_order, // input: interpolation order
856 &sim_controls_.time_step, // input: time step
857 &sim_controls_.max_time, // input: maximum simulation time
858 &store_HH_wind_speed_int, // input: store HH wind speed
859 &write_vtk, // input: write VTK output
860 &vtk_type, // input: VTK output type
861 &vtk_settings_.vtk_dt, // input: VTK output time step
862 vtk_settings_.vtk_nacelle_dimensions.data(), // input: VTK nacelle dimensions
863 &vtk_settings_.vtk_hub_radius, // input: VTK hub radius
864 &output_format, // input: output format
865 &sim_controls_.output_time_step, // input: output time step
866 &n_channels, // output: number of channels
867 channel_names_c.data(), // output: output channel names
868 channel_units_c.data(), // output: output channel units
869 &error_handling_.error_status, // output: error status
870 error_handling_.error_message.data() // output: error message buffer
871 );
872
873 // Allocate vector of output channel values
874 sim_controls_.n_channels = static_cast<size_t>(n_channels);
875 channel_values = std::vector<float>(sim_controls_.n_channels, 0.F);
876 channel_names.resize(sim_controls_.n_channels);
877 channel_units.resize(sim_controls_.n_channels);
878 std::string tmp;
879 for (auto i : std::views::iota(0U, sim_controls_.n_channels)) {
880 tmp = channel_names_c.substr(20UL * i, 20);
881 tmp.erase(tmp.find_last_not_of(' ') + 1);
882 channel_names[i] = tmp;
883 tmp = channel_units_c.substr(20UL * i, 20);
884 tmp.erase(tmp.find_last_not_of(' ') + 1);
885 channel_units[i] = tmp;
886 }
887
888 error_handling_.CheckError();
889 is_initialized_ = true;
890 }
891
899 auto
900 ADI_C_SetRotorMotion =
901 lib_
903 void(int*, const float*, const double*, const float*, const float*, const float*, const double*, const float*, const float*, const float*, const double*, const float*, const float*, const int*, const float*, const double*, const float*, const float*, int*, char*)>(
904 "ADI_C_SetRotorMotion"
905 );
906
907 // Loop through turbines and set the rotor motion
908 int32_t turbine_number{0};
909 for (const auto& td : turbines) {
910 // Turbine number is 1 indexed i.e. 1, 2, 3, ...
911 ++turbine_number;
912 ADI_C_SetRotorMotion(
913 &turbine_number, // input: current turbine number
914 td.hub.position[0].data(), // input: hub positions
915 td.hub.orientation[0][0].data(), // input: hub orientations
916 td.hub.velocity[0].data(), // input: hub velocities
917 td.hub.acceleration[0].data(), // input: hub accelerations
918 td.nacelle.position[0].data(), // input: nacelle positions
919 td.nacelle.orientation[0][0].data(), // input: nacelle orientations
920 td.nacelle.velocity[0].data(), // input: nacelle velocities
921 td.nacelle.acceleration[0].data(), // input: nacelle accelerations
922 td.blade_roots.position[0].data(), // input: root positions
923 td.blade_roots.orientation[0][0].data(), // input: root orientations
924 td.blade_roots.velocity[0].data(), // input: root velocities
925 td.blade_roots.acceleration[0].data(), // input: root accelerations
926 &td.blade_nodes.n_points, // input: number of mesh points
927 td.blade_nodes.position[0].data(), // input: mesh positions
928 td.blade_nodes.orientation[0][0].data(), // input: mesh orientations
929 td.blade_nodes.velocity[0].data(), // input: mesh velocities
930 td.blade_nodes.acceleration[0].data(), // input: mesh accelerations
931 &error_handling_.error_status, // output: error status
932 error_handling_.error_message.data() // output: error message buffer
933 );
934
935 error_handling_.CheckError();
936 }
937 }
938
947 void CalculateOutput(double time) {
948 auto ADI_C_CalcOutput =
949 lib_.get_function<void(double*, float*, int*, char*)>("ADI_C_CalcOutput");
950
951 ADI_C_CalcOutput(
952 &time, // input: time at which to calculate output forces
953 channel_values.data(), // output: output channel values
954 &error_handling_.error_status, // output: error status
955 error_handling_.error_message.data() // output: error message buffer
956 );
957
958 error_handling_.CheckError();
959
960 auto ADI_C_GetRotorLoads =
961 lib_.get_function<void(int*, int*, float*, float*, int*, char*)>("ADI_C_GetRotorLoads");
962
963 // Loop through turbines and get the rotor loads
964 int32_t turbine_number{0};
965 for (auto& td : turbines) {
966 // Turbine number is 1 indexed i.e. 1, 2, 3, ...
967 ++turbine_number;
968
969 ADI_C_GetRotorLoads(
970 &turbine_number, // input: current turbine number
971 &td.blade_nodes.n_points, // input: number of mesh points
972 td.blade_nodes.load[0].data(), // output: mesh force/moment array
973 td.hh_vel.data(), // output: hub height wind velocity array
974 &error_handling_.error_status, // output: error status
975 error_handling_.error_message.data() // output: error message buffer
976 );
977
978 error_handling_.CheckError();
979 }
980 }
981
991 void UpdateStates(double current_time, double next_time) {
992 auto ADI_C_UpdateStates =
993 lib_.get_function<void(double*, double*, int*, char*)>("ADI_C_UpdateStates");
994
995 ADI_C_UpdateStates(
996 &current_time, // input: current time
997 &next_time, // input: next time step
998 &error_handling_.error_status, // output: error status
999 error_handling_.error_message.data() // output: error message buffer
1000 );
1001
1002 error_handling_.CheckError();
1003 }
1004
1011 void Finalize() {
1012 auto ADI_C_End = lib_.get_function<void(int*, char*)>("ADI_C_End");
1013
1014 ADI_C_End(
1015 &error_handling_.error_status, // output: error status
1016 error_handling_.error_message.data() // output: error message buffer
1017 );
1018
1019 error_handling_.CheckError();
1020 is_initialized_ = false;
1021 }
1022
1023 std::vector<TurbineData> turbines; //< Turbine data (1 per turbine)
1024 std::vector<std::string> channel_names; //< Output channel names
1025 std::vector<std::string> channel_units; //< Output channel units
1026 std::vector<float> channel_values; //< Output channel values
1027
1028private:
1029 bool is_initialized_{false}; //< Flag to check if the library is initialized
1030 util::dylib lib_; //< Dynamic library object for AeroDyn Inflow
1031 ErrorHandling error_handling_; //< Error handling settings
1032 FluidProperties air_; //< Properties of the working fluid (air)
1033 EnvironmentalConditions env_conditions_; //< Environmental conditions
1034 SimulationControls sim_controls_; //< Simulation control settings
1035 VTKSettings vtk_settings_; //< VTK output settings
1036};
1037
1038} // namespace kynema::util
Wrapper class for the AeroDynInflow (ADI) shared library.
Definition aerodyn_inflow.hpp:669
void Finalize()
Ends the simulation and frees memory.
Definition aerodyn_inflow.hpp:1011
const VTKSettings & GetVTKSettings() const
Definition aerodyn_inflow.hpp:701
void CalculateOutput(double time)
Calculates the output channels at a given time.
Definition aerodyn_inflow.hpp:947
std::vector< std::string > channel_names
Definition aerodyn_inflow.hpp:1024
void Initialize(std::span< const TurbineConfig > turbine_configs)
Initialize the AeroDyn Inflow library.
Definition aerodyn_inflow.hpp:714
void FinalizeInitialization()
Finalizes the initialization process.
Definition aerodyn_inflow.hpp:806
void SetupRotors(std::span< const TurbineConfig > turbine_configs)
Sets up rotor configurations for all turbines.
Definition aerodyn_inflow.hpp:753
const FluidProperties & GetFluidProperties() const
Definition aerodyn_inflow.hpp:699
void SetRotorMotion()
Set up the rotor motion for the current simulation step.
Definition aerodyn_inflow.hpp:898
AeroDynInflowLibrary(const std::string &shared_lib_path="aerodyn_inflow_c_binding.dll", ErrorHandling eh=ErrorHandling{}, FluidProperties fp=FluidProperties{}, EnvironmentalConditions ec=EnvironmentalConditions{}, SimulationControls sc=SimulationControls{}, VTKSettings vtk=VTKSettings{})
Construct a new AeroDynInflowLibrary object.
Definition aerodyn_inflow.hpp:681
const SimulationControls & GetSimulationControls() const
Definition aerodyn_inflow.hpp:700
std::vector< std::string > channel_units
Definition aerodyn_inflow.hpp:1025
std::vector< float > channel_values
Definition aerodyn_inflow.hpp:1026
const ErrorHandling & GetErrorHandling() const
Getter methods for the private member variables.
Definition aerodyn_inflow.hpp:695
const EnvironmentalConditions & GetEnvironmentalConditions() const
Definition aerodyn_inflow.hpp:696
void UpdateStates(double current_time, double next_time)
Updates the states of the AeroDyn Inflow library.
Definition aerodyn_inflow.hpp:991
std::vector< TurbineData > turbines
Definition aerodyn_inflow.hpp:1023
void PreInitialize(size_t n_turbines)
Performs pre-initialization setup.
Definition aerodyn_inflow.hpp:726
Definition dylib.hpp:62
T * get_function(const char *symbol_name) const
Definition dylib.hpp:246
C++ cross-platform wrapper around dynamic loading of shared libraries.
Definition aerodyn_inflow.hpp:14
void SetPositionAndOrientation(std::span< const double, 7 > data, std::span< float, 3 > position, std::array< std::array< double, 3 >, 3 > &orientation)
Converts a 7-element array of position and quaternion to separate position and orientation arrays.
Definition aerodyn_inflow.hpp:162
blade
Definition preprocess_windio_exp.py:52
Struct to hold the environmental conditions.
Definition aerodyn_inflow.hpp:84
float water_depth
Definition aerodyn_inflow.hpp:87
float msl_offset
Definition aerodyn_inflow.hpp:88
float gravity
Definition aerodyn_inflow.hpp:85
float atm_pressure
Definition aerodyn_inflow.hpp:86
Struct for error handling settings.
Definition aerodyn_inflow.hpp:50
void CheckError() const
Checks for errors and throws an exception if found.
Definition aerodyn_inflow.hpp:68
std::array< char, kErrorMessagesLength > error_message
Definition aerodyn_inflow.hpp:65
int error_status
Definition aerodyn_inflow.hpp:64
ErrorLevel
Error levels used in InflowWind.
Definition aerodyn_inflow.hpp:52
static constexpr size_t kErrorMessagesLength
Definition aerodyn_inflow.hpp:60
int abort_error_level
Definition aerodyn_inflow.hpp:61
Struct to hold the properties of the working fluid (air)
Definition aerodyn_inflow.hpp:76
float density
Definition aerodyn_inflow.hpp:77
float kinematic_viscosity
Definition aerodyn_inflow.hpp:78
float vapor_pressure
Definition aerodyn_inflow.hpp:80
float sound_speed
Definition aerodyn_inflow.hpp:79
Struct to hold the motion + loads data of any structural mesh component in AeroDyn/InflowWind compati...
Definition aerodyn_inflow.hpp:187
int32_t n_points
Definition aerodyn_inflow.hpp:188
MeshData(size_t n_nodes)
Constructor to initialize all mesh data to zero based on provided number of nodes.
Definition aerodyn_inflow.hpp:198
std::vector< std::array< float, 6 > > velocity
Definition aerodyn_inflow.hpp:192
std::vector< std::array< std::array< double, 3 >, 3 > > orientation
Definition aerodyn_inflow.hpp:191
size_t NumberOfMeshPoints() const
Returns the number of mesh points as size_t.
Definition aerodyn_inflow.hpp:255
MeshData(size_t n_mesh_pts, std::span< const std::array< double, 7 > > pos, std::span< const std::array< float, 6 > > vel, std::span< const std::array< float, 6 > > acc, std::span< const std::array< float, 6 > > ld)
Constructor to initialize all mesh data based on provided inputs.
Definition aerodyn_inflow.hpp:210
std::vector< std::array< float, 6 > > load
Definition aerodyn_inflow.hpp:195
void Validate() const
Definition aerodyn_inflow.hpp:233
std::vector< std::array< float, 3 > > position
Definition aerodyn_inflow.hpp:189
void SetValues(size_t point_number, std::span< const double, 7 > pos, std::span< const double, 6 > vel, std::span< const double, 6 > acc)
Definition aerodyn_inflow.hpp:258
std::vector< std::array< float, 6 > > acceleration
Definition aerodyn_inflow.hpp:194
Struct to hold the settings for simulation controls.
Definition aerodyn_inflow.hpp:574
size_t n_channels
Definition aerodyn_inflow.hpp:616
std::string aerodyn_input
Definition aerodyn_inflow.hpp:595
std::string inflowwind_input
Definition aerodyn_inflow.hpp:596
int interpolation_order
Definition aerodyn_inflow.hpp:599
double total_elapsed_time
Definition aerodyn_inflow.hpp:604
std::string output_root_name
Definition aerodyn_inflow.hpp:614
bool point_load_output
Definition aerodyn_inflow.hpp:609
double max_time
Definition aerodyn_inflow.hpp:603
static constexpr size_t kDefaultStringLength
Definition aerodyn_inflow.hpp:592
double time_step
Definition aerodyn_inflow.hpp:602
OutputFormat
Write output format.
Definition aerodyn_inflow.hpp:585
bool transpose_DCM
Definition aerodyn_inflow.hpp:608
int n_time_steps
Definition aerodyn_inflow.hpp:605
DebugLevel debug_level
Definition aerodyn_inflow.hpp:610
double output_time_step
Definition aerodyn_inflow.hpp:615
DebugLevel
Debug levels used in AeroDyn-Inflow C bindings.
Definition aerodyn_inflow.hpp:576
OutputFormat output_format
Definition aerodyn_inflow.hpp:613
Initial state for a single blade of a turbine.
Definition aerodyn_inflow.hpp:105
std::vector< std::array< double, 7 > > node_initial_positions
Definition aerodyn_inflow.hpp:109
std::array< double, 7 > root_initial_position
Definition aerodyn_inflow.hpp:106
BladeInitialState(std::span< double, 7 > root, std::span< const std::array< double, 7 > > nodes)
Definition aerodyn_inflow.hpp:111
Configuration for the initial state of a turbine.
Definition aerodyn_inflow.hpp:98
std::array< double, 7 > nacelle_initial_position
Definition aerodyn_inflow.hpp:120
TurbineConfig(bool is_hawt, std::span< const float, 3 > ref_pos, std::span< const double, 7 > hub_pos, std::span< const double, 7 > nacelle_pos, std::span< const BladeInitialState > blade_states)
Definition aerodyn_inflow.hpp:124
std::array< float, 3 > reference_position
Definition aerodyn_inflow.hpp:118
void Validate() const
Definition aerodyn_inflow.hpp:137
std::array< double, 7 > hub_initial_position
Definition aerodyn_inflow.hpp:119
bool is_horizontal_axis
Definition aerodyn_inflow.hpp:117
std::vector< BladeInitialState > blade_initial_states
Definition aerodyn_inflow.hpp:122
size_t NumberOfBlades() const
Returns the number of blades in the turbine.
Definition aerodyn_inflow.hpp:152
Struct to hold and manage turbine-specific data.
Definition aerodyn_inflow.hpp:280
void SetBladeNodeMotion(size_t blade_number, size_t node_number, const std::array< double, 7 > &position, const std::array< double, 6 > &velocity, const std::array< double, 6 > &acceleration)
Sets the blade node values based on blade number and node number.
Definition aerodyn_inflow.hpp:389
MeshData blade_roots
Definition aerodyn_inflow.hpp:284
void SetNacelleMotion(const std::array< double, 7 > &position, const std::array< double, 6 > &velocity, const std::array< double, 6 > &acceleration)
Sets the nacelle motion values.
Definition aerodyn_inflow.hpp:483
std::array< double, 6 > GetBladeNodeLoad(size_t blade_number, size_t node_number) const
Gets the blade node loads based on blade number and node number.
Definition aerodyn_inflow.hpp:499
void SetBladeRootMotion(size_t blade_number, const std::array< double, 7 > &position, const std::array< double, 6 > &velocity, const std::array< double, 6 > &acceleration)
Sets the blade root values based on blade number.
Definition aerodyn_inflow.hpp:430
MeshData hub
Definition aerodyn_inflow.hpp:282
std::array< float, 3 > hh_vel
Definition aerodyn_inflow.hpp:286
void Validate() const
Definition aerodyn_inflow.hpp:333
MeshData nacelle
Definition aerodyn_inflow.hpp:283
std::vector< int32_t > blade_nodes_to_blade_num_mapping
Mapping of blade nodes to blade numbers (1D array)
Definition aerodyn_inflow.hpp:295
TurbineData(const TurbineConfig &tc)
Constructor for TurbineData based on a TurbineConfig object.
Definition aerodyn_inflow.hpp:315
std::vector< std::vector< size_t > > node_indices_by_blade
Unique indices of nodes for each blade (2D array)
Definition aerodyn_inflow.hpp:305
size_t NumberOfBlades() const
Returns the number of blades as size_t.
Definition aerodyn_inflow.hpp:373
int32_t n_blades
Definition aerodyn_inflow.hpp:281
void SetHubMotion(const std::array< double, 7 > &position, const std::array< double, 6 > &velocity, const std::array< double, 6 > &acceleration)
Sets the hub motion values.
Definition aerodyn_inflow.hpp:466
MeshData blade_nodes
Definition aerodyn_inflow.hpp:285
Struct to hold the settings for VTK output.
Definition aerodyn_inflow.hpp:625
OutputType vtk_type
Definition aerodyn_inflow.hpp:642
float vtk_hub_radius
Definition aerodyn_inflow.hpp:647
std::string output_dir_name
Definition aerodyn_inflow.hpp:640
double vtk_dt
Definition aerodyn_inflow.hpp:643
WriteType write_vtk
Definition aerodyn_inflow.hpp:641
std::array< float, 6 > vtk_nacelle_dimensions
Definition aerodyn_inflow.hpp:644
WriteType
Write type.
Definition aerodyn_inflow.hpp:627
OutputType
Mesh output type.
Definition aerodyn_inflow.hpp:634