diff --git a/.github/workflows/pypi_build.yaml b/.github/workflows/pypi_build.yaml new file mode 100644 index 000000000..c39115d99 --- /dev/null +++ b/.github/workflows/pypi_build.yaml @@ -0,0 +1,90 @@ +name: Create and publish pypi image + +on: + # only runs when there are pushes to develop and main for publishing + # and for testing, pull requests to develop and main + # and if there are changes to the build process and github action + push: + branches: + - develop + - main + paths: + - 'setup.py' + - '.github/workflows/pypi*' + pull_request: + branches: + - main + - develop + - 'rc*' + +jobs: + create-pypi-image: + name: >- + Create .whl 🛞 from SHARPy distribution + runs-on: ubuntu-20.04 + env: + python-version-chosen: "3.10.8" + permissions: + contents: read + packages: write + + steps: + - uses: actions/checkout@v2 + - name: Set up Python ${{ env.python-version-chosen }} + uses: actions/setup-python@v2 + with: + python-version: ${{ env.python-version-chosen }} + - name: Set up GCC + uses: egor-tensin/setup-gcc@v1 + with: + version: 7 + platform: x64 + - name: Pre-Install dependencies + run: | + export QT_QPA_PLATFORM='offscreen' + sudo apt install libeigen3-dev + git submodule init + git submodule update + - name: Install pypa/build + run: >- + python3 -m + pip install + build + --user + - name: Install wheel + run: python3 -m pip install wheel --user + - name: Build a source tarball + run: python setup.py sdist + - name: Build a binary wheel + run: python3 setup.py bdist_wheel + - name: Find the wheel created during pip install + run: + python3 -m pip cache dir + - name: Store the distribution packages + uses: actions/upload-artifact@v4 + with: + name: python-package-distributions + path: dist/ + + publish-to-pypi: + name: >- + Publish Python 🐍 distribution 📦 to PyPI + if: startsWith(github.ref, 'refs/tags/v') # only publish to PyPI on tag pushes + needs: + - create-pypi-image + runs-on: ubuntu-latest + environment: + name: pypi + url: https://pypi.org/p/ic_sharpy # Replace with your PyPI project name + permissions: + id-token: write # IMPORTANT: mandatory for trusted publishing + steps: + - name: Download all the dists + uses: actions/download-artifact@v4 + with: + name: python-package-distributions + path: dist/ + - name: Publish distribution 📦 to PyPI + uses: pypa/gh-action-pypi-publish@release/v1 + # with: + # path: dist/* diff --git a/.github/workflows/readme.md b/.github/workflows/readme.md index 3124c604b..f8762f531 100644 --- a/.github/workflows/readme.md +++ b/.github/workflows/readme.md @@ -1,6 +1,6 @@ # SHARPy GitHub Workflows -There are 4 automated workflows for SHARPy's CI/CD. +There are 4(+1 experimental) automated workflows for SHARPy's CI/CD. ## SHARPy Tests @@ -19,5 +19,12 @@ Python code, hence allowing the merge. Two nearly identical workflows, the only difference is that one pushes the Docker image to the SHARPy packages. Therefore: - * `docker_build.yaml`: Builds the Docker image but does not push. Runs on changes to the `docker*` workflows, changes to the `utils/` directory (environments) and changes to the `Dockerfile`. Required test for PRs to merge to `develop` and `main`. + * `docker_build_test.yaml`: Builds the Docker image but does not push. Runs on changes to the `docker*` workflows, changes to the `utils/` directory (environments) and changes to the `Dockerfile`. Required test for PRs to merge to `develop` and `main`. * `docker_build.yaml`: Builds and pushes the Docker image. Runs on pushes to `develop`, `main` and annotated tags. + +## Pypi (experimental!) + +One workflow with two jobs, the first creates and the second pushes the wheel +artifact to ic-sharpy @ pypi. Therefore: + + * `pypi_build.yaml`: Builds and pushes the pypi wheel according to conditions. Runs on changes to the `pypi*` workflow, changes to the `setup.py`, and PRs and pushes to main and develop. Required test for PRs to merge to `develop` and `main`. Publishes on annotated tags. diff --git a/CHANGELOG.md b/CHANGELOG.md index ee8733634..dc9683176 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,48 @@ # Changelog +## [2.3](https://github.com/imperialcollegelondon/sharpy/tree/2.3) (2024-05-10) + +[Full Changelog](https://github.com/imperialcollegelondon/sharpy/compare/2.2...2.3) + +**Implemented enhancements:** + +- Version 2.3 update [\#289](https://github.com/ImperialCollegeLondon/sharpy/pull/289) ([ben-l-p](https://github.com/ben-l-p)) +- Update develop branch with main [\#284](https://github.com/ImperialCollegeLondon/sharpy/pull/284) ([ben-l-p](https://github.com/ben-l-p)) +- Added pip install \(with docs\) [\#280](https://github.com/ImperialCollegeLondon/sharpy/pull/280) ([ben-l-p](https://github.com/ben-l-p)) +- Update beamplot.py to have stride option, consistent with aerogridplot.py [\#279](https://github.com/ImperialCollegeLondon/sharpy/pull/279) ([kccwing](https://github.com/kccwing)) + +**Fixed bugs:** + +- Fix Github Runner Docker build failing [\#285](https://github.com/ImperialCollegeLondon/sharpy/pull/285) ([ben-l-p](https://github.com/ben-l-p)) +- Add scipy version info to env yml [\#277](https://github.com/ImperialCollegeLondon/sharpy/pull/277) ([SJ-Innovation](https://github.com/SJ-Innovation)) + +**Closed issues:** + +- Scipy 1.12.0 Incompatible [\#276](https://github.com/ImperialCollegeLondon/sharpy/issues/276) +- BeamLoader postprocessor squishing answers [\#270](https://github.com/ImperialCollegeLondon/sharpy/issues/270) +- Solving Environment gets killed. [\#268](https://github.com/ImperialCollegeLondon/sharpy/issues/268) +- Error when running sharpy unittest: module scipy.sparse.\_sputils not found [\#227](https://github.com/ImperialCollegeLondon/sharpy/issues/227) +- Potential bug in /sharpy/structure/utils/modalutils.py [\#208](https://github.com/ImperialCollegeLondon/sharpy/issues/208) + +**Merged pull requests:** + +- Added ability to turn aligned grid off [\#288](https://github.com/ImperialCollegeLondon/sharpy/pull/288) ([ben-l-p](https://github.com/ben-l-p)) +- Update with main for mamba fixes [\#286](https://github.com/ImperialCollegeLondon/sharpy/pull/286) ([ben-l-p](https://github.com/ben-l-p)) +- Correct typos caught by Divya Sanghi [\#283](https://github.com/ImperialCollegeLondon/sharpy/pull/283) ([bbahiam](https://github.com/bbahiam)) +- Develop: Update environment.yml to fix scipy version issue [\#282](https://github.com/ImperialCollegeLondon/sharpy/pull/282) ([kccwing](https://github.com/kccwing)) +- Update noaero.py for consistency in function input [\#275](https://github.com/ImperialCollegeLondon/sharpy/pull/275) ([kccwing](https://github.com/kccwing)) +- A few minor bug fixes [\#273](https://github.com/ImperialCollegeLondon/sharpy/pull/273) ([sduess](https://github.com/sduess)) +- Update XBeam version to include compiler optimisation [\#272](https://github.com/ImperialCollegeLondon/sharpy/pull/272) ([ben-l-p](https://github.com/ben-l-p)) +- Update XBeam version to include compiler optimisation [\#271](https://github.com/ImperialCollegeLondon/sharpy/pull/271) ([ben-l-p](https://github.com/ben-l-p)) +- Improve docs and code of newmark\_ss [\#267](https://github.com/ImperialCollegeLondon/sharpy/pull/267) ([bbahiam](https://github.com/bbahiam)) +- Changed Github runner from Conda to Mamba [\#266](https://github.com/ImperialCollegeLondon/sharpy/pull/266) ([ben-l-p](https://github.com/ben-l-p)) +- Changed Github runner from Conda to Mamba [\#265](https://github.com/ImperialCollegeLondon/sharpy/pull/265) ([ben-l-p](https://github.com/ben-l-p)) +- Hotfix for documentation search [\#264](https://github.com/ImperialCollegeLondon/sharpy/pull/264) ([kccwing](https://github.com/kccwing)) +- Hotfix for documentation - develop [\#263](https://github.com/ImperialCollegeLondon/sharpy/pull/263) ([kccwing](https://github.com/kccwing)) +- Hotfix for documentation - main [\#262](https://github.com/ImperialCollegeLondon/sharpy/pull/262) ([kccwing](https://github.com/kccwing)) +- Merging v2.2 into develop [\#261](https://github.com/ImperialCollegeLondon/sharpy/pull/261) ([kccwing](https://github.com/kccwing)) + + ## [2.2](https://github.com/imperialcollegelondon/sharpy/tree/2.2) (2023-10-18) [Full Changelog](https://github.com/imperialcollegelondon/sharpy/compare/2.1...2.2) diff --git a/docs/source/content/installation.md b/docs/source/content/installation.md index 0f71abfb0..f3223f168 100644 --- a/docs/source/content/installation.md +++ b/docs/source/content/installation.md @@ -1,7 +1,7 @@ -# SHARPy v2.2 Installation Guide -__Last revision 26 February 2024__ +# SHARPy v2.3 Installation Guide +__Last revision 10 June 2024__ -The following step by step tutorial will guide you through the installation process of SHARPy. This is the updated process valid from v2.2. +The following step by step tutorial will guide you through the installation process of SHARPy. This is the updated process valid from v2.3. ## Requirements @@ -113,7 +113,17 @@ These are specified in an Anaconda environment that shall be activated prior to ``` This should take approximately 5 minutes to complete (Tested on Ubuntu 22.04.1). For installation on Apple Silicon, use ```environment_arm64.yml```; this requires GCC and GFortran to be installed prior. -5. Activate the `sharpy` conda environment: + Installation using Conda can be memory intensive, and will give the message ```Collecting package metadata (repodata.json): - Killed``` if all the available RAM is filled. From testing, 16GB of total system RAM is reliable for Conda install, whereas 8GB may have issues. Three solutions are available: + * Increase available RAM (if running on a compute cluster etc) + * Use [Mamba](https://mamba.readthedocs.io/en/latest/), a more efficient drop-in replacement for Conda + * Create a blank conda environment and install the required packages: + ```bash + conda create --name sharpy python=3.10 + conda config –add channels conda-forge + conda install eigen libopenblas libblas libcblas liblapack libgfortran libgcc libgfortran-ng + ``` + +6. Activate the `sharpy` conda environment: ```bash conda activate sharpy ``` @@ -293,6 +303,20 @@ python -m unittest **Enjoy!** +## Obtain SHARPy from PyPI (experimental!) + +You can obtain a built version of SHARPy, ic-sharpy, from PyPI [here](https://pypi.org/project/ic-sharpy/). + +To install at default directory use +``` +python3 -m pip install ic-sharpy +``` +To install at current directory use +``` +python3 -m pip install --prefix . ic-sharpy +``` +The source code can be found at `/lib/python3.10/site-packages/sharpy` and the executable at `/bin/sharpy`. + ## Running SHARPy ### Automated tests diff --git a/setup.py b/setup.py index 98124f297..034aa82be 100644 --- a/setup.py +++ b/setup.py @@ -103,7 +103,7 @@ def run(self): long_description = f.read() run() setup( - name="sharpy", + name="ic_sharpy", # due to the name sharpy being taken on pypi version=__version__, description="""SHARPy is a nonlinear aeroelastic analysis package developed at the Department of Aeronautics, Imperial College London. It can be used @@ -139,7 +139,7 @@ def run(self): "colorama", "dill", "jupyterlab", - "mayavi @ git+https://github.com/enthought/mayavi.git", #Used for TVTK. Bug in pip install, hence git clone + "mayavi", # github direct dependency removed since pip version is fixed, and also not compatible with pypi "pandas", "control", "openpyxl>=3.0.10", @@ -163,8 +163,11 @@ def run(self): ], }, classifiers=[ - "Operating System :: Linux, Mac OS", - "Programming Language :: Python, C++", + "Operating System :: MacOS", + "Operating System :: POSIX :: Linux", + "Programming Language :: Python :: 3.10", + "Programming Language :: Fortran", + "Programming Language :: C++" ], entry_points={ diff --git a/sharpy/postproc/aeroforcescalculator.py b/sharpy/postproc/aeroforcescalculator.py index cb6833ff3..ea9511a7d 100644 --- a/sharpy/postproc/aeroforcescalculator.py +++ b/sharpy/postproc/aeroforcescalculator.py @@ -63,6 +63,10 @@ class AeroForcesCalculator(BaseSolver): settings_default['c_ref'] = 1 settings_description['c_ref'] = 'Reference chord' + settings_types['u_inf_dir'] = 'list(float)' + settings_default['u_inf_dir'] = [1., 0., 0.] + settings_description['u_inf_dir'] = 'Flow direction' + settings_table = settings_utils.SettingsTable() __doc__ += settings_table.generate(settings_types, settings_default, settings_description) @@ -118,39 +122,58 @@ def run(self, **kwargs): if self.settings['write_text_file']: self.file_output(self.settings['text_file_name']) return self.data - + def calculate_forces(self, ts): - # Forces per surface in G frame - self.rot = algebra.quat2rotation(self.data.structure.timestep_info[ts].quat) + self.rot = algebra.quat2rotation(self.data.structure.timestep_info[ts].quat) # R_GA + + # flow rotation angle from x and z components of flow direction + # WARNING: this will give incorrect results when there is sideslip + rot_xy = np.arctan2(-self.settings['u_inf_dir'][2], self.settings['u_inf_dir'][0]) + rmat_xy = algebra.euler2rot((0., rot_xy, 0.)) + + # Forces per surface in A frame relative to the flow force = self.data.aero.timestep_info[ts].forces unsteady_force = self.data.aero.timestep_info[ts].dynamic_forces - for i_surf in range(self.data.aero.n_surf): + + n_surf = self.data.aero.n_surf + + rmat = np.block([[self.rot @ rmat_xy.T, np.zeros((3, 3))], [np.zeros((3, 3)), self.rot @ rmat_xy.T]]) + force_g = [np.moveaxis(np.squeeze(rmat @ np.expand_dims(np.moveaxis( + force[i], (0, 1, 2), (2, 0, 1)), -1)), source=(0, 1, 2), destination=(1, 2, 0)) + for i in range(n_surf)] + unsteady_force_g = [np.moveaxis(np.squeeze(rmat @ np.expand_dims(np.moveaxis( + unsteady_force[i], (0, 1, 2), (2, 0, 1)), -1)), source=(0, 1, 2), destination=(1, 2, 0)) + for i in range(n_surf)] + + for i_surf in range(n_surf): ( - self.data.aero.timestep_info[ts].inertial_steady_forces[i_surf, 0:3], - self.data.aero.timestep_info[ts].inertial_unsteady_forces[i_surf, 0:3], - self.data.aero.timestep_info[ts].body_steady_forces[i_surf, 0:3], - self.data.aero.timestep_info[ts].body_unsteady_forces[i_surf, 0:3] - ) = self.calculate_forces_for_isurf_in_g_frame(force[i_surf], unsteady_force=unsteady_force[i_surf]) - + self.data.aero.timestep_info[ts].inertial_steady_forces[i_surf, 0:3], + self.data.aero.timestep_info[ts].inertial_unsteady_forces[i_surf, 0:3], + self.data.aero.timestep_info[ts].body_steady_forces[i_surf, 0:3], + self.data.aero.timestep_info[ts].body_unsteady_forces[i_surf, 0:3] + ) = self.calculate_forces_for_isurf_in_g_frame(force_g[i_surf], unsteady_force=unsteady_force_g[i_surf]) + if self.settings["nonlifting_body"]: for i_surf in range(self.data.nonlifting_body.n_surf): ( - self.data.nonlifting_body.timestep_info[ts].inertial_steady_forces[i_surf, 0:3], - self.data.nonlifting_body.timestep_info[ts].body_steady_forces[i_surf, 0:3], - ) = self.calculate_forces_for_isurf_in_g_frame(self.data.nonlifting_body.timestep_info[ts].forces[i_surf], nonlifting=True) - + self.data.nonlifting_body.timestep_info[ts].inertial_steady_forces[i_surf, 0:3], + self.data.nonlifting_body.timestep_info[ts].body_steady_forces[i_surf, 0:3], + ) = self.calculate_forces_for_isurf_in_g_frame( + self.data.nonlifting_body.timestep_info[ts].forces[i_surf], nonlifting=True) + # Convert to forces in B frame try: steady_forces_b = self.data.structure.timestep_info[ts].postproc_node['aero_steady_forces'] except KeyError: if self.settings["nonlifting_body"]: - warnings.warn('Nonlifting forces are not considered in aero forces calculation since forces cannot not be retrieved from postproc node.') - steady_forces_b = self.map_forces_beam_dof(self.data.aero, ts, force) + warnings.warn( + 'Nonlifting forces are not considered in aero forces calculation since forces cannot not be retrieved from postproc node.') + steady_forces_b = self.map_forces_beam_dof(self.data.aero, ts, force_g) try: unsteady_forces_b = self.data.structure.timestep_info[ts].postproc_node['aero_unsteady_forces'] except KeyError: - unsteady_forces_b = self.map_forces_beam_dof(self.data.aero, ts, unsteady_force) + unsteady_forces_b = self.map_forces_beam_dof(self.data.aero, ts, unsteady_force_g) # Convert to forces in A frame steady_forces_a = self.data.structure.timestep_info[ts].nodal_b_for_2_a_for(steady_forces_b, self.data.structure) @@ -158,15 +181,14 @@ def calculate_forces(self, ts): unsteady_forces_a = self.data.structure.timestep_info[ts].nodal_b_for_2_a_for(unsteady_forces_b, self.data.structure) - # Express total forces in A frame self.data.aero.timestep_info[ts].total_steady_body_forces = \ - mapping.total_forces_moments(steady_forces_a, - self.data.structure.timestep_info[ts].pos, - ref_pos=self.moment_reference_location) + rmat @ mapping.total_forces_moments(steady_forces_a, + self.data.structure.timestep_info[ts].pos, + ref_pos=self.moment_reference_location) self.data.aero.timestep_info[ts].total_unsteady_body_forces = \ - mapping.total_forces_moments(unsteady_forces_a, - self.data.structure.timestep_info[ts].pos, - ref_pos=self.moment_reference_location) + rmat @ mapping.total_forces_moments(unsteady_forces_a, + self.data.structure.timestep_info[ts].pos, + ref_pos=self.moment_reference_location) # Express total forces in G frame self.data.aero.timestep_info[ts].total_steady_inertial_forces = \ @@ -179,7 +201,7 @@ def calculate_forces(self, ts): [np.zeros((3, 3)), self.rot]]).dot( self.data.aero.timestep_info[ts].total_unsteady_body_forces) - def calculate_forces_for_isurf_in_g_frame(self, force, unsteady_force = None, nonlifting = False): + def calculate_forces_for_isurf_in_g_frame(self, force, unsteady_force=None, nonlifting=False): """ Forces for a surface in G frame """ @@ -193,11 +215,11 @@ def calculate_forces_for_isurf_in_g_frame(self, force, unsteady_force = None, no if not nonlifting: total_unsteady_force += unsteady_force[0:3, i_m, i_n] if not nonlifting: - return total_steady_force, total_unsteady_force, np.dot(self.rot.T, total_steady_force), np.dot(self.rot.T, total_unsteady_force) + return total_steady_force, total_unsteady_force, np.dot(self.rot.T, total_steady_force), np.dot(self.rot.T, + total_unsteady_force) else: return total_steady_force, np.dot(self.rot.T, total_steady_force) - def map_forces_beam_dof(self, aero_data, ts, force): struct_tstep = self.data.structure.timestep_info[ts] aero_forces_beam_dof = mapping.aero2struct_force_mapping(force, @@ -212,19 +234,19 @@ def map_forces_beam_dof(self, aero_data, ts, force): def calculate_coefficients(self, fx, fy, fz, mx, my, mz): qS = self.settings['q_ref'] * self.settings['S_ref'] - return fx/qS, fy/qS, fz/qS, mx/qS/self.settings['b_ref'], my/qS/self.settings['c_ref'], \ - mz/qS/self.settings['b_ref'] + return fx / qS, fy / qS, fz / qS, mx / qS / self.settings['b_ref'], my / qS / self.settings['c_ref'], \ + mz / qS / self.settings['b_ref'] def screen_output(self, ts): # print time step total aero forces - forces = np.zeros(3) - moments = np.zeros(3) + forces = np.zeros(3) + moments = np.zeros(3) aero_tstep = self.data.aero.timestep_info[ts] forces += aero_tstep.total_steady_inertial_forces[:3] + aero_tstep.total_unsteady_inertial_forces[:3] moments += aero_tstep.total_steady_inertial_forces[3:] + aero_tstep.total_unsteady_inertial_forces[3:] - if self.settings['coefficients']: # TODO: Check if coefficients have to be computed differently for fuselages + if self.settings['coefficients']: # TODO: Check if coefficients have to be computed differently for fuselages Cfx, Cfy, Cfz, Cmx, Cmy, Cmz = self.calculate_coefficients(*forces, *moments) self.table.print_line([ts, Cfx, Cfy, Cfz, Cmx, Cmy, Cmz]) else: @@ -233,7 +255,7 @@ def screen_output(self, ts): def file_output(self, filename): # assemble forces/moments matrix # (1 timestep) + (3+3 inertial steady+unsteady) + (3+3 body steady+unsteady) - force_matrix = np.zeros((self.ts_max, 1 + 3 + 3 + 3 + 3 )) + force_matrix = np.zeros((self.ts_max, 1 + 3 + 3 + 3 + 3)) moment_matrix = np.zeros((self.ts_max, 1 + 3 + 3 + 3 + 3)) for ts in range(self.ts_max): aero_tstep = self.data.aero.timestep_info[ts] @@ -243,24 +265,23 @@ def file_output(self, filename): i += 1 # Steady forces/moments G - force_matrix[ts, i:i+3] = aero_tstep.total_steady_inertial_forces[:3] - moment_matrix[ts, i:i+3] = aero_tstep.total_steady_inertial_forces[3:] + force_matrix[ts, i:i + 3] = aero_tstep.total_steady_inertial_forces[:3] + moment_matrix[ts, i:i + 3] = aero_tstep.total_steady_inertial_forces[3:] i += 3 # Unsteady forces/moments G - force_matrix[ts, i:i+3] = aero_tstep.total_unsteady_inertial_forces[:3] - moment_matrix[ts, i:i+3] = aero_tstep.total_unsteady_inertial_forces[3:] + force_matrix[ts, i:i + 3] = aero_tstep.total_unsteady_inertial_forces[:3] + moment_matrix[ts, i:i + 3] = aero_tstep.total_unsteady_inertial_forces[3:] i += 3 # Steady forces/moments A - force_matrix[ts, i:i+3] = aero_tstep.total_steady_body_forces[:3] - moment_matrix[ts, i:i+3] = aero_tstep.total_steady_body_forces[3:] + force_matrix[ts, i:i + 3] = aero_tstep.total_steady_body_forces[:3] + moment_matrix[ts, i:i + 3] = aero_tstep.total_steady_body_forces[3:] i += 3 # Unsteady forces/moments A - force_matrix[ts, i:i+3] = aero_tstep.total_unsteady_body_forces[:3] - moment_matrix[ts, i:i+3] = aero_tstep.total_unsteady_body_forces[3:] - + force_matrix[ts, i:i + 3] = aero_tstep.total_unsteady_body_forces[:3] + moment_matrix[ts, i:i + 3] = aero_tstep.total_unsteady_body_forces[3:] header = '' header += 'tstep, ' diff --git a/sharpy/utils/datastructures.py b/sharpy/utils/datastructures.py index dbb569523..c734cfedc 100644 --- a/sharpy/utils/datastructures.py +++ b/sharpy/utils/datastructures.py @@ -431,6 +431,10 @@ class AeroTimeStepInfo(TimeStepInfo): ``[num_surf x chordwise panels x spanwise panels]`` dimensions_star (np.ndarray): Matrix defining the dimensions of the vortex grid on wakes ``[num_surf x streamwise panels x spanwise panels]`` + + Note, Ben Preston 27/09/24: forces and dynamic forces are stated to be in ``G`` however were actually + determined to be in ``A``. This issue may apply to other parameters, however errors due to this were only apparent + in the AeroForcesCalculator postprocessor. """ def __init__(self, dimensions, dimensions_star): super().__init__(dimensions) @@ -983,12 +987,6 @@ def change_to_global_AFoR(self, for0_pos, for0_vel, quat0): for ielem in range(self.psi.shape[0]): for inode in range(3): - # psi_slave = self.psi[ielem,inode,:] + np.zeros((3,),) - # self.psi[ielem, inode, :] = np.dot(Cms, self.psi[ielem, inode, :]) - # self.psi_dot[ielem, inode, :] = (np.dot(Cms, self.psi_dot[ielem, inode, :] + algebra.cross3(self.for_vel[3:6], psi_slave)) - - # algebra.multiply_matrices(CAmasterG, algebra.skew(self.for0_vel[3:6]), CGAslave, psi_slave)) - - self.psi_local[ielem, inode, :] = self.psi[ielem, inode, :].copy() # Copy here the result from the structural computation self.psi_dot_local[ielem, inode, :] = self.psi_dot[ielem, inode, :].copy() # Copy here the result from the structural computation diff --git a/sharpy/utils/generate_cases.py b/sharpy/utils/generate_cases.py index 60e32953c..e7c054015 100644 --- a/sharpy/utils/generate_cases.py +++ b/sharpy/utils/generate_cases.py @@ -590,7 +590,10 @@ def create_frame_of_reference_delta(self, y_BFoR='y_AFoR'): y_BFoR (string): Direction of the yB axis """ - if y_BFoR == 'x_AFoR': + if isinstance(y_BFoR,(list,np.ndarray)): + yB = np.asarray(y_BFoR) + cout.cout_wrap(("WARNING: custom FoR delta defined, using the given value: y_BFoR = {y_BFoR}" % (y_BFoR)), 3) + elif y_BFoR == 'x_AFoR': yB = np.array([1.0, 0.0, 0.0]) elif y_BFoR == 'y_AFoR': yB = np.array([0.0, 1.0, 0.0]) @@ -2036,12 +2039,19 @@ def generate_multibody_file(list_LagrangeConstraints, list_Bodies, route, case_n except: pass + try: constraint_id.create_dataset("aerogrid_warp_factor", data=getattr(constraint, "aerogrid_warp_factor")) except AttributeError: pass + try: + constraint_id.create_dataset("rot_axisA2", + data=getattr(constraint, "rot_axisA2")) + except: + pass + iconstraint += 1 # Write the body information diff --git a/tests/uvlm/static/polars/test_polars.py b/tests/uvlm/static/polars/test_polars.py index f78476938..44def2bc5 100644 --- a/tests/uvlm/static/polars/test_polars.py +++ b/tests/uvlm/static/polars/test_polars.py @@ -53,8 +53,8 @@ def test_infinite_wing(self): results = postprocess(output_route + '/' + case_header + '/') - results[:, 1:3] /= wing.force_coef(1.225, 1) - results[:, -1] /= wing.moment_coef(1.225, 1) + results[:, 1:3] /= wing.force_coef(1.225, 1.) + results[:, -1] /= wing.moment_coef(1.225, 1.) with self.subTest('lift'): cl_polar = np.interp(results[:, 0], self.polar_data[:, 0], self.polar_data[:, 1]) @@ -95,12 +95,13 @@ def process_case(path_to_case): case_name = path_to_case.split('/')[-1] pmor = configobj.ConfigObj(path_to_case + f'/{case_name}.pmor.sharpy') alpha = pmor['parameters']['alpha'] - inertial_forces = np.loadtxt(f'{path_to_case}/forces/forces_aeroforces.txt', - skiprows=1, delimiter=',', dtype=float)[1:4] - inertial_moments = np.loadtxt(f'{path_to_case}/forces/moments_aeroforces.txt', - skiprows=1, delimiter=',', dtype=float)[1:4] - return alpha, inertial_forces[2], inertial_forces[0], inertial_moments[1] + body_forces = np.loadtxt(f'{path_to_case}/forces/forces_aeroforces.txt', + skiprows=1, delimiter=',', dtype=float)[7:10] + body_moments = np.loadtxt(f'{path_to_case}/forces/moments_aeroforces.txt', + skiprows=1, delimiter=',', dtype=float)[7:10] + + return alpha, body_forces[2], body_forces[0], body_moments[1] class TestStab(unittest.TestCase):