├── .codecov.yml ├── .coveragerc ├── .github ├── ISSUE_TEMPLATE │ └── bug_report.md └── workflows │ ├── docker_build.yaml │ ├── docker_build_test.yaml │ ├── pypi_build.yaml │ ├── readme.md │ ├── sharpy_no_test_needed.yaml │ └── sharpy_tests.yaml ├── .github_changelog_generator ├── .gitignore ├── .gitmodules ├── .readthedocs.yaml ├── .version.json ├── .zenodo.json ├── CHANGELOG.md ├── CMakeLists.txt ├── CONTRIBUTING.md ├── Dockerfile ├── LICENSE ├── README.md ├── docs ├── .nojekyll ├── JOSS │ ├── codemeta.json │ ├── generate.rb │ ├── media │ │ └── pretty_pic_snapshots_thickerwake.jpeg │ ├── paper.bib │ └── paper.md ├── Makefile ├── docignore.yml ├── requirements_rtd └── source │ ├── _static │ ├── .placeholder │ ├── XHALE-render.jpg │ ├── capabilities │ │ ├── goland_flutter.png │ │ ├── goland_rom.png │ │ ├── hale_cruise.png │ │ ├── hale_turb.jpeg │ │ ├── sears.png │ │ ├── turbine.png │ │ └── xhale.png │ ├── case_files │ │ ├── connectivities.png │ │ ├── frame_of_reference_delta.jpg │ │ ├── frames_of_reference.jpg │ │ └── sharpy_modular.png │ ├── debugguide │ │ └── rubberduck.png │ ├── notebooks │ │ └── turbulence_no_legend.png │ └── sharpy_guide │ │ └── sharpy_intro.html │ ├── conf.py │ ├── content │ ├── capabilities.md │ ├── casefiles.rst │ ├── contributing.md │ ├── debug.rst │ ├── example_notebooks │ │ ├── UDP_control │ │ │ ├── control_design_script.m │ │ │ ├── get_settings_udp.py │ │ │ ├── matlab_functions │ │ │ │ ├── PID_linear_model.slx │ │ │ │ ├── adjust_state_space_system.m │ │ │ │ ├── get_1minuscosine_gust_input.m │ │ │ │ ├── read_SHARPy_state_space_system.m │ │ │ │ └── set_input_parameters.m │ │ │ ├── parameter_UDP_control_pazy_udp_closed_loop_gust_response.json │ │ │ ├── pazy_PID_controller_UDP.py │ │ │ ├── pazy_network_info.yml │ │ │ ├── pid_controller.py │ │ │ └── tutorial_udp_control.ipynb │ │ ├── cantilever │ │ │ ├── images │ │ │ │ └── cantilever.png │ │ │ ├── model_static_cantilever.py │ │ │ └── static_cantilever.ipynb │ │ ├── cantilever_wing.ipynb │ │ ├── images │ │ │ ├── simple_wing_scheme.png │ │ │ ├── t-tail_geometry.png │ │ │ ├── t-tail_properties.png │ │ │ ├── t-tail_solution.png │ │ │ └── turbulence_no_legend.png │ │ ├── linear_goland_flutter.ipynb │ │ ├── linear_horten.ipynb │ │ ├── nonlinear_t-tail_HALE.ipynb │ │ ├── source │ │ │ └── type04_db_nrel5mw_oc3_v06.xlsx │ │ └── wind_turbine.ipynb │ ├── examples.rst │ ├── faqs.md │ ├── installation.md │ ├── postproc.rst │ ├── publications.md │ ├── solvers.rst │ └── test_cases.rst │ ├── includes │ ├── aero │ │ ├── index.rst │ │ ├── models │ │ │ ├── aerogrid │ │ │ │ ├── AeroTimeStepInfo.rst │ │ │ │ ├── Aerogrid.rst │ │ │ │ ├── generate_strip.rst │ │ │ │ └── index.rst │ │ │ └── index.rst │ │ └── utils │ │ │ ├── airfoilpolars │ │ │ ├── Polar.rst │ │ │ └── index.rst │ │ │ ├── index.rst │ │ │ └── mapping │ │ │ ├── aero2struct_force_mapping.rst │ │ │ ├── index.rst │ │ │ └── total_forces_moments.rst │ ├── cases │ │ ├── coupled │ │ │ ├── X-HALE │ │ │ │ ├── generate_xhale │ │ │ │ │ ├── generate_naca_camber.rst │ │ │ │ │ ├── generate_solver_file.rst │ │ │ │ │ ├── index.rst │ │ │ │ │ └── read_beam_data.rst │ │ │ │ └── index.rst │ │ │ └── index.rst │ │ ├── hangar │ │ │ ├── horten_wing │ │ │ │ ├── HortenWing.rst │ │ │ │ └── index.rst │ │ │ ├── index.rst │ │ │ ├── richards_wing │ │ │ │ ├── HortenWing.rst │ │ │ │ └── index.rst │ │ │ └── swept_flying_wing │ │ │ │ ├── SweptWing.rst │ │ │ │ └── index.rst │ │ ├── index.rst │ │ └── templates │ │ │ ├── Ttail │ │ │ ├── Ttail_3beams.rst │ │ │ ├── Ttail_canonical.rst │ │ │ └── index.rst │ │ │ ├── flying_wings │ │ │ ├── FlyingWing.rst │ │ │ ├── Goland.rst │ │ │ ├── Pazy.rst │ │ │ ├── QuasiInfinite.rst │ │ │ ├── Smith.rst │ │ │ └── index.rst │ │ │ ├── index.rst │ │ │ └── template_wt │ │ │ ├── create_blade_coordinates.rst │ │ │ ├── create_node_radial_pos_from_elem_centres.rst │ │ │ ├── generate_from_excel_type03.rst │ │ │ ├── index.rst │ │ │ ├── rotor_from_excel_type03.rst │ │ │ └── spar_from_excel_type04.rst │ ├── controllers │ │ ├── controlsurfacepidcontroller │ │ │ ├── ControlSurfacePidController.rst │ │ │ └── index.rst │ │ ├── index.rst │ │ └── takeofftrajectorycontroller │ │ │ ├── TakeOffTrajectoryController.rst │ │ │ └── index.rst │ ├── generators │ │ ├── bumpvelocityfield │ │ │ ├── BumpVelocityField.rst │ │ │ └── index.rst │ │ ├── dynamiccontrolsurface │ │ │ ├── DynamicControlSurface.rst │ │ │ └── index.rst │ │ ├── floatingforces │ │ │ ├── FloatingForces.rst │ │ │ ├── change_of_to_sharpy.rst │ │ │ ├── compute_equiv_hd_added_mass.rst │ │ │ ├── compute_jacobian.rst │ │ │ ├── compute_xf_zf.rst │ │ │ ├── index.rst │ │ │ ├── jonswap_spectrum.rst │ │ │ ├── matrix_from_rf.rst │ │ │ ├── noise_freq_1s.rst │ │ │ ├── quasisteady_mooring.rst │ │ │ ├── rename_terms.rst │ │ │ ├── response_freq_dep_matrix.rst │ │ │ ├── rfval.rst │ │ │ ├── time_wave_forces.rst │ │ │ └── wave_radiation_damping.rst │ │ ├── gridbox │ │ │ ├── GridBox.rst │ │ │ └── index.rst │ │ ├── gustvelocityfield │ │ │ ├── DARPA.rst │ │ │ ├── GustVelocityField.rst │ │ │ ├── continuous_sin.rst │ │ │ ├── index.rst │ │ │ ├── lateral_one_minus_cos.rst │ │ │ ├── one_minus_cos.rst │ │ │ ├── span_sine.rst │ │ │ ├── time_varying.rst │ │ │ └── time_varying_global.rst │ │ ├── helicoidalwake │ │ │ ├── HelicoidalWake.rst │ │ │ └── index.rst │ │ ├── index.rst │ │ ├── modifystructure │ │ │ ├── ChangeLumpedMass.rst │ │ │ ├── ChangedVariable.rst │ │ │ ├── LumpedMassControl.rst │ │ │ ├── ModifyStructure.rst │ │ │ └── index.rst │ │ ├── polaraeroforces │ │ │ ├── EfficiencyCorrection.rst │ │ │ ├── PolarCorrection.rst │ │ │ ├── get_aoacl0_from_camber.rst │ │ │ ├── index.rst │ │ │ ├── local_stability_axes.rst │ │ │ ├── magnitude_and_direction_of_relative_velocity.rst │ │ │ └── span_chord.rst │ │ ├── shearvelocityfield │ │ │ ├── ShearVelocityField.rst │ │ │ └── index.rst │ │ ├── steadyvelocityfield │ │ │ ├── SteadyVelocityField.rst │ │ │ └── index.rst │ │ ├── straightwake │ │ │ ├── StraightWake.rst │ │ │ └── index.rst │ │ ├── trajectorygenerator │ │ │ ├── TrajectoryGenerator.rst │ │ │ └── index.rst │ │ ├── turbvelocityfield │ │ │ ├── TurbVelocityField.rst │ │ │ └── index.rst │ │ └── turbvelocityfieldbts │ │ │ ├── TurbVelocityFieldBts.rst │ │ │ └── index.rst │ ├── index.rst │ ├── io │ │ ├── index.rst │ │ ├── inout_variables │ │ │ ├── SetOfVariables.rst │ │ │ └── index.rst │ │ └── network_interface │ │ │ ├── InNetwork.rst │ │ │ ├── Network.rst │ │ │ ├── NetworkLoader.rst │ │ │ ├── OutNetwork.rst │ │ │ └── index.rst │ ├── linear │ │ ├── assembler │ │ │ ├── index.rst │ │ │ ├── lincontrolsurfacedeflector │ │ │ │ ├── LinControlSurfaceDeflector.rst │ │ │ │ ├── der_R_arbitrary_axis_times_v.rst │ │ │ │ └── index.rst │ │ │ ├── linearaeroelastic │ │ │ │ ├── LinearAeroelastic.rst │ │ │ │ └── index.rst │ │ │ ├── linearbeam │ │ │ │ ├── LinearBeam.rst │ │ │ │ └── index.rst │ │ │ ├── lineargustassembler │ │ │ │ ├── LeadingEdge.rst │ │ │ │ ├── MultiLeadingEdge.rst │ │ │ │ ├── campbell.rst │ │ │ │ ├── gust_from_string.rst │ │ │ │ ├── index.rst │ │ │ │ └── spanwise_interpolation.rst │ │ │ └── linearuvlm │ │ │ │ ├── LinearUVLM.rst │ │ │ │ └── index.rst │ │ ├── index.rst │ │ └── src │ │ │ ├── assembly │ │ │ ├── AICs.rst │ │ │ ├── dfqsdgamma_vrel0.rst │ │ │ ├── dfqsduinput.rst │ │ │ ├── dfqsdvind_gamma.rst │ │ │ ├── dfqsdvind_zeta.rst │ │ │ ├── dfqsdzeta_omega.rst │ │ │ ├── dfqsdzeta_vrel0.rst │ │ │ ├── dfunstdgamma_dot.rst │ │ │ ├── dvinddzeta.rst │ │ │ ├── dvinddzeta_cpp.rst │ │ │ ├── eval_panel_cpp.rst │ │ │ ├── index.rst │ │ │ ├── nc_domegazetadzeta.rst │ │ │ ├── nc_dqcdzeta.rst │ │ │ ├── nc_dqcdzeta_Sin_to_Sout.rst │ │ │ ├── test_wake_prop_term.rst │ │ │ ├── uc_dncdzeta.rst │ │ │ ├── wake_prop.rst │ │ │ └── wake_prop_from_dimensions.rst │ │ │ ├── gridmapping │ │ │ ├── AeroGridMap.rst │ │ │ └── index.rst │ │ │ ├── index.rst │ │ │ ├── interp │ │ │ ├── get_Wnv_vector.rst │ │ │ ├── get_Wvc_scalar.rst │ │ │ ├── get_panel_wcv.rst │ │ │ └── index.rst │ │ │ ├── lib_dbiot │ │ │ ├── Dvcross_by_skew3d.rst │ │ │ ├── eval_panel_comp.rst │ │ │ ├── eval_panel_cpp.rst │ │ │ ├── eval_panel_exp.rst │ │ │ ├── eval_panel_fast.rst │ │ │ ├── eval_panel_fast_coll.rst │ │ │ ├── eval_seg_comp_loop.rst │ │ │ ├── eval_seg_exp.rst │ │ │ ├── eval_seg_exp_loop.rst │ │ │ └── index.rst │ │ │ ├── lib_ucdncdzeta │ │ │ ├── eval.rst │ │ │ └── index.rst │ │ │ ├── libfit │ │ │ ├── fitfrd.rst │ │ │ ├── get_rfa_res.rst │ │ │ ├── get_rfa_res_norm.rst │ │ │ ├── index.rst │ │ │ ├── poly_fit.rst │ │ │ ├── rfa.rst │ │ │ ├── rfa_fit_dev.rst │ │ │ ├── rfa_mimo.rst │ │ │ └── rfader.rst │ │ │ ├── libsparse │ │ │ ├── block_dot.rst │ │ │ ├── block_matrix_dot_vector.rst │ │ │ ├── block_sum.rst │ │ │ ├── csc_matrix.rst │ │ │ ├── dense.rst │ │ │ ├── dot.rst │ │ │ ├── eye_as.rst │ │ │ ├── index.rst │ │ │ ├── solve.rst │ │ │ └── zeros_as.rst │ │ │ ├── libss │ │ │ ├── Hnorm_from_freq_resp.rst │ │ │ ├── SSconv.rst │ │ │ ├── SSderivative.rst │ │ │ ├── SSintegr.rst │ │ │ ├── StateSpace.rst │ │ │ ├── addGain.rst │ │ │ ├── adjust_phase.rst │ │ │ ├── build_SS_poly.rst │ │ │ ├── butter.rst │ │ │ ├── compare_ss.rst │ │ │ ├── couple.rst │ │ │ ├── disc2cont.rst │ │ │ ├── eigvals.rst │ │ │ ├── freqresp.rst │ │ │ ├── get_freq_from_eigs.rst │ │ │ ├── index.rst │ │ │ ├── join.rst │ │ │ ├── join2.rst │ │ │ ├── parallel.rst │ │ │ ├── project.rst │ │ │ ├── random_ss.rst │ │ │ ├── retain_inout_channels.rst │ │ │ ├── scale_SS.rst │ │ │ ├── series.rst │ │ │ ├── simulate.rst │ │ │ ├── ss_block.rst │ │ │ ├── ss_to_scipy.rst │ │ │ └── sum_ss.rst │ │ │ ├── lin_aeroelastic │ │ │ ├── LinAeroEla.rst │ │ │ └── index.rst │ │ │ ├── lin_utils │ │ │ ├── Info.rst │ │ │ ├── comp_tot_force.rst │ │ │ ├── extract_from_data.rst │ │ │ ├── index.rst │ │ │ └── solve_linear.rst │ │ │ ├── lingebm │ │ │ ├── FlexDynamic.rst │ │ │ ├── index.rst │ │ │ ├── newmark_ss.rst │ │ │ └── sort_eigvals.rst │ │ │ ├── linuvlm │ │ │ ├── Dynamic.rst │ │ │ ├── DynamicBlock.rst │ │ │ ├── Frequency.rst │ │ │ ├── Static.rst │ │ │ ├── get_Cw_cpx.rst │ │ │ └── index.rst │ │ │ ├── multisurfaces │ │ │ ├── MultiAeroGridSurfaces.rst │ │ │ └── index.rst │ │ │ └── surface │ │ │ ├── AeroGridGeo.rst │ │ │ ├── AeroGridSurface.rst │ │ │ ├── get_aic3_cpp.rst │ │ │ └── index.rst │ ├── postprocs │ │ ├── AeroForcesCalculator.rst │ │ ├── AerogridPlot.rst │ │ ├── AsymptoticStability.rst │ │ ├── BeamLoads.rst │ │ ├── BeamPlot.rst │ │ ├── Cleanup.rst │ │ ├── FrequencyResponse.rst │ │ ├── LiftDistribution.rst │ │ ├── PickleData.rst │ │ ├── PlotFlowField.rst │ │ ├── SaveData.rst │ │ ├── SaveParametricCase.rst │ │ ├── StabilityDerivatives.rst │ │ ├── StallCheck.rst │ │ ├── UDPout.rst │ │ └── WriteVariablesTime.rst │ ├── rom │ │ ├── balanced │ │ │ ├── Balanced.rst │ │ │ ├── Direct.rst │ │ │ ├── FrequencyLimited.rst │ │ │ ├── Iterative.rst │ │ │ └── index.rst │ │ ├── index.rst │ │ ├── krylov │ │ │ ├── Krylov.rst │ │ │ └── index.rst │ │ └── utils │ │ │ ├── index.rst │ │ │ ├── krylovutils │ │ │ ├── check_eye.rst │ │ │ ├── construct_krylov.rst │ │ │ ├── evec.rst │ │ │ ├── index.rst │ │ │ ├── lu_factor.rst │ │ │ ├── lu_solve.rst │ │ │ ├── mgs_ortho.rst │ │ │ ├── remove_a12.rst │ │ │ └── schur_ordered.rst │ │ │ ├── librom │ │ │ ├── balfreq.rst │ │ │ ├── balreal_direct_py.rst │ │ │ ├── balreal_iter.rst │ │ │ ├── balreal_iter_old.rst │ │ │ ├── check_stability.rst │ │ │ ├── eigen_dec.rst │ │ │ ├── get_gauss_weights.rst │ │ │ ├── get_trapz_weights.rst │ │ │ ├── index.rst │ │ │ ├── low_rank_smith.rst │ │ │ ├── modred.rst │ │ │ ├── res_discrete_lyap.rst │ │ │ ├── smith_iter.rst │ │ │ └── tune_rom.rst │ │ │ └── librom_interp │ │ │ ├── FLB_transfer_function.rst │ │ │ ├── InterpROM.rst │ │ │ ├── index.rst │ │ │ └── transfer_function.rst │ ├── solvers │ │ ├── aero │ │ │ ├── DynamicUVLM.rst │ │ │ ├── NoAero.rst │ │ │ ├── PrescribedUvlm.rst │ │ │ ├── StaticUvlm.rst │ │ │ ├── StepLinearUVLM.rst │ │ │ └── StepUvlm.rst │ │ ├── aero_solvers.rst │ │ ├── coupled │ │ │ ├── DynamicCoupled.rst │ │ │ ├── LinDynamicSim.rst │ │ │ ├── StaticCoupled.rst │ │ │ └── StaticCoupledRBM.rst │ │ ├── coupled_solvers.rst │ │ ├── flight dynamics │ │ │ ├── StaticTrim.rst │ │ │ └── Trim.rst │ │ ├── flight dynamics_solvers.rst │ │ ├── linear │ │ │ ├── LinearAssembler.rst │ │ │ └── Modal.rst │ │ ├── linear_solvers.rst │ │ ├── loader │ │ │ ├── AerogridLoader.rst │ │ │ ├── BeamLoader.rst │ │ │ └── PreSharpy.rst │ │ ├── loader_solvers.rst │ │ ├── structural │ │ │ ├── NonLinearDynamic.rst │ │ │ ├── NonLinearDynamicCoupledStep.rst │ │ │ ├── NonLinearDynamicMultibody.rst │ │ │ ├── NonLinearDynamicPrescribedStep.rst │ │ │ ├── NonLinearStatic.rst │ │ │ ├── RigidDynamicCoupledStep.rst │ │ │ └── RigidDynamicPrescribedStep.rst │ │ ├── structural_solvers.rst │ │ ├── time_integrator │ │ │ ├── GeneralisedAlpha.rst │ │ │ └── NewmarkBeta.rst │ │ └── time_integrator_solvers.rst │ ├── structure │ │ ├── index.rst │ │ ├── models │ │ │ ├── beam │ │ │ │ ├── StructTimeStepInfo.rst │ │ │ │ └── index.rst │ │ │ ├── beamstructures │ │ │ │ ├── Element.rst │ │ │ │ └── index.rst │ │ │ └── index.rst │ │ └── utils │ │ │ ├── index.rst │ │ │ ├── lagrangeconstraints │ │ │ ├── BaseLagrangeConstraint.rst │ │ │ ├── constant_rot_vel_FoR.rst │ │ │ ├── constant_vel_FoR.rst │ │ │ ├── def_rot_axis_FoR_wrt_node_general.rst │ │ │ ├── def_rot_axis_FoR_wrt_node_xyz.rst │ │ │ ├── def_rot_vect_FoR_wrt_node.rst │ │ │ ├── def_rot_vel_FoR_wrt_node.rst │ │ │ ├── define_FoR_dof.rst │ │ │ ├── define_node_dof.rst │ │ │ ├── define_num_LM_eq.rst │ │ │ ├── equal_lin_vel_node_FoR.rst │ │ │ ├── equal_pos_node_FoR.rst │ │ │ ├── free.rst │ │ │ ├── fully_constrained_node_FoR.rst │ │ │ ├── generate_lagrange_matrix.rst │ │ │ ├── hinge_FoR.rst │ │ │ ├── hinge_FoR_wrtG.rst │ │ │ ├── hinge_node_FoR.rst │ │ │ ├── hinge_node_FoR_constant_vel.rst │ │ │ ├── index.rst │ │ │ ├── initialise_lc.rst │ │ │ ├── lagrangeconstraint.rst │ │ │ ├── lc_from_string.rst │ │ │ ├── lin_vel_node_wrtA.rst │ │ │ ├── lin_vel_node_wrtG.rst │ │ │ ├── postprocess.rst │ │ │ ├── print_available_lc.rst │ │ │ ├── remove_constraint.rst │ │ │ ├── spherical_FoR.rst │ │ │ └── spherical_node_FoR.rst │ │ │ ├── modalutils │ │ │ ├── assert_modes_mass_normalised.rst │ │ │ ├── assert_orthogonal_eigenvectors.rst │ │ │ ├── free_modes_principal_axes.rst │ │ │ ├── get_mode_zeta.rst │ │ │ ├── index.rst │ │ │ ├── mode_sign_convention.rst │ │ │ ├── modes_to_cg_ref.rst │ │ │ ├── principal_axes_inertia.rst │ │ │ ├── scale_mass_normalised_modes.rst │ │ │ ├── scale_mode.rst │ │ │ ├── write_modes_vtk.rst │ │ │ └── write_zeta_vtk.rst │ │ │ └── xbeamlib │ │ │ ├── Xbopts.rst │ │ │ ├── cbeam3_asbly_dynamic.rst │ │ │ ├── cbeam3_asbly_static.rst │ │ │ ├── cbeam3_correct_gravity_forces.rst │ │ │ ├── cbeam3_loads.rst │ │ │ ├── cbeam3_solv_modal.rst │ │ │ ├── cbeam3_solv_nlnstatic.rst │ │ │ ├── index.rst │ │ │ └── xbeam3_asbly_dynamic.rst │ └── utils │ │ ├── algebra │ │ ├── cross3.rst │ │ ├── crv2quat.rst │ │ ├── crv2rotation.rst │ │ ├── crv2tan.rst │ │ ├── crv_bounds.rst │ │ ├── der_CcrvT_by_v.rst │ │ ├── der_Ccrv_by_v.rst │ │ ├── der_Ceuler_by_v.rst │ │ ├── der_Ceuler_by_v_NED.rst │ │ ├── der_CquatT_by_v.rst │ │ ├── der_Cquat_by_v.rst │ │ ├── der_Peuler_by_v.rst │ │ ├── der_TanT_by_xv.rst │ │ ├── der_Tan_by_xv.rst │ │ ├── der_Teuler_by_w.rst │ │ ├── der_Teuler_by_w_NED.rst │ │ ├── der_quat_wrt_crv.rst │ │ ├── der_skewp_skewp_v.rst │ │ ├── deuler_dt.rst │ │ ├── deuler_dt_NED.rst │ │ ├── euler2quat.rst │ │ ├── euler2rot.rst │ │ ├── get_transformation_matrix.rst │ │ ├── get_triad.rst │ │ ├── index.rst │ │ ├── mat2quat.rst │ │ ├── multiply_matrices.rst │ │ ├── norm3d.rst │ │ ├── normsq3d.rst │ │ ├── panel_area.rst │ │ ├── quadskew.rst │ │ ├── quat2euler.rst │ │ ├── quat2rotation.rst │ │ ├── quat_bound.rst │ │ ├── rotation2crv.rst │ │ ├── rotation2quat.rst │ │ ├── rotation3d_x.rst │ │ ├── rotation3d_y.rst │ │ ├── rotation3d_z.rst │ │ ├── skew.rst │ │ ├── tangent_vector.rst │ │ ├── triad2rotation.rst │ │ └── unit_vector.rst │ │ ├── analytical │ │ ├── flat_plate_analytical.rst │ │ ├── garrick_drag_pitch.rst │ │ ├── garrick_drag_plunge.rst │ │ ├── index.rst │ │ ├── nc_derivs.rst │ │ ├── qs_derivs.rst │ │ ├── sears_CL_freq_resp.rst │ │ ├── sears_fun.rst │ │ ├── sears_lift_sin_gust.rst │ │ ├── theo_CL_freq_resp.rst │ │ ├── theo_CM_freq_resp.rst │ │ ├── theo_fun.rst │ │ ├── theo_lift.rst │ │ └── wagner_imp_start.rst │ │ ├── control_utils │ │ ├── PID.rst │ │ └── index.rst │ │ ├── datastructures │ │ ├── AeroTimeStepInfo.rst │ │ ├── Linear.rst │ │ ├── LinearTimeStepInfo.rst │ │ ├── StructTimeStepInfo.rst │ │ └── index.rst │ │ ├── docutils │ │ ├── check_folder_in_ignore.rst │ │ ├── generate_documentation.rst │ │ ├── index.rst │ │ ├── output_documentation_module_page.rst │ │ ├── write_file.rst │ │ └── write_folder.rst │ │ ├── exceptions │ │ ├── DocumentationError.rst │ │ ├── NotConvergedSolver.rst │ │ ├── NotRecognisedSetting.rst │ │ ├── NotValidSetting.rst │ │ └── index.rst │ │ ├── frequencyutils │ │ ├── find_limits.rst │ │ ├── find_target_system.rst │ │ ├── freqresp_relative_error.rst │ │ ├── frobenius_norm.rst │ │ ├── h_infinity_norm.rst │ │ ├── hamiltonian.rst │ │ ├── index.rst │ │ ├── l2norm.rst │ │ └── max_eigs.rst │ │ ├── generate_cases │ │ ├── AerodynamicInformation.rst │ │ ├── AeroelasticInformation.rst │ │ ├── SimulationInformation.rst │ │ ├── StructuralInformation.rst │ │ ├── clean_test_files.rst │ │ ├── from_node_array_to_elem_matrix.rst │ │ ├── from_node_list_to_elem_matrix.rst │ │ ├── get_airfoil_camber.rst │ │ ├── get_aoacl0_from_camber.rst │ │ ├── get_factor_geometric_progression.rst │ │ ├── get_mu0_from_camber.rst │ │ ├── index.rst │ │ └── read_column_sheet_type01.rst │ │ ├── generator_interface │ │ ├── index.rst │ │ └── output_documentation.rst │ │ ├── geo_utils │ │ ├── generate_naca_camber.rst │ │ ├── index.rst │ │ └── interpolate_naca_camber.rst │ │ ├── h5utils │ │ ├── add_array_to_grp.rst │ │ ├── add_as_grp.rst │ │ ├── check_file_exists.rst │ │ ├── index.rst │ │ ├── read_group.rst │ │ ├── readh5.rst │ │ ├── save_list_as_array.rst │ │ └── saveh5.rst │ │ ├── index.rst │ │ ├── model_utils │ │ ├── index.rst │ │ └── mass_matrix_generator.rst │ │ ├── multibody │ │ ├── disp_and_accel2state.rst │ │ ├── get_elems_nodes_list.rst │ │ ├── index.rst │ │ ├── merge_multibody.rst │ │ ├── split_multibody.rst │ │ ├── state2disp_and_accel.rst │ │ └── update_mb_dB_before_merge.rst │ │ ├── plotutils │ │ ├── index.rst │ │ ├── plot_timestep.rst │ │ └── set_axes_equal.rst │ │ └── settings │ │ ├── SettingsTable.rst │ │ ├── check_settings_in_options.rst │ │ ├── index.rst │ │ └── load_config_file.rst │ └── index.rst ├── environment.yml ├── environment_arm64.yml ├── lib ├── .placeholder └── CMakeLists.txt ├── pyproject.toml ├── scripts ├── __init__.py ├── optimiser │ ├── __init__.py │ ├── base_case │ │ └── generate.py │ ├── optimiser.py │ └── optimiser_input.yaml └── xplaneUDPout │ ├── HALE_varDIe.acf │ ├── __init__.py │ ├── variables.yaml │ └── xplaneUDP.py ├── setup.py ├── sharpy ├── __init__.py ├── aero │ ├── __init__.py │ ├── models │ │ ├── __init__.py │ │ ├── aerogrid.py │ │ ├── grid.py │ │ └── nonliftingbodygrid.py │ └── utils │ │ ├── __init__.py │ │ ├── airfoilpolars.py │ │ ├── mapping.py │ │ ├── utils.py │ │ └── uvlmlib.py ├── cases │ ├── __init__.py │ ├── coupled │ │ ├── WindTurbine │ │ │ ├── __init__.py │ │ │ └── generate_rotor.py │ │ ├── X-HALE │ │ │ ├── generate_xhale.py │ │ │ └── inputs │ │ │ │ ├── EMX-07_camber.txt │ │ │ │ ├── aero_properties.xlsx │ │ │ │ ├── beam_properties.xlsx │ │ │ │ └── lumped_mass.xlsx │ │ ├── __init__.py │ │ ├── hinged_controlled_wing │ │ │ ├── __init__.py │ │ │ ├── generate_hinged_controlled_wing.py │ │ │ └── generate_hinged_roll_controlled_wing.py │ │ ├── linear_horten │ │ │ └── __init__.py │ │ ├── multibody_takeoff │ │ │ ├── __init__.py │ │ │ └── generate_hale.py │ │ └── simple_HALE │ │ │ ├── __init__.py │ │ │ └── generate_hale.py │ ├── hangar │ │ ├── __init__.py │ │ ├── horten_wing.py │ │ ├── richards_wing.py │ │ └── swept_flying_wing.py │ └── templates │ │ ├── Ttail.py │ │ ├── __init__.py │ │ ├── flying_wings.py │ │ ├── fuselage_wing_configuration │ │ ├── __init__.py │ │ ├── fuselage_wing_configuration.py │ │ ├── fwc_aero.py │ │ ├── fwc_fuselage.py │ │ ├── fwc_get_settings.py │ │ └── fwc_structure.py │ │ └── template_wt.py ├── controllers │ ├── __init__.py │ ├── bladepitchpid.py │ ├── controlsurfacepidcontroller.py │ ├── multibodycontroller.py │ └── takeofftrajectorycontroller.py ├── generators │ ├── __init__.py │ ├── bumpvelocityfield.py │ ├── dynamiccontrolsurface.py │ ├── floatingforces.py │ ├── gridbox.py │ ├── gustvelocityfield.py │ ├── helicoidalwake.py │ ├── modifystructure.py │ ├── polaraeroforces.py │ ├── shearvelocityfield.py │ ├── steadyvelocityfield.py │ ├── straightwake.py │ ├── trajectorygenerator.py │ ├── turbvelocityfield.py │ └── turbvelocityfieldbts.py ├── io │ ├── __init__.py │ ├── inout_variables.py │ ├── logger_utils.py │ ├── message_interface.py │ └── network_interface.py ├── linear │ ├── __init__.py │ ├── assembler │ │ ├── __init__.py │ │ ├── lincontrolsurfacedeflector.py │ │ ├── linearaeroelastic.py │ │ ├── linearbeam.py │ │ ├── linearcustom.py │ │ ├── lineargustassembler.py │ │ └── linearuvlm.py │ ├── dev │ │ ├── __init__.py │ │ ├── linfunc.py │ │ ├── linsym_biot_segment.py │ │ ├── linsym_uc_dncdzeta.py │ │ └── sym_dev_dbiot.py │ ├── src │ │ ├── __init__.py │ │ ├── assembly.py │ │ ├── gridmapping.py │ │ ├── interp.py │ │ ├── lib_dbiot.py │ │ ├── lib_ucdncdzeta.py │ │ ├── libfit.py │ │ ├── libsparse.py │ │ ├── libss.py │ │ ├── lin_aeroelastic.py │ │ ├── lin_utils.py │ │ ├── lingebm.py │ │ ├── linuvlm.py │ │ ├── multisurfaces.py │ │ ├── surface.py │ │ └── uvlmutils.py │ └── utils │ │ ├── __init__.py │ │ ├── derivatives.py │ │ ├── ss_interface.py │ │ └── sselements.py ├── postproc │ ├── __init__.py │ ├── aeroforcescalculator.py │ ├── aerogridplot.py │ ├── asymptoticstability.py │ ├── beamloads.py │ ├── beamplot.py │ ├── cleanup.py │ ├── frequencyresponse.py │ ├── liftdistribution.py │ ├── pickledata.py │ ├── plotflowfield.py │ ├── savedata.py │ ├── saveparametriccase.py │ ├── stabilityderivatives.py │ ├── stallcheck.py │ ├── udpout.py │ └── writevariablestime.py ├── presharpy │ ├── __init__.py │ └── presharpy.py ├── rom │ ├── __init__.py │ ├── balanced.py │ ├── krylov.py │ └── utils │ │ ├── __init__.py │ │ ├── krylovutils.py │ │ ├── librom.py │ │ └── librom_interp.py ├── sharpy_main.py ├── solvers │ ├── __init__.py │ ├── _basestructural.py │ ├── aerogridloader.py │ ├── beamloader.py │ ├── dynamiccoupled.py │ ├── dynamicuvlm.py │ ├── gridloader.py │ ├── initialaeroelasticloader.py │ ├── lindynamicsim.py │ ├── linearassembler.py │ ├── modal.py │ ├── noaero.py │ ├── nonliftingbodygridloader.py │ ├── nonlineardynamic.py │ ├── nonlineardynamiccoupledstep.py │ ├── nonlineardynamicmultibody.py │ ├── nonlineardynamicmultibodyjax.py │ ├── nonlineardynamicprescribedstep.py │ ├── nonlinearstatic.py │ ├── nostructural.py │ ├── prescribeduvlm.py │ ├── rigiddynamiccoupledstep.py │ ├── rigiddynamicprescribedstep.py │ ├── staticcoupled.py │ ├── statictrim.py │ ├── staticuvlm.py │ ├── steplinearuvlm.py │ ├── stepuvlm.py │ ├── timeintegrators.py │ ├── timeintegratorsjax.py │ ├── trim.py │ └── updatepickle.py ├── structure │ ├── __init__.py │ ├── basestructure.py │ ├── models │ │ ├── __init__.py │ │ ├── beam.py │ │ └── beamstructures.py │ └── utils │ │ ├── __init__.py │ │ ├── lagrangeconstraints.py │ │ ├── lagrangeconstraintsjax.py │ │ ├── modalutils.py │ │ └── xbeamlib.py ├── utils │ ├── __init__.py │ ├── algebra.py │ ├── analytical.py │ ├── constants.py │ ├── control_utils.py │ ├── controller_interface.py │ ├── cout_utils.py │ ├── ctypes_utils.py │ ├── datastructures.py │ ├── docutils.py │ ├── exceptions.py │ ├── frequencyutils.py │ ├── generate_cases.py │ ├── generator_interface.py │ ├── geo_utils.py │ ├── h5utils.py │ ├── input_arg.py │ ├── linearutils.py │ ├── model_utils.py │ ├── multibody.py │ ├── multibodyjax.py │ ├── num_utils.py │ ├── plotutils.py │ ├── rom_interface.py │ ├── settings.py │ ├── sharpydir.py │ └── solver_interface.py └── version.py ├── tests ├── __init__.py ├── coupled │ ├── __init__.py │ ├── dynamic │ │ ├── __init__.py │ │ ├── hale │ │ │ └── generate_hale.py │ │ └── test_dynamic.py │ ├── multibody │ │ ├── __init__.py │ │ ├── double_pendulum │ │ │ ├── __init__.py │ │ │ └── test_double_pendulum_geradin.py │ │ ├── double_prescribed_pendulum │ │ │ └── test_double_prescribed_pendulum.py │ │ ├── double_slanted_pendulum │ │ │ ├── __init__.py │ │ │ └── test_double_pendulum_slanted.py │ │ ├── fix_node_velocity_wrtA │ │ │ ├── __init__.py │ │ │ └── test_fix_node_velocity_wrtA.py │ │ ├── fix_node_velocity_wrtG │ │ │ ├── __init__.py │ │ │ └── test_fix_node_velocity_wrtG.py │ │ ├── floating_forces │ │ │ ├── MooringLineFD.dat │ │ │ └── test_floatingforces.py │ │ └── floating_wind_turbine │ │ │ ├── oc3_cs_v07.floating.h5 │ │ │ └── test_floating_wind_turbine.py │ ├── prescribed │ │ ├── WindTurbine │ │ │ ├── __init__.py │ │ │ └── test_rotor.py │ │ ├── __init__.py │ │ ├── gamma_dot_test │ │ │ └── test_gamma_dot.py │ │ ├── rotating_wing │ │ │ └── generate_rotating_wing.py │ │ └── test_prescribed.py │ └── static │ │ ├── __init__.py │ │ ├── pazy │ │ └── generate_pazy.py │ │ ├── smith_g_2deg │ │ ├── __init__.py │ │ └── generate_smith_g_2deg.py │ │ ├── smith_g_4deg │ │ ├── __init__.py │ │ └── generate_smith_g_4deg.py │ │ ├── smith_nog_2deg │ │ ├── __init__.py │ │ └── generate_smith_nog_2deg.py │ │ ├── smith_nog_4deg │ │ ├── __init__.py │ │ └── generate_smith_nog_4deg.py │ │ ├── test_pazy_static.py │ │ └── test_static.py ├── docs │ ├── __init__.py │ └── test_docs.py ├── io │ ├── Example_simple_hale │ │ ├── Client_HALE.py │ │ ├── __init__.py │ │ ├── generate_hale_io.py │ │ └── variables_hale.yaml │ ├── __init__.py │ ├── generate_pazy_udpout.py │ ├── sample_udp_inout │ │ ├── __init__.py │ │ ├── client.py │ │ ├── generate_pazy_test_io_local.py │ │ └── variables_coarse.yaml │ ├── test_pazy_udpout.py │ └── variables.yaml ├── linear │ ├── __init__.py │ ├── assembly │ │ ├── __init__.py │ │ ├── h5input │ │ │ ├── goland_mod_Nsurf01_M003_N004_a040.aero_state.h5 │ │ │ └── goland_mod_Nsurf02_M003_N004_a040.aero_state.h5 │ │ └── test_assembly.py │ ├── control_surfaces │ │ ├── __init__.py │ │ └── test_control_surfaces.py │ ├── derivatives │ │ ├── __init__.py │ │ ├── test_ders.py │ │ └── test_stabilityderivatives.py │ ├── frequencyutils │ │ ├── __init__.py │ │ ├── src │ │ │ ├── a.npy │ │ │ ├── b.npy │ │ │ ├── c.npy │ │ │ └── d.npy │ │ └── test_frequency_utils.py │ ├── goland_wing │ │ ├── __init__.py │ │ └── test_goland_flutter.py │ ├── gusts │ │ ├── __init__.py │ │ ├── test_external_gust.py │ │ └── test_linear_gusts.py │ ├── horten │ │ ├── __init__.py │ │ └── test_horten.py │ ├── rom │ │ ├── __init__.py │ │ ├── src │ │ │ ├── A.mat │ │ │ ├── B.mat │ │ │ ├── C.mat │ │ │ └── schur_A.dat │ │ ├── test_balancing.py │ │ ├── test_krylov.py │ │ ├── test_rom_framework.py │ │ ├── test_schur.py │ │ └── test_springmasssystem.py │ ├── statespace │ │ ├── __init__.py │ │ ├── test_statespace.py │ │ └── test_variable_tracker.py │ └── uvlm │ │ ├── __init__.py │ │ └── test_infinite_span.py ├── sourcepanelmethod │ ├── __init__.py │ ├── geometry_parameter_models.json │ ├── test_data │ │ ├── results_low_wing_coupled_0.csv │ │ └── results_low_wing_coupled_1.csv │ ├── test_source_panel_method.py │ └── test_vlm_coupled_spm.py ├── utils │ ├── __init__.py │ ├── test_algebra.py │ ├── test_generate_cases.py │ └── test_settings.py ├── uvlm │ ├── __init__.py │ ├── dynamic │ │ └── test_wake_cfl_n1.py │ └── static │ │ ├── __init__.py │ │ ├── big_wake_planarwing │ │ └── generate_big_wake_planarwing.py │ │ ├── planarwing │ │ ├── __init__.py │ │ └── generate_planarwing.py │ │ └── polars │ │ ├── __init__.py │ │ ├── generate_wing.py │ │ ├── test_polars.py │ │ └── xf-naca0018-il-50000.txt └── xbeam │ ├── __init__.py │ ├── geradin │ ├── __init__.py │ └── generate_geradin.py │ ├── modal │ └── rotating_beam │ │ └── generate_bielawa_baromega2_1e3.py │ └── test_xbeam.py └── utils ├── docker └── bashrc └── environment.yml /.codecov.yml: -------------------------------------------------------------------------------- 1 | ignore: 2 | - '*/tests/*' 3 | -------------------------------------------------------------------------------- /.coveragerc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.coveragerc -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/bug_report.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.github/ISSUE_TEMPLATE/bug_report.md -------------------------------------------------------------------------------- /.github/workflows/docker_build.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.github/workflows/docker_build.yaml -------------------------------------------------------------------------------- /.github/workflows/docker_build_test.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.github/workflows/docker_build_test.yaml -------------------------------------------------------------------------------- /.github/workflows/pypi_build.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.github/workflows/pypi_build.yaml -------------------------------------------------------------------------------- /.github/workflows/readme.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.github/workflows/readme.md -------------------------------------------------------------------------------- /.github/workflows/sharpy_no_test_needed.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.github/workflows/sharpy_no_test_needed.yaml -------------------------------------------------------------------------------- /.github/workflows/sharpy_tests.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.github/workflows/sharpy_tests.yaml -------------------------------------------------------------------------------- /.github_changelog_generator: -------------------------------------------------------------------------------- 1 | since-tag=1.0.0 -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.gitignore -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.gitmodules -------------------------------------------------------------------------------- /.readthedocs.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.readthedocs.yaml -------------------------------------------------------------------------------- /.version.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.version.json -------------------------------------------------------------------------------- /.zenodo.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/.zenodo.json -------------------------------------------------------------------------------- /CHANGELOG.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/CHANGELOG.md -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/CMakeLists.txt -------------------------------------------------------------------------------- /CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | docs/source/content/contributing.md -------------------------------------------------------------------------------- /Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/Dockerfile -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/LICENSE -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/README.md -------------------------------------------------------------------------------- /docs/.nojekyll: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /docs/JOSS/codemeta.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/JOSS/codemeta.json -------------------------------------------------------------------------------- /docs/JOSS/generate.rb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/JOSS/generate.rb -------------------------------------------------------------------------------- /docs/JOSS/media/pretty_pic_snapshots_thickerwake.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/JOSS/media/pretty_pic_snapshots_thickerwake.jpeg -------------------------------------------------------------------------------- /docs/JOSS/paper.bib: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/JOSS/paper.bib -------------------------------------------------------------------------------- /docs/JOSS/paper.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/JOSS/paper.md -------------------------------------------------------------------------------- /docs/Makefile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/Makefile -------------------------------------------------------------------------------- /docs/docignore.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/docignore.yml -------------------------------------------------------------------------------- /docs/requirements_rtd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/requirements_rtd -------------------------------------------------------------------------------- /docs/source/_static/.placeholder: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /docs/source/_static/XHALE-render.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/XHALE-render.jpg -------------------------------------------------------------------------------- /docs/source/_static/capabilities/goland_flutter.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/capabilities/goland_flutter.png -------------------------------------------------------------------------------- /docs/source/_static/capabilities/goland_rom.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/capabilities/goland_rom.png -------------------------------------------------------------------------------- /docs/source/_static/capabilities/hale_cruise.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/capabilities/hale_cruise.png -------------------------------------------------------------------------------- /docs/source/_static/capabilities/hale_turb.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/capabilities/hale_turb.jpeg -------------------------------------------------------------------------------- /docs/source/_static/capabilities/sears.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/capabilities/sears.png -------------------------------------------------------------------------------- /docs/source/_static/capabilities/turbine.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/capabilities/turbine.png -------------------------------------------------------------------------------- /docs/source/_static/capabilities/xhale.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/capabilities/xhale.png -------------------------------------------------------------------------------- /docs/source/_static/case_files/connectivities.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/case_files/connectivities.png -------------------------------------------------------------------------------- /docs/source/_static/case_files/frame_of_reference_delta.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/case_files/frame_of_reference_delta.jpg -------------------------------------------------------------------------------- /docs/source/_static/case_files/frames_of_reference.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/case_files/frames_of_reference.jpg -------------------------------------------------------------------------------- /docs/source/_static/case_files/sharpy_modular.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/case_files/sharpy_modular.png -------------------------------------------------------------------------------- /docs/source/_static/debugguide/rubberduck.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/debugguide/rubberduck.png -------------------------------------------------------------------------------- /docs/source/_static/notebooks/turbulence_no_legend.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/notebooks/turbulence_no_legend.png -------------------------------------------------------------------------------- /docs/source/_static/sharpy_guide/sharpy_intro.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/_static/sharpy_guide/sharpy_intro.html -------------------------------------------------------------------------------- /docs/source/conf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/conf.py -------------------------------------------------------------------------------- /docs/source/content/capabilities.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/capabilities.md -------------------------------------------------------------------------------- /docs/source/content/casefiles.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/casefiles.rst -------------------------------------------------------------------------------- /docs/source/content/contributing.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/contributing.md -------------------------------------------------------------------------------- /docs/source/content/debug.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/debug.rst -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/UDP_control/pid_controller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/UDP_control/pid_controller.py -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/cantilever_wing.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/cantilever_wing.ipynb -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/images/simple_wing_scheme.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/images/simple_wing_scheme.png -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/images/t-tail_geometry.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/images/t-tail_geometry.png -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/images/t-tail_properties.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/images/t-tail_properties.png -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/images/t-tail_solution.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/images/t-tail_solution.png -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/linear_goland_flutter.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/linear_goland_flutter.ipynb -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/linear_horten.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/linear_horten.ipynb -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/nonlinear_t-tail_HALE.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/nonlinear_t-tail_HALE.ipynb -------------------------------------------------------------------------------- /docs/source/content/example_notebooks/wind_turbine.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/example_notebooks/wind_turbine.ipynb -------------------------------------------------------------------------------- /docs/source/content/examples.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/examples.rst -------------------------------------------------------------------------------- /docs/source/content/faqs.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/faqs.md -------------------------------------------------------------------------------- /docs/source/content/installation.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/installation.md -------------------------------------------------------------------------------- /docs/source/content/postproc.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/postproc.rst -------------------------------------------------------------------------------- /docs/source/content/publications.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/publications.md -------------------------------------------------------------------------------- /docs/source/content/solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/solvers.rst -------------------------------------------------------------------------------- /docs/source/content/test_cases.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/content/test_cases.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/index.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/models/aerogrid/AeroTimeStepInfo.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/models/aerogrid/AeroTimeStepInfo.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/models/aerogrid/Aerogrid.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/models/aerogrid/Aerogrid.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/models/aerogrid/generate_strip.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/models/aerogrid/generate_strip.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/models/aerogrid/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/models/aerogrid/index.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/models/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/models/index.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/utils/airfoilpolars/Polar.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/utils/airfoilpolars/Polar.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/utils/airfoilpolars/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./Polar 5 | -------------------------------------------------------------------------------- /docs/source/includes/aero/utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/utils/mapping/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/utils/mapping/index.rst -------------------------------------------------------------------------------- /docs/source/includes/aero/utils/mapping/total_forces_moments.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/aero/utils/mapping/total_forces_moments.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/coupled/X-HALE/generate_xhale/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/coupled/X-HALE/generate_xhale/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/coupled/X-HALE/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/coupled/X-HALE/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/coupled/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/coupled/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/hangar/horten_wing/HortenWing.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/hangar/horten_wing/HortenWing.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/hangar/horten_wing/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/hangar/horten_wing/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/hangar/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/hangar/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/hangar/richards_wing/HortenWing.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/hangar/richards_wing/HortenWing.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/hangar/richards_wing/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/hangar/richards_wing/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/hangar/swept_flying_wing/SweptWing.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/hangar/swept_flying_wing/SweptWing.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/hangar/swept_flying_wing/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/hangar/swept_flying_wing/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/Ttail/Ttail_3beams.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/Ttail/Ttail_3beams.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/Ttail/Ttail_canonical.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/Ttail/Ttail_canonical.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/Ttail/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/Ttail/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/flying_wings/FlyingWing.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/flying_wings/FlyingWing.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/flying_wings/Goland.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/flying_wings/Goland.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/flying_wings/Pazy.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/flying_wings/Pazy.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/flying_wings/QuasiInfinite.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/flying_wings/QuasiInfinite.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/flying_wings/Smith.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/flying_wings/Smith.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/flying_wings/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/flying_wings/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/index.rst -------------------------------------------------------------------------------- /docs/source/includes/cases/templates/template_wt/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/cases/templates/template_wt/index.rst -------------------------------------------------------------------------------- /docs/source/includes/controllers/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/controllers/index.rst -------------------------------------------------------------------------------- /docs/source/includes/controllers/takeofftrajectorycontroller/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./TakeOffTrajectoryController 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/bumpvelocityfield/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./BumpVelocityField 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/dynamiccontrolsurface/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./DynamicControlSurface 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/FloatingForces.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/FloatingForces.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/compute_jacobian.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/compute_jacobian.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/compute_xf_zf.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/compute_xf_zf.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/index.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/jonswap_spectrum.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/jonswap_spectrum.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/matrix_from_rf.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/matrix_from_rf.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/noise_freq_1s.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/noise_freq_1s.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/rename_terms.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/rename_terms.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/rfval.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/rfval.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/floatingforces/time_wave_forces.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/floatingforces/time_wave_forces.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/gridbox/GridBox.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/gridbox/GridBox.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/gridbox/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./GridBox 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/gustvelocityfield/DARPA.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/gustvelocityfield/DARPA.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/gustvelocityfield/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/gustvelocityfield/index.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/gustvelocityfield/one_minus_cos.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/gustvelocityfield/one_minus_cos.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/gustvelocityfield/span_sine.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/gustvelocityfield/span_sine.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/gustvelocityfield/time_varying.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/gustvelocityfield/time_varying.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/helicoidalwake/HelicoidalWake.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/helicoidalwake/HelicoidalWake.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/helicoidalwake/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./HelicoidalWake 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/index.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/modifystructure/ChangedVariable.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/modifystructure/ChangedVariable.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/modifystructure/ModifyStructure.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/modifystructure/ModifyStructure.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/modifystructure/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/modifystructure/index.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/polaraeroforces/PolarCorrection.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/polaraeroforces/PolarCorrection.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/polaraeroforces/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/polaraeroforces/index.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/polaraeroforces/span_chord.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/polaraeroforces/span_chord.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/shearvelocityfield/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./ShearVelocityField 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/steadyvelocityfield/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./SteadyVelocityField 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/straightwake/StraightWake.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/generators/straightwake/StraightWake.rst -------------------------------------------------------------------------------- /docs/source/includes/generators/straightwake/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./StraightWake 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/trajectorygenerator/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./TrajectoryGenerator 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/turbvelocityfield/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./TurbVelocityField 5 | -------------------------------------------------------------------------------- /docs/source/includes/generators/turbvelocityfieldbts/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./TurbVelocityFieldBts 5 | -------------------------------------------------------------------------------- /docs/source/includes/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/index.rst -------------------------------------------------------------------------------- /docs/source/includes/io/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/io/index.rst -------------------------------------------------------------------------------- /docs/source/includes/io/inout_variables/SetOfVariables.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/io/inout_variables/SetOfVariables.rst -------------------------------------------------------------------------------- /docs/source/includes/io/inout_variables/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./SetOfVariables 5 | -------------------------------------------------------------------------------- /docs/source/includes/io/network_interface/InNetwork.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/io/network_interface/InNetwork.rst -------------------------------------------------------------------------------- /docs/source/includes/io/network_interface/Network.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/io/network_interface/Network.rst -------------------------------------------------------------------------------- /docs/source/includes/io/network_interface/NetworkLoader.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/io/network_interface/NetworkLoader.rst -------------------------------------------------------------------------------- /docs/source/includes/io/network_interface/OutNetwork.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/io/network_interface/OutNetwork.rst -------------------------------------------------------------------------------- /docs/source/includes/io/network_interface/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/io/network_interface/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/assembler/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/assembler/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/assembler/linearaeroelastic/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./LinearAeroelastic 5 | -------------------------------------------------------------------------------- /docs/source/includes/linear/assembler/linearbeam/LinearBeam.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/assembler/linearbeam/LinearBeam.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/assembler/linearbeam/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/assembler/linearbeam/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/assembler/lineargustassembler/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/assembler/lineargustassembler/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/assembler/linearuvlm/LinearUVLM.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/assembler/linearuvlm/LinearUVLM.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/assembler/linearuvlm/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/assembler/linearuvlm/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/AICs.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/AICs.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dfqsdgamma_vrel0.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dfqsdgamma_vrel0.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dfqsduinput.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dfqsduinput.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dfqsdvind_gamma.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dfqsdvind_gamma.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dfqsdvind_zeta.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dfqsdvind_zeta.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dfqsdzeta_omega.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dfqsdzeta_omega.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dfqsdzeta_vrel0.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dfqsdzeta_vrel0.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dfunstdgamma_dot.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dfunstdgamma_dot.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dvinddzeta.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dvinddzeta.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/dvinddzeta_cpp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/dvinddzeta_cpp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/eval_panel_cpp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/eval_panel_cpp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/nc_domegazetadzeta.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/nc_domegazetadzeta.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/nc_dqcdzeta.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/nc_dqcdzeta.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/test_wake_prop_term.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/test_wake_prop_term.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/uc_dncdzeta.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/uc_dncdzeta.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/assembly/wake_prop.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/assembly/wake_prop.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/gridmapping/AeroGridMap.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/gridmapping/AeroGridMap.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/gridmapping/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/gridmapping/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/interp/get_Wnv_vector.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/interp/get_Wnv_vector.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/interp/get_Wvc_scalar.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/interp/get_Wvc_scalar.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/interp/get_panel_wcv.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/interp/get_panel_wcv.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/interp/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/interp/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/Dvcross_by_skew3d.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/Dvcross_by_skew3d.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_panel_comp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_panel_comp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_panel_cpp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_panel_cpp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_panel_exp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_panel_exp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_panel_fast.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_panel_fast.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_panel_fast_coll.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_panel_fast_coll.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_seg_comp_loop.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_seg_comp_loop.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_seg_exp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_seg_exp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/eval_seg_exp_loop.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/eval_seg_exp_loop.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_dbiot/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_dbiot/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_ucdncdzeta/eval.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_ucdncdzeta/eval.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lib_ucdncdzeta/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lib_ucdncdzeta/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/fitfrd.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/fitfrd.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/get_rfa_res.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/get_rfa_res.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/get_rfa_res_norm.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/get_rfa_res_norm.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/poly_fit.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/poly_fit.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/rfa.rst: -------------------------------------------------------------------------------- 1 | rfa 2 | --- 3 | 4 | .. automodule:: sharpy.linear.src.libfit.rfa -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/rfa_fit_dev.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/rfa_fit_dev.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/rfa_mimo.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/rfa_mimo.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libfit/rfader.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libfit/rfader.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/block_dot.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/block_dot.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/block_sum.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/block_sum.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/csc_matrix.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/csc_matrix.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/dense.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/dense.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/dot.rst: -------------------------------------------------------------------------------- 1 | dot 2 | --- 3 | 4 | .. automodule:: sharpy.linear.src.libsparse.dot -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/eye_as.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/eye_as.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/solve.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/solve.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libsparse/zeros_as.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libsparse/zeros_as.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/Hnorm_from_freq_resp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/Hnorm_from_freq_resp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/SSconv.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/SSconv.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/SSderivative.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/SSderivative.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/SSintegr.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/SSintegr.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/StateSpace.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/StateSpace.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/addGain.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/addGain.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/adjust_phase.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/adjust_phase.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/build_SS_poly.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/build_SS_poly.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/butter.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/butter.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/compare_ss.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/compare_ss.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/couple.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/couple.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/disc2cont.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/disc2cont.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/eigvals.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/eigvals.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/freqresp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/freqresp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/get_freq_from_eigs.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/get_freq_from_eigs.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/join.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/join.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/join2.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/join2.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/parallel.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/parallel.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/project.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/project.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/random_ss.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/random_ss.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/retain_inout_channels.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/retain_inout_channels.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/scale_SS.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/scale_SS.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/series.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/series.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/simulate.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/simulate.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/ss_block.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/ss_block.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/ss_to_scipy.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/ss_to_scipy.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/libss/sum_ss.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/libss/sum_ss.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lin_aeroelastic/LinAeroEla.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lin_aeroelastic/LinAeroEla.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lin_aeroelastic/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lin_aeroelastic/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lin_utils/Info.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lin_utils/Info.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lin_utils/comp_tot_force.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lin_utils/comp_tot_force.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lin_utils/extract_from_data.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lin_utils/extract_from_data.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lin_utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lin_utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lin_utils/solve_linear.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lin_utils/solve_linear.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lingebm/FlexDynamic.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lingebm/FlexDynamic.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lingebm/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lingebm/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lingebm/newmark_ss.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lingebm/newmark_ss.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/lingebm/sort_eigvals.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/lingebm/sort_eigvals.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/linuvlm/Dynamic.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/linuvlm/Dynamic.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/linuvlm/DynamicBlock.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/linuvlm/DynamicBlock.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/linuvlm/Frequency.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/linuvlm/Frequency.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/linuvlm/Static.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/linuvlm/Static.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/linuvlm/get_Cw_cpx.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/linuvlm/get_Cw_cpx.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/linuvlm/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/linuvlm/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/multisurfaces/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/multisurfaces/index.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/surface/AeroGridGeo.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/surface/AeroGridGeo.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/surface/AeroGridSurface.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/surface/AeroGridSurface.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/surface/get_aic3_cpp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/surface/get_aic3_cpp.rst -------------------------------------------------------------------------------- /docs/source/includes/linear/src/surface/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/linear/src/surface/index.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/AeroForcesCalculator.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/AeroForcesCalculator.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/AerogridPlot.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/AerogridPlot.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/AsymptoticStability.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/AsymptoticStability.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/BeamLoads.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/BeamLoads.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/BeamPlot.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/BeamPlot.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/Cleanup.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/Cleanup.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/FrequencyResponse.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/FrequencyResponse.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/LiftDistribution.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/LiftDistribution.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/PickleData.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/PickleData.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/PlotFlowField.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/PlotFlowField.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/SaveData.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/SaveData.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/SaveParametricCase.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/SaveParametricCase.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/StabilityDerivatives.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/StabilityDerivatives.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/StallCheck.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/StallCheck.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/UDPout.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/UDPout.rst -------------------------------------------------------------------------------- /docs/source/includes/postprocs/WriteVariablesTime.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/postprocs/WriteVariablesTime.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/balanced/Balanced.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/balanced/Balanced.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/balanced/Direct.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/balanced/Direct.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/balanced/FrequencyLimited.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/balanced/FrequencyLimited.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/balanced/Iterative.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/balanced/Iterative.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/balanced/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/balanced/index.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/index.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/krylov/Krylov.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/krylov/Krylov.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/krylov/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/krylov/index.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/check_eye.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/check_eye.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/construct_krylov.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/construct_krylov.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/evec.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/evec.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/lu_factor.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/lu_factor.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/lu_solve.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/lu_solve.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/mgs_ortho.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/mgs_ortho.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/remove_a12.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/remove_a12.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/krylovutils/schur_ordered.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/krylovutils/schur_ordered.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/balfreq.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/balfreq.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/balreal_direct_py.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/balreal_direct_py.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/balreal_iter.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/balreal_iter.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/balreal_iter_old.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/balreal_iter_old.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/check_stability.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/check_stability.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/eigen_dec.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/eigen_dec.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/get_gauss_weights.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/get_gauss_weights.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/get_trapz_weights.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/get_trapz_weights.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/index.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/low_rank_smith.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/low_rank_smith.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/modred.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/modred.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/res_discrete_lyap.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/res_discrete_lyap.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/smith_iter.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/smith_iter.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom/tune_rom.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom/tune_rom.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom_interp/InterpROM.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom_interp/InterpROM.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom_interp/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom_interp/index.rst -------------------------------------------------------------------------------- /docs/source/includes/rom/utils/librom_interp/transfer_function.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/rom/utils/librom_interp/transfer_function.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/aero/DynamicUVLM.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/aero/DynamicUVLM.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/aero/NoAero.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/aero/NoAero.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/aero/PrescribedUvlm.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/aero/PrescribedUvlm.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/aero/StaticUvlm.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/aero/StaticUvlm.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/aero/StepLinearUVLM.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/aero/StepLinearUVLM.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/aero/StepUvlm.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/aero/StepUvlm.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/aero_solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/aero_solvers.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/coupled/DynamicCoupled.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/coupled/DynamicCoupled.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/coupled/LinDynamicSim.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/coupled/LinDynamicSim.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/coupled/StaticCoupled.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/coupled/StaticCoupled.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/coupled/StaticCoupledRBM.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/coupled/StaticCoupledRBM.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/coupled_solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/coupled_solvers.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/flight dynamics/StaticTrim.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/flight dynamics/StaticTrim.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/flight dynamics/Trim.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/flight dynamics/Trim.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/flight dynamics_solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/flight dynamics_solvers.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/linear/LinearAssembler.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/linear/LinearAssembler.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/linear/Modal.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/linear/Modal.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/linear_solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/linear_solvers.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/loader/AerogridLoader.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/loader/AerogridLoader.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/loader/BeamLoader.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/loader/BeamLoader.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/loader/PreSharpy.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/loader/PreSharpy.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/loader_solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/loader_solvers.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/structural/NonLinearDynamic.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/structural/NonLinearDynamic.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/structural/NonLinearStatic.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/structural/NonLinearStatic.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/structural/RigidDynamicCoupledStep.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/structural/RigidDynamicCoupledStep.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/structural_solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/structural_solvers.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/time_integrator/GeneralisedAlpha.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/time_integrator/GeneralisedAlpha.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/time_integrator/NewmarkBeta.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/time_integrator/NewmarkBeta.rst -------------------------------------------------------------------------------- /docs/source/includes/solvers/time_integrator_solvers.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/solvers/time_integrator_solvers.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/index.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/models/beam/StructTimeStepInfo.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/models/beam/StructTimeStepInfo.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/models/beam/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./StructTimeStepInfo 5 | -------------------------------------------------------------------------------- /docs/source/includes/structure/models/beamstructures/Element.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/models/beamstructures/Element.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/models/beamstructures/index.rst: -------------------------------------------------------------------------------- 1 | .. toctree:: 2 | :glob: 3 | 4 | ./Element 5 | -------------------------------------------------------------------------------- /docs/source/includes/structure/models/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/models/index.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/lagrangeconstraints/free.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/lagrangeconstraints/free.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/lagrangeconstraints/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/lagrangeconstraints/index.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/modalutils/get_mode_zeta.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/modalutils/get_mode_zeta.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/modalutils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/modalutils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/modalutils/modes_to_cg_ref.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/modalutils/modes_to_cg_ref.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/modalutils/scale_mode.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/modalutils/scale_mode.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/modalutils/write_modes_vtk.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/modalutils/write_modes_vtk.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/modalutils/write_zeta_vtk.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/modalutils/write_zeta_vtk.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/xbeamlib/Xbopts.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/xbeamlib/Xbopts.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/xbeamlib/cbeam3_loads.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/xbeamlib/cbeam3_loads.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/xbeamlib/cbeam3_solv_modal.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/xbeamlib/cbeam3_solv_modal.rst -------------------------------------------------------------------------------- /docs/source/includes/structure/utils/xbeamlib/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/structure/utils/xbeamlib/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/cross3.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/cross3.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/crv2quat.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/crv2quat.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/crv2rotation.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/crv2rotation.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/crv2tan.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/crv2tan.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/crv_bounds.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/crv_bounds.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_CcrvT_by_v.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_CcrvT_by_v.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Ccrv_by_v.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Ccrv_by_v.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Ceuler_by_v.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Ceuler_by_v.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Ceuler_by_v_NED.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Ceuler_by_v_NED.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_CquatT_by_v.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_CquatT_by_v.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Cquat_by_v.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Cquat_by_v.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Peuler_by_v.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Peuler_by_v.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_TanT_by_xv.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_TanT_by_xv.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Tan_by_xv.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Tan_by_xv.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Teuler_by_w.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Teuler_by_w.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_Teuler_by_w_NED.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_Teuler_by_w_NED.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_quat_wrt_crv.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_quat_wrt_crv.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/der_skewp_skewp_v.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/der_skewp_skewp_v.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/deuler_dt.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/deuler_dt.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/deuler_dt_NED.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/deuler_dt_NED.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/euler2quat.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/euler2quat.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/euler2rot.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/euler2rot.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/get_transformation_matrix.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/get_transformation_matrix.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/get_triad.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/get_triad.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/mat2quat.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/mat2quat.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/multiply_matrices.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/multiply_matrices.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/norm3d.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/norm3d.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/normsq3d.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/normsq3d.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/panel_area.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/panel_area.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/quadskew.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/quadskew.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/quat2euler.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/quat2euler.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/quat2rotation.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/quat2rotation.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/quat_bound.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/quat_bound.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/rotation2crv.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/rotation2crv.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/rotation2quat.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/rotation2quat.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/rotation3d_x.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/rotation3d_x.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/rotation3d_y.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/rotation3d_y.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/rotation3d_z.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/rotation3d_z.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/skew.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/skew.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/tangent_vector.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/tangent_vector.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/triad2rotation.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/triad2rotation.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/algebra/unit_vector.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/algebra/unit_vector.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/flat_plate_analytical.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/flat_plate_analytical.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/garrick_drag_pitch.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/garrick_drag_pitch.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/garrick_drag_plunge.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/garrick_drag_plunge.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/nc_derivs.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/nc_derivs.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/qs_derivs.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/qs_derivs.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/sears_CL_freq_resp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/sears_CL_freq_resp.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/sears_fun.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/sears_fun.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/sears_lift_sin_gust.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/sears_lift_sin_gust.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/theo_CL_freq_resp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/theo_CL_freq_resp.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/theo_CM_freq_resp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/theo_CM_freq_resp.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/theo_fun.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/theo_fun.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/theo_lift.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/theo_lift.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/analytical/wagner_imp_start.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/analytical/wagner_imp_start.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/control_utils/PID.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/control_utils/PID.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/control_utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/control_utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/datastructures/AeroTimeStepInfo.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/datastructures/AeroTimeStepInfo.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/datastructures/Linear.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/datastructures/Linear.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/datastructures/LinearTimeStepInfo.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/datastructures/LinearTimeStepInfo.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/datastructures/StructTimeStepInfo.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/datastructures/StructTimeStepInfo.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/datastructures/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/datastructures/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/docutils/check_folder_in_ignore.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/docutils/check_folder_in_ignore.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/docutils/generate_documentation.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/docutils/generate_documentation.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/docutils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/docutils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/docutils/write_file.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/docutils/write_file.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/docutils/write_folder.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/docutils/write_folder.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/exceptions/DocumentationError.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/exceptions/DocumentationError.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/exceptions/NotConvergedSolver.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/exceptions/NotConvergedSolver.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/exceptions/NotRecognisedSetting.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/exceptions/NotRecognisedSetting.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/exceptions/NotValidSetting.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/exceptions/NotValidSetting.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/exceptions/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/exceptions/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/find_limits.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/find_limits.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/find_target_system.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/find_target_system.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/frobenius_norm.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/frobenius_norm.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/h_infinity_norm.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/h_infinity_norm.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/hamiltonian.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/hamiltonian.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/l2norm.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/l2norm.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/frequencyutils/max_eigs.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/frequencyutils/max_eigs.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/generate_cases/SimulationInformation.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/generate_cases/SimulationInformation.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/generate_cases/StructuralInformation.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/generate_cases/StructuralInformation.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/generate_cases/clean_test_files.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/generate_cases/clean_test_files.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/generate_cases/get_airfoil_camber.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/generate_cases/get_airfoil_camber.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/generate_cases/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/generate_cases/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/generator_interface/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/generator_interface/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/geo_utils/generate_naca_camber.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/geo_utils/generate_naca_camber.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/geo_utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/geo_utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/geo_utils/interpolate_naca_camber.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/geo_utils/interpolate_naca_camber.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/add_array_to_grp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/add_array_to_grp.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/add_as_grp.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/add_as_grp.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/check_file_exists.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/check_file_exists.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/read_group.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/read_group.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/readh5.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/readh5.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/save_list_as_array.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/save_list_as_array.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/h5utils/saveh5.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/h5utils/saveh5.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/model_utils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/model_utils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/model_utils/mass_matrix_generator.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/model_utils/mass_matrix_generator.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/multibody/disp_and_accel2state.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/multibody/disp_and_accel2state.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/multibody/get_elems_nodes_list.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/multibody/get_elems_nodes_list.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/multibody/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/multibody/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/multibody/merge_multibody.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/multibody/merge_multibody.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/multibody/split_multibody.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/multibody/split_multibody.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/multibody/state2disp_and_accel.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/multibody/state2disp_and_accel.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/plotutils/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/plotutils/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/plotutils/plot_timestep.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/plotutils/plot_timestep.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/plotutils/set_axes_equal.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/plotutils/set_axes_equal.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/settings/SettingsTable.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/settings/SettingsTable.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/settings/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/settings/index.rst -------------------------------------------------------------------------------- /docs/source/includes/utils/settings/load_config_file.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/includes/utils/settings/load_config_file.rst -------------------------------------------------------------------------------- /docs/source/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/docs/source/index.rst -------------------------------------------------------------------------------- /environment.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/environment.yml -------------------------------------------------------------------------------- /environment_arm64.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/environment_arm64.yml -------------------------------------------------------------------------------- /lib/.placeholder: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /lib/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/lib/CMakeLists.txt -------------------------------------------------------------------------------- /pyproject.toml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/pyproject.toml -------------------------------------------------------------------------------- /scripts/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /scripts/optimiser/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /scripts/optimiser/base_case/generate.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/scripts/optimiser/base_case/generate.py -------------------------------------------------------------------------------- /scripts/optimiser/optimiser.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/scripts/optimiser/optimiser.py -------------------------------------------------------------------------------- /scripts/optimiser/optimiser_input.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/scripts/optimiser/optimiser_input.yaml -------------------------------------------------------------------------------- /scripts/xplaneUDPout/HALE_varDIe.acf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/scripts/xplaneUDPout/HALE_varDIe.acf -------------------------------------------------------------------------------- /scripts/xplaneUDPout/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /scripts/xplaneUDPout/variables.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/scripts/xplaneUDPout/variables.yaml -------------------------------------------------------------------------------- /scripts/xplaneUDPout/xplaneUDP.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/scripts/xplaneUDPout/xplaneUDP.py -------------------------------------------------------------------------------- /setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/setup.py -------------------------------------------------------------------------------- /sharpy/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/__init__.py -------------------------------------------------------------------------------- /sharpy/aero/__init__.py: -------------------------------------------------------------------------------- 1 | """Aerodynamic Packages""" -------------------------------------------------------------------------------- /sharpy/aero/models/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/aero/models/aerogrid.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/aero/models/aerogrid.py -------------------------------------------------------------------------------- /sharpy/aero/models/grid.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/aero/models/grid.py -------------------------------------------------------------------------------- /sharpy/aero/models/nonliftingbodygrid.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/aero/models/nonliftingbodygrid.py -------------------------------------------------------------------------------- /sharpy/aero/utils/__init__.py: -------------------------------------------------------------------------------- 1 | """Aerodynamic Utilities""" -------------------------------------------------------------------------------- /sharpy/aero/utils/airfoilpolars.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/aero/utils/airfoilpolars.py -------------------------------------------------------------------------------- /sharpy/aero/utils/mapping.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/aero/utils/mapping.py -------------------------------------------------------------------------------- /sharpy/aero/utils/utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/aero/utils/utils.py -------------------------------------------------------------------------------- /sharpy/aero/utils/uvlmlib.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/aero/utils/uvlmlib.py -------------------------------------------------------------------------------- /sharpy/cases/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/coupled/WindTurbine/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/coupled/WindTurbine/generate_rotor.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/WindTurbine/generate_rotor.py -------------------------------------------------------------------------------- /sharpy/cases/coupled/X-HALE/generate_xhale.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/X-HALE/generate_xhale.py -------------------------------------------------------------------------------- /sharpy/cases/coupled/X-HALE/inputs/EMX-07_camber.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/X-HALE/inputs/EMX-07_camber.txt -------------------------------------------------------------------------------- /sharpy/cases/coupled/X-HALE/inputs/aero_properties.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/X-HALE/inputs/aero_properties.xlsx -------------------------------------------------------------------------------- /sharpy/cases/coupled/X-HALE/inputs/beam_properties.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/X-HALE/inputs/beam_properties.xlsx -------------------------------------------------------------------------------- /sharpy/cases/coupled/X-HALE/inputs/lumped_mass.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/X-HALE/inputs/lumped_mass.xlsx -------------------------------------------------------------------------------- /sharpy/cases/coupled/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/coupled/hinged_controlled_wing/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/coupled/linear_horten/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/coupled/multibody_takeoff/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/coupled/multibody_takeoff/generate_hale.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/multibody_takeoff/generate_hale.py -------------------------------------------------------------------------------- /sharpy/cases/coupled/simple_HALE/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/coupled/simple_HALE/generate_hale.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/coupled/simple_HALE/generate_hale.py -------------------------------------------------------------------------------- /sharpy/cases/hangar/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/hangar/horten_wing.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/hangar/horten_wing.py -------------------------------------------------------------------------------- /sharpy/cases/hangar/richards_wing.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/hangar/richards_wing.py -------------------------------------------------------------------------------- /sharpy/cases/hangar/swept_flying_wing.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/hangar/swept_flying_wing.py -------------------------------------------------------------------------------- /sharpy/cases/templates/Ttail.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/templates/Ttail.py -------------------------------------------------------------------------------- /sharpy/cases/templates/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/templates/flying_wings.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/templates/flying_wings.py -------------------------------------------------------------------------------- /sharpy/cases/templates/fuselage_wing_configuration/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/cases/templates/fuselage_wing_configuration/fwc_aero.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/templates/fuselage_wing_configuration/fwc_aero.py -------------------------------------------------------------------------------- /sharpy/cases/templates/template_wt.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/cases/templates/template_wt.py -------------------------------------------------------------------------------- /sharpy/controllers/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/controllers/__init__.py -------------------------------------------------------------------------------- /sharpy/controllers/bladepitchpid.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/controllers/bladepitchpid.py -------------------------------------------------------------------------------- /sharpy/controllers/controlsurfacepidcontroller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/controllers/controlsurfacepidcontroller.py -------------------------------------------------------------------------------- /sharpy/controllers/multibodycontroller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/controllers/multibodycontroller.py -------------------------------------------------------------------------------- /sharpy/controllers/takeofftrajectorycontroller.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/controllers/takeofftrajectorycontroller.py -------------------------------------------------------------------------------- /sharpy/generators/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/__init__.py -------------------------------------------------------------------------------- /sharpy/generators/bumpvelocityfield.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/bumpvelocityfield.py -------------------------------------------------------------------------------- /sharpy/generators/dynamiccontrolsurface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/dynamiccontrolsurface.py -------------------------------------------------------------------------------- /sharpy/generators/floatingforces.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/floatingforces.py -------------------------------------------------------------------------------- /sharpy/generators/gridbox.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/gridbox.py -------------------------------------------------------------------------------- /sharpy/generators/gustvelocityfield.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/gustvelocityfield.py -------------------------------------------------------------------------------- /sharpy/generators/helicoidalwake.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/helicoidalwake.py -------------------------------------------------------------------------------- /sharpy/generators/modifystructure.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/modifystructure.py -------------------------------------------------------------------------------- /sharpy/generators/polaraeroforces.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/polaraeroforces.py -------------------------------------------------------------------------------- /sharpy/generators/shearvelocityfield.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/shearvelocityfield.py -------------------------------------------------------------------------------- /sharpy/generators/steadyvelocityfield.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/steadyvelocityfield.py -------------------------------------------------------------------------------- /sharpy/generators/straightwake.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/straightwake.py -------------------------------------------------------------------------------- /sharpy/generators/trajectorygenerator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/trajectorygenerator.py -------------------------------------------------------------------------------- /sharpy/generators/turbvelocityfield.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/turbvelocityfield.py -------------------------------------------------------------------------------- /sharpy/generators/turbvelocityfieldbts.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/generators/turbvelocityfieldbts.py -------------------------------------------------------------------------------- /sharpy/io/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/io/__init__.py -------------------------------------------------------------------------------- /sharpy/io/inout_variables.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/io/inout_variables.py -------------------------------------------------------------------------------- /sharpy/io/logger_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/io/logger_utils.py -------------------------------------------------------------------------------- /sharpy/io/message_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/io/message_interface.py -------------------------------------------------------------------------------- /sharpy/io/network_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/io/network_interface.py -------------------------------------------------------------------------------- /sharpy/linear/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/__init__.py -------------------------------------------------------------------------------- /sharpy/linear/assembler/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/assembler/__init__.py -------------------------------------------------------------------------------- /sharpy/linear/assembler/lincontrolsurfacedeflector.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/assembler/lincontrolsurfacedeflector.py -------------------------------------------------------------------------------- /sharpy/linear/assembler/linearaeroelastic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/assembler/linearaeroelastic.py -------------------------------------------------------------------------------- /sharpy/linear/assembler/linearbeam.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/assembler/linearbeam.py -------------------------------------------------------------------------------- /sharpy/linear/assembler/linearcustom.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/assembler/linearcustom.py -------------------------------------------------------------------------------- /sharpy/linear/assembler/lineargustassembler.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/assembler/lineargustassembler.py -------------------------------------------------------------------------------- /sharpy/linear/assembler/linearuvlm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/assembler/linearuvlm.py -------------------------------------------------------------------------------- /sharpy/linear/dev/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/linear/dev/linfunc.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/dev/linfunc.py -------------------------------------------------------------------------------- /sharpy/linear/dev/linsym_biot_segment.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/dev/linsym_biot_segment.py -------------------------------------------------------------------------------- /sharpy/linear/dev/linsym_uc_dncdzeta.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/dev/linsym_uc_dncdzeta.py -------------------------------------------------------------------------------- /sharpy/linear/dev/sym_dev_dbiot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/dev/sym_dev_dbiot.py -------------------------------------------------------------------------------- /sharpy/linear/src/__init__.py: -------------------------------------------------------------------------------- 1 | """Linearised System Source Code""" -------------------------------------------------------------------------------- /sharpy/linear/src/assembly.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/assembly.py -------------------------------------------------------------------------------- /sharpy/linear/src/gridmapping.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/gridmapping.py -------------------------------------------------------------------------------- /sharpy/linear/src/interp.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/interp.py -------------------------------------------------------------------------------- /sharpy/linear/src/lib_dbiot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/lib_dbiot.py -------------------------------------------------------------------------------- /sharpy/linear/src/lib_ucdncdzeta.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/lib_ucdncdzeta.py -------------------------------------------------------------------------------- /sharpy/linear/src/libfit.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/libfit.py -------------------------------------------------------------------------------- /sharpy/linear/src/libsparse.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/libsparse.py -------------------------------------------------------------------------------- /sharpy/linear/src/libss.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/libss.py -------------------------------------------------------------------------------- /sharpy/linear/src/lin_aeroelastic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/lin_aeroelastic.py -------------------------------------------------------------------------------- /sharpy/linear/src/lin_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/lin_utils.py -------------------------------------------------------------------------------- /sharpy/linear/src/lingebm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/lingebm.py -------------------------------------------------------------------------------- /sharpy/linear/src/linuvlm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/linuvlm.py -------------------------------------------------------------------------------- /sharpy/linear/src/multisurfaces.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/multisurfaces.py -------------------------------------------------------------------------------- /sharpy/linear/src/surface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/surface.py -------------------------------------------------------------------------------- /sharpy/linear/src/uvlmutils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/src/uvlmutils.py -------------------------------------------------------------------------------- /sharpy/linear/utils/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/linear/utils/derivatives.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/utils/derivatives.py -------------------------------------------------------------------------------- /sharpy/linear/utils/ss_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/utils/ss_interface.py -------------------------------------------------------------------------------- /sharpy/linear/utils/sselements.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/linear/utils/sselements.py -------------------------------------------------------------------------------- /sharpy/postproc/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/__init__.py -------------------------------------------------------------------------------- /sharpy/postproc/aeroforcescalculator.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/aeroforcescalculator.py -------------------------------------------------------------------------------- /sharpy/postproc/aerogridplot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/aerogridplot.py -------------------------------------------------------------------------------- /sharpy/postproc/asymptoticstability.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/asymptoticstability.py -------------------------------------------------------------------------------- /sharpy/postproc/beamloads.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/beamloads.py -------------------------------------------------------------------------------- /sharpy/postproc/beamplot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/beamplot.py -------------------------------------------------------------------------------- /sharpy/postproc/cleanup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/cleanup.py -------------------------------------------------------------------------------- /sharpy/postproc/frequencyresponse.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/frequencyresponse.py -------------------------------------------------------------------------------- /sharpy/postproc/liftdistribution.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/liftdistribution.py -------------------------------------------------------------------------------- /sharpy/postproc/pickledata.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/pickledata.py -------------------------------------------------------------------------------- /sharpy/postproc/plotflowfield.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/plotflowfield.py -------------------------------------------------------------------------------- /sharpy/postproc/savedata.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/savedata.py -------------------------------------------------------------------------------- /sharpy/postproc/saveparametriccase.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/saveparametriccase.py -------------------------------------------------------------------------------- /sharpy/postproc/stabilityderivatives.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/stabilityderivatives.py -------------------------------------------------------------------------------- /sharpy/postproc/stallcheck.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/stallcheck.py -------------------------------------------------------------------------------- /sharpy/postproc/udpout.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/udpout.py -------------------------------------------------------------------------------- /sharpy/postproc/writevariablestime.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/postproc/writevariablestime.py -------------------------------------------------------------------------------- /sharpy/presharpy/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/presharpy/presharpy.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/presharpy/presharpy.py -------------------------------------------------------------------------------- /sharpy/rom/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/rom/__init__.py -------------------------------------------------------------------------------- /sharpy/rom/balanced.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/rom/balanced.py -------------------------------------------------------------------------------- /sharpy/rom/krylov.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/rom/krylov.py -------------------------------------------------------------------------------- /sharpy/rom/utils/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/rom/utils/krylovutils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/rom/utils/krylovutils.py -------------------------------------------------------------------------------- /sharpy/rom/utils/librom.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/rom/utils/librom.py -------------------------------------------------------------------------------- /sharpy/rom/utils/librom_interp.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/rom/utils/librom_interp.py -------------------------------------------------------------------------------- /sharpy/sharpy_main.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/sharpy_main.py -------------------------------------------------------------------------------- /sharpy/solvers/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/__init__.py -------------------------------------------------------------------------------- /sharpy/solvers/_basestructural.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/_basestructural.py -------------------------------------------------------------------------------- /sharpy/solvers/aerogridloader.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/aerogridloader.py -------------------------------------------------------------------------------- /sharpy/solvers/beamloader.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/beamloader.py -------------------------------------------------------------------------------- /sharpy/solvers/dynamiccoupled.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/dynamiccoupled.py -------------------------------------------------------------------------------- /sharpy/solvers/dynamicuvlm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/dynamicuvlm.py -------------------------------------------------------------------------------- /sharpy/solvers/gridloader.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/gridloader.py -------------------------------------------------------------------------------- /sharpy/solvers/initialaeroelasticloader.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/initialaeroelasticloader.py -------------------------------------------------------------------------------- /sharpy/solvers/lindynamicsim.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/lindynamicsim.py -------------------------------------------------------------------------------- /sharpy/solvers/linearassembler.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/linearassembler.py -------------------------------------------------------------------------------- /sharpy/solvers/modal.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/modal.py -------------------------------------------------------------------------------- /sharpy/solvers/noaero.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/noaero.py -------------------------------------------------------------------------------- /sharpy/solvers/nonliftingbodygridloader.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nonliftingbodygridloader.py -------------------------------------------------------------------------------- /sharpy/solvers/nonlineardynamic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nonlineardynamic.py -------------------------------------------------------------------------------- /sharpy/solvers/nonlineardynamiccoupledstep.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nonlineardynamiccoupledstep.py -------------------------------------------------------------------------------- /sharpy/solvers/nonlineardynamicmultibody.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nonlineardynamicmultibody.py -------------------------------------------------------------------------------- /sharpy/solvers/nonlineardynamicmultibodyjax.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nonlineardynamicmultibodyjax.py -------------------------------------------------------------------------------- /sharpy/solvers/nonlineardynamicprescribedstep.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nonlineardynamicprescribedstep.py -------------------------------------------------------------------------------- /sharpy/solvers/nonlinearstatic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nonlinearstatic.py -------------------------------------------------------------------------------- /sharpy/solvers/nostructural.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/nostructural.py -------------------------------------------------------------------------------- /sharpy/solvers/prescribeduvlm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/prescribeduvlm.py -------------------------------------------------------------------------------- /sharpy/solvers/rigiddynamiccoupledstep.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/rigiddynamiccoupledstep.py -------------------------------------------------------------------------------- /sharpy/solvers/rigiddynamicprescribedstep.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/rigiddynamicprescribedstep.py -------------------------------------------------------------------------------- /sharpy/solvers/staticcoupled.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/staticcoupled.py -------------------------------------------------------------------------------- /sharpy/solvers/statictrim.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/statictrim.py -------------------------------------------------------------------------------- /sharpy/solvers/staticuvlm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/staticuvlm.py -------------------------------------------------------------------------------- /sharpy/solvers/steplinearuvlm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/steplinearuvlm.py -------------------------------------------------------------------------------- /sharpy/solvers/stepuvlm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/stepuvlm.py -------------------------------------------------------------------------------- /sharpy/solvers/timeintegrators.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/timeintegrators.py -------------------------------------------------------------------------------- /sharpy/solvers/timeintegratorsjax.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/timeintegratorsjax.py -------------------------------------------------------------------------------- /sharpy/solvers/trim.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/trim.py -------------------------------------------------------------------------------- /sharpy/solvers/updatepickle.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/solvers/updatepickle.py -------------------------------------------------------------------------------- /sharpy/structure/__init__.py: -------------------------------------------------------------------------------- 1 | """Structural Packages 2 | """ -------------------------------------------------------------------------------- /sharpy/structure/basestructure.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/structure/basestructure.py -------------------------------------------------------------------------------- /sharpy/structure/models/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/structure/models/beam.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/structure/models/beam.py -------------------------------------------------------------------------------- /sharpy/structure/models/beamstructures.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/structure/models/beamstructures.py -------------------------------------------------------------------------------- /sharpy/structure/utils/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /sharpy/structure/utils/lagrangeconstraints.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/structure/utils/lagrangeconstraints.py -------------------------------------------------------------------------------- /sharpy/structure/utils/lagrangeconstraintsjax.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/structure/utils/lagrangeconstraintsjax.py -------------------------------------------------------------------------------- /sharpy/structure/utils/modalutils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/structure/utils/modalutils.py -------------------------------------------------------------------------------- /sharpy/structure/utils/xbeamlib.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/structure/utils/xbeamlib.py -------------------------------------------------------------------------------- /sharpy/utils/__init__.py: -------------------------------------------------------------------------------- 1 | """Utilities""" -------------------------------------------------------------------------------- /sharpy/utils/algebra.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/algebra.py -------------------------------------------------------------------------------- /sharpy/utils/analytical.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/analytical.py -------------------------------------------------------------------------------- /sharpy/utils/constants.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/constants.py -------------------------------------------------------------------------------- /sharpy/utils/control_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/control_utils.py -------------------------------------------------------------------------------- /sharpy/utils/controller_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/controller_interface.py -------------------------------------------------------------------------------- /sharpy/utils/cout_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/cout_utils.py -------------------------------------------------------------------------------- /sharpy/utils/ctypes_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/ctypes_utils.py -------------------------------------------------------------------------------- /sharpy/utils/datastructures.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/datastructures.py -------------------------------------------------------------------------------- /sharpy/utils/docutils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/docutils.py -------------------------------------------------------------------------------- /sharpy/utils/exceptions.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/exceptions.py -------------------------------------------------------------------------------- /sharpy/utils/frequencyutils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/frequencyutils.py -------------------------------------------------------------------------------- /sharpy/utils/generate_cases.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/generate_cases.py -------------------------------------------------------------------------------- /sharpy/utils/generator_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/generator_interface.py -------------------------------------------------------------------------------- /sharpy/utils/geo_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/geo_utils.py -------------------------------------------------------------------------------- /sharpy/utils/h5utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/h5utils.py -------------------------------------------------------------------------------- /sharpy/utils/input_arg.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/input_arg.py -------------------------------------------------------------------------------- /sharpy/utils/linearutils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/linearutils.py -------------------------------------------------------------------------------- /sharpy/utils/model_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/model_utils.py -------------------------------------------------------------------------------- /sharpy/utils/multibody.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/multibody.py -------------------------------------------------------------------------------- /sharpy/utils/multibodyjax.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/multibodyjax.py -------------------------------------------------------------------------------- /sharpy/utils/num_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/num_utils.py -------------------------------------------------------------------------------- /sharpy/utils/plotutils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/plotutils.py -------------------------------------------------------------------------------- /sharpy/utils/rom_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/rom_interface.py -------------------------------------------------------------------------------- /sharpy/utils/settings.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/settings.py -------------------------------------------------------------------------------- /sharpy/utils/sharpydir.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/sharpydir.py -------------------------------------------------------------------------------- /sharpy/utils/solver_interface.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/utils/solver_interface.py -------------------------------------------------------------------------------- /sharpy/version.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/sharpy/version.py -------------------------------------------------------------------------------- /tests/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/dynamic/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/dynamic/hale/generate_hale.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/dynamic/hale/generate_hale.py -------------------------------------------------------------------------------- /tests/coupled/dynamic/test_dynamic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/dynamic/test_dynamic.py -------------------------------------------------------------------------------- /tests/coupled/multibody/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/multibody/__init__.py -------------------------------------------------------------------------------- /tests/coupled/multibody/double_pendulum/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/multibody/double_slanted_pendulum/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/multibody/fix_node_velocity_wrtA/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/multibody/fix_node_velocity_wrtG/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/multibody/floating_forces/MooringLineFD.dat: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/multibody/floating_forces/MooringLineFD.dat -------------------------------------------------------------------------------- /tests/coupled/multibody/floating_forces/test_floatingforces.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/multibody/floating_forces/test_floatingforces.py -------------------------------------------------------------------------------- /tests/coupled/prescribed/WindTurbine/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/prescribed/WindTurbine/test_rotor.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/prescribed/WindTurbine/test_rotor.py -------------------------------------------------------------------------------- /tests/coupled/prescribed/__init__.py: -------------------------------------------------------------------------------- 1 | import tests.coupled.prescribed.WindTurbine 2 | -------------------------------------------------------------------------------- /tests/coupled/prescribed/gamma_dot_test/test_gamma_dot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/prescribed/gamma_dot_test/test_gamma_dot.py -------------------------------------------------------------------------------- /tests/coupled/prescribed/rotating_wing/generate_rotating_wing.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/prescribed/rotating_wing/generate_rotating_wing.py -------------------------------------------------------------------------------- /tests/coupled/prescribed/test_prescribed.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/prescribed/test_prescribed.py -------------------------------------------------------------------------------- /tests/coupled/static/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/static/pazy/generate_pazy.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/static/pazy/generate_pazy.py -------------------------------------------------------------------------------- /tests/coupled/static/smith_g_2deg/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/static/smith_g_2deg/generate_smith_g_2deg.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/static/smith_g_2deg/generate_smith_g_2deg.py -------------------------------------------------------------------------------- /tests/coupled/static/smith_g_4deg/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/static/smith_g_4deg/generate_smith_g_4deg.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/static/smith_g_4deg/generate_smith_g_4deg.py -------------------------------------------------------------------------------- /tests/coupled/static/smith_nog_2deg/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/static/smith_nog_2deg/generate_smith_nog_2deg.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/static/smith_nog_2deg/generate_smith_nog_2deg.py -------------------------------------------------------------------------------- /tests/coupled/static/smith_nog_4deg/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/coupled/static/smith_nog_4deg/generate_smith_nog_4deg.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/static/smith_nog_4deg/generate_smith_nog_4deg.py -------------------------------------------------------------------------------- /tests/coupled/static/test_pazy_static.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/static/test_pazy_static.py -------------------------------------------------------------------------------- /tests/coupled/static/test_static.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/coupled/static/test_static.py -------------------------------------------------------------------------------- /tests/docs/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/docs/test_docs.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/docs/test_docs.py -------------------------------------------------------------------------------- /tests/io/Example_simple_hale/Client_HALE.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/Example_simple_hale/Client_HALE.py -------------------------------------------------------------------------------- /tests/io/Example_simple_hale/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/io/Example_simple_hale/generate_hale_io.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/Example_simple_hale/generate_hale_io.py -------------------------------------------------------------------------------- /tests/io/Example_simple_hale/variables_hale.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/Example_simple_hale/variables_hale.yaml -------------------------------------------------------------------------------- /tests/io/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/io/generate_pazy_udpout.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/generate_pazy_udpout.py -------------------------------------------------------------------------------- /tests/io/sample_udp_inout/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/io/sample_udp_inout/client.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/sample_udp_inout/client.py -------------------------------------------------------------------------------- /tests/io/sample_udp_inout/generate_pazy_test_io_local.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/sample_udp_inout/generate_pazy_test_io_local.py -------------------------------------------------------------------------------- /tests/io/sample_udp_inout/variables_coarse.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/sample_udp_inout/variables_coarse.yaml -------------------------------------------------------------------------------- /tests/io/test_pazy_udpout.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/test_pazy_udpout.py -------------------------------------------------------------------------------- /tests/io/variables.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/io/variables.yaml -------------------------------------------------------------------------------- /tests/linear/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/assembly/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/assembly/test_assembly.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/assembly/test_assembly.py -------------------------------------------------------------------------------- /tests/linear/control_surfaces/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/control_surfaces/test_control_surfaces.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/control_surfaces/test_control_surfaces.py -------------------------------------------------------------------------------- /tests/linear/derivatives/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/derivatives/test_ders.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/derivatives/test_ders.py -------------------------------------------------------------------------------- /tests/linear/derivatives/test_stabilityderivatives.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/derivatives/test_stabilityderivatives.py -------------------------------------------------------------------------------- /tests/linear/frequencyutils/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/frequencyutils/src/a.npy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/frequencyutils/src/a.npy -------------------------------------------------------------------------------- /tests/linear/frequencyutils/src/b.npy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/frequencyutils/src/b.npy -------------------------------------------------------------------------------- /tests/linear/frequencyutils/src/c.npy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/frequencyutils/src/c.npy -------------------------------------------------------------------------------- /tests/linear/frequencyutils/src/d.npy: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/frequencyutils/src/d.npy -------------------------------------------------------------------------------- /tests/linear/frequencyutils/test_frequency_utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/frequencyutils/test_frequency_utils.py -------------------------------------------------------------------------------- /tests/linear/goland_wing/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/goland_wing/test_goland_flutter.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/goland_wing/test_goland_flutter.py -------------------------------------------------------------------------------- /tests/linear/gusts/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/gusts/test_external_gust.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/gusts/test_external_gust.py -------------------------------------------------------------------------------- /tests/linear/gusts/test_linear_gusts.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/gusts/test_linear_gusts.py -------------------------------------------------------------------------------- /tests/linear/horten/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/horten/test_horten.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/horten/test_horten.py -------------------------------------------------------------------------------- /tests/linear/rom/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/rom/src/A.mat: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/src/A.mat -------------------------------------------------------------------------------- /tests/linear/rom/src/B.mat: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/src/B.mat -------------------------------------------------------------------------------- /tests/linear/rom/src/C.mat: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/src/C.mat -------------------------------------------------------------------------------- /tests/linear/rom/src/schur_A.dat: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/src/schur_A.dat -------------------------------------------------------------------------------- /tests/linear/rom/test_balancing.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/test_balancing.py -------------------------------------------------------------------------------- /tests/linear/rom/test_krylov.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/test_krylov.py -------------------------------------------------------------------------------- /tests/linear/rom/test_rom_framework.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/test_rom_framework.py -------------------------------------------------------------------------------- /tests/linear/rom/test_schur.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/test_schur.py -------------------------------------------------------------------------------- /tests/linear/rom/test_springmasssystem.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/rom/test_springmasssystem.py -------------------------------------------------------------------------------- /tests/linear/statespace/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/statespace/test_statespace.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/statespace/test_statespace.py -------------------------------------------------------------------------------- /tests/linear/statespace/test_variable_tracker.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/statespace/test_variable_tracker.py -------------------------------------------------------------------------------- /tests/linear/uvlm/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/linear/uvlm/test_infinite_span.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/linear/uvlm/test_infinite_span.py -------------------------------------------------------------------------------- /tests/sourcepanelmethod/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/sourcepanelmethod/geometry_parameter_models.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/sourcepanelmethod/geometry_parameter_models.json -------------------------------------------------------------------------------- /tests/sourcepanelmethod/test_data/results_low_wing_coupled_0.csv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/sourcepanelmethod/test_data/results_low_wing_coupled_0.csv -------------------------------------------------------------------------------- /tests/sourcepanelmethod/test_data/results_low_wing_coupled_1.csv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/sourcepanelmethod/test_data/results_low_wing_coupled_1.csv -------------------------------------------------------------------------------- /tests/sourcepanelmethod/test_source_panel_method.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/sourcepanelmethod/test_source_panel_method.py -------------------------------------------------------------------------------- /tests/sourcepanelmethod/test_vlm_coupled_spm.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/sourcepanelmethod/test_vlm_coupled_spm.py -------------------------------------------------------------------------------- /tests/utils/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/utils/test_algebra.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/utils/test_algebra.py -------------------------------------------------------------------------------- /tests/utils/test_generate_cases.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/utils/test_generate_cases.py -------------------------------------------------------------------------------- /tests/utils/test_settings.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/utils/test_settings.py -------------------------------------------------------------------------------- /tests/uvlm/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/uvlm/dynamic/test_wake_cfl_n1.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/uvlm/dynamic/test_wake_cfl_n1.py -------------------------------------------------------------------------------- /tests/uvlm/static/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/uvlm/static/planarwing/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/uvlm/static/planarwing/generate_planarwing.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/uvlm/static/planarwing/generate_planarwing.py -------------------------------------------------------------------------------- /tests/uvlm/static/polars/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/uvlm/static/polars/generate_wing.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/uvlm/static/polars/generate_wing.py -------------------------------------------------------------------------------- /tests/uvlm/static/polars/test_polars.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/uvlm/static/polars/test_polars.py -------------------------------------------------------------------------------- /tests/uvlm/static/polars/xf-naca0018-il-50000.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/uvlm/static/polars/xf-naca0018-il-50000.txt -------------------------------------------------------------------------------- /tests/xbeam/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/xbeam/geradin/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tests/xbeam/geradin/generate_geradin.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/xbeam/geradin/generate_geradin.py -------------------------------------------------------------------------------- /tests/xbeam/test_xbeam.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/tests/xbeam/test_xbeam.py -------------------------------------------------------------------------------- /utils/docker/bashrc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/utils/docker/bashrc -------------------------------------------------------------------------------- /utils/environment.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ImperialCollegeLondon/sharpy/HEAD/utils/environment.yml --------------------------------------------------------------------------------