def run(self): r""" Extracts the eigenvalues and eigenvectors of the clamped structure. If ``use_undamped_modes == True`` then the free vibration modes of the clamped structure are found solving: .. math:: \mathbf{M\,\ddot{\eta}} + \mathbf{K\,\eta} = 0 that flows down to solving the non-trivial solutions to: .. math:: (-\omega_n^2\,\mathbf{M} + \mathbf{K})\mathbf{\Phi} = 0 On the other hand, if the damped modes are chosen because the system has damping, the free vibration modes are found solving the equation of motion of the form: .. math:: \mathbf{M\,\ddot{\eta}} + \mathbf{C\,\dot{\eta}} + \mathbf{K\,\eta} = 0 which can be written in state space form, with the state vector :math:`\mathbf{x} = [\eta^T,\,\dot{\eta}^T]^T` as .. math:: \mathbf{\dot{x}} = \begin{bmatrix} 0 & \mathbf{I} \\ -\mathbf{M^{-1}K} & -\mathbf{M^{-1}C} \end{bmatrix} \mathbf{x} and therefore the mode shapes and frequencies correspond to the solution of the eigenvalue problem .. math:: \mathbf{A\,\Phi} = \mathbf{\Lambda\,\Phi}. From the eigenvalues, the following system characteristics are provided: * Natural Frequency: :math:`\omega_n = |\lambda|` * Damped natural frequency: :math:`\omega_d = \text{Im}(\lambda) = \omega_n \sqrt{1-\zeta^2}` * Damping ratio: :math:`\zeta = -\frac{\text{Re}(\lambda)}{\omega_n}` In addition to the above, the modal output dictionary includes the following: * ``M``: Tangent mass matrix * ``C``: Tangent damping matrix * ``K``: Tangent stiffness matrix * ``Ccut``: Modal damping matrix :math:`\mathbf{C}_m = \mathbf{\Phi}^T\mathbf{C}\mathbf{\Phi}` * ``Kin_damp``: Forces gain matrix (when damped): :math:`K_{in} = \mathbf{\Phi}_L^T \mathbf{M}^{-1}` * ``eigenvectors``: Right eigenvectors * ``eigenvectors_left``: Left eigenvectors given when the system is damped Returns: PreSharpy: updated data object with modal analysis as part of the last structural time step. """ # Number of degrees of freedom num_str_dof = self.data.structure.num_dof.value if self.rigid_body_motion: num_rigid_dof = 10 else: num_rigid_dof = 0 num_dof = num_str_dof + num_rigid_dof # if NumLambda # Initialize matrices FullMglobal = np.zeros((num_dof, num_dof), dtype=ct.c_double, order='F') FullKglobal = np.zeros((num_dof, num_dof), dtype=ct.c_double, order='F') FullCglobal = np.zeros((num_dof, num_dof), dtype=ct.c_double, order='F') if self.rigid_body_motion: # Settings for the assembly of the matrices # try: # full_matrix_settings = self.data.settings['StaticCoupled']['structural_solver_settings'] # full_matrix_settings['dt'] = ct.c_double(0.01) # Dummy: required but not used # full_matrix_settings['newmark_damp'] = ct.c_double(1e-2) # Dummy: required but not used # except KeyError: # full_matrix_settings = self.data.settings['DynamicCoupled']['structural_solver_settings'] import sharpy.solvers._basestructural as basestructuralsolver full_matrix_settings = basestructuralsolver._BaseStructural().settings_default settings.to_custom_types(full_matrix_settings, basestructuralsolver._BaseStructural().settings_types, full_matrix_settings) # Obtain the tangent mass, damping and stiffness matrices FullMglobal, FullCglobal, FullKglobal, FullQ = xbeamlib.xbeam3_asbly_dynamic(self.data.structure, self.data.structure.timestep_info[self.data.ts], full_matrix_settings) else: xbeamlib.cbeam3_solv_modal(self.data.structure, self.settings, self.data.ts, FullMglobal, FullCglobal, FullKglobal) # Print matrices if self.settings['print_matrices'].value: np.savetxt(self.folder + "Mglobal.dat", FullMglobal, fmt='%.12f', delimiter='\t', newline='\n') np.savetxt(self.folder + "Cglobal.dat", FullCglobal, fmt='%.12f', delimiter='\t', newline='\n') np.savetxt(self.folder + "Kglobal.dat", FullKglobal, fmt='%.12f', delimiter='\t', newline='\n') # Check if the damping matrix is zero (issue working) if self.settings['use_undamped_modes'].value: zero_FullCglobal = True for i,j in itertools.product(range(num_dof),range(num_dof)): if(np.absolute(FullCglobal[i, j]) > np.finfo(float).eps): zero_FullCglobal = False warnings.warn( 'Projecting a system with damping on undamped modal shapes') break # Check if the damping matrix is skew-symmetric # skewsymmetric_FullCglobal = True # for i in range(num_dof): # for j in range(i:num_dof): # if((i==j) and (np.absolute(FullCglobal[i, j]) > np.finfo(float).eps)): # skewsymmetric_FullCglobal = False # elif(np.absolute(FullCglobal[i, j] + FullCglobal[j, i]) > np.finfo(float).eps): # skewsymmetric_FullCglobal = False NumLambda = min(num_dof, self.settings['NumLambda'].value) if self.settings['use_undamped_modes'].value: # Solve for eigenvalues (with unit eigenvectors) eigenvalues,eigenvectors=np.linalg.eig( np.linalg.solve(FullMglobal,FullKglobal)) eigenvectors_left=None # Define vibration frequencies and damping freq_natural = np.sqrt(eigenvalues) order = np.argsort(freq_natural)[:NumLambda] freq_natural = freq_natural[order] #freq_damped = freq_natural eigenvalues = eigenvalues[order] eigenvectors = eigenvectors[:,order] damping = np.zeros((NumLambda,)) else: # State-space model Minv_neg = -np.linalg.inv(FullMglobal) A = np.zeros((2*num_dof, 2*num_dof), dtype=ct.c_double, order='F') A[:num_dof, num_dof:] = np.eye(num_dof) A[num_dof:, :num_dof] = np.dot(Minv_neg, FullKglobal) A[num_dof:, num_dof:] = np.dot(Minv_neg, FullCglobal) # Solve the eigenvalues problem eigenvalues, eigenvectors_left, eigenvectors = \ sc.linalg.eig(A,left=True,right=True) freq_natural = np.abs(eigenvalues) damping = np.zeros_like(freq_natural) iiflex = freq_natural > 1e-16*np.mean(freq_natural) # Pick only structural modes damping[iiflex] = -eigenvalues[iiflex].real/freq_natural[iiflex] freq_damped = freq_natural * np.sqrt(1-damping**2) # Order & downselect complex conj: # this algorithm assumes that complex conj eigenvalues appear consecutively # in eigenvalues. For symmetrical systems, this relies on the fact that: # - complex conj eigenvalues have the same absolute value (to machine # precision) # - couples of eigenvalues with multiplicity higher than 1, show larger # numerical difference order = np.argsort(freq_damped)[:2*NumLambda] freq_damped = freq_damped[order] freq_natural = freq_natural[order] eigenvalues = eigenvalues[order] include = np.ones((2*NumLambda,), dtype=np.bool) ii = 0 tol_rel = np.finfo(float).eps * freq_damped[ii] while ii < 2*NumLambda: # check complex if np.abs(eigenvalues[ii].imag) > 0.: if np.abs(eigenvalues[ii+1].real-eigenvalues[ii].real) > tol_rel or\ np.abs(eigenvalues[ii+1].imag+eigenvalues[ii].imag) > tol_rel: raise NameError('Complex conjugate expected but not found!') ii += 1 try: include[ii] = False except IndexError: pass ii += 1 freq_damped = freq_damped[include] eigenvalues = eigenvalues[include] if self.settings['continuous_eigenvalues']: if self.settings['dt'].value == 0.: raise ValueError('Cannot compute the continuous eigenvalues without a dt value') eigenvalues = np.log(eigenvalues)/self.settings['dt'].value order = order[include] damping = damping[order] eigenvectors = eigenvectors[:, order] eigenvectors_left = eigenvectors_left[:, order].conj() # Modify rigid body modes for them to be defined wrt the CG if self.settings['rigid_modes_cg']: if not eigenvectors_left: eigenvectors = self.free_free_modes(eigenvectors, FullMglobal) # Scaling eigenvectors, eigenvectors_left = self.scale_modes_unit_mass_matrix(eigenvectors, FullMglobal, eigenvectors_left) # Other terms required for state-space realisation # non-zero damping matrix # Modal damping matrix if self.settings['use_undamped_modes'] and not(zero_FullCglobal): Ccut = np.dot(eigenvectors.T, np.dot(FullCglobal, eigenvectors)) else: Ccut = None # forces gain matrix (nodal -> modal) if not self.settings['use_undamped_modes']: Kin_damp = np.dot(eigenvectors_left[num_dof:, :].T, -Minv_neg) else: Kin_damp = None # Plot eigenvalues using matplotlib if specified in settings if self.settings['plot_eigenvalues']: import matplotlib.pyplot as plt fig = plt.figure() plt.scatter(eigenvalues.real, eigenvalues.imag) plt.show() plt.savefig(self.folder + 'eigenvalues.png', transparent=True, bbox_inches='tight') # Write dat files if self.settings['write_dat'].value: if type(eigenvalues) == complex: np.savetxt(self.folder + "eigenvalues.dat", eigenvalues.view(float).reshape(-1, 2), fmt='%.12f', delimiter='\t', newline='\n') else: np.savetxt(self.folder + "eigenvalues.dat", eigenvalues.view(float), fmt='%.12f', delimiter='\t', newline='\n') np.savetxt(self.folder + "eigenvectors.dat", eigenvectors[:num_dof].real, fmt='%.12f', delimiter='\t', newline='\n') if not self.settings['use_undamped_modes'].value: np.savetxt(self.folder + 'frequencies.dat', freq_damped[:NumLambda], fmt='%e', delimiter='\t', newline='\n') else: np.savetxt(self.folder + 'frequencies.dat', freq_natural[:NumLambda], fmt='%e', delimiter='\t', newline='\n') np.savetxt(self.filename_damp, damping[:NumLambda], fmt='%e', delimiter='\t', newline='\n') # Write vtk if self.settings['write_modes_vtk'].value: try: self.data.aero aero_model = True except AttributeError: warnings.warn('No aerodynamic model found - unable to project the mode onto aerodynamic grid') aero_model = False if aero_model: modalutils.write_modes_vtk( self.data, eigenvectors[:num_dof], NumLambda, self.filename_shapes, self.settings['max_rotation_deg'], self.settings['max_displacement'], ts=self.settings['use_custom_timestep'].value) outdict = dict() if self.settings['use_undamped_modes']: outdict['modes'] = 'undamped' outdict['freq_natural'] = freq_natural if not zero_FullCglobal: outdict['warning'] =\ 'system with damping: mode shapes and natural frequencies do not account for damping!' else: outdict['modes'] = 'damped' outdict['freq_damped'] = freq_damped outdict['freq_natural'] = freq_natural outdict['damping'] = damping outdict['eigenvalues'] = eigenvalues outdict['eigenvectors'] = eigenvectors if Ccut is not None: outdict['Ccut'] = Ccut if Kin_damp is not None: outdict['Kin_damp'] = Kin_damp if not self.settings['use_undamped_modes']: outdict['eigenvectors_left'] = eigenvectors_left if self.settings['keep_linear_matrices'].value: outdict['M'] = FullMglobal outdict['C'] = FullCglobal outdict['K'] = FullKglobal self.data.structure.timestep_info[self.data.ts].modal = outdict if self.settings['print_info']: if self.settings['use_undamped_modes']: self.eigenvalue_table.print_evals(np.sqrt(eigenvalues[:NumLambda])*1j) else: self.eigenvalue_table.print_evals(eigenvalues[:NumLambda]) return self.data
def run(self): self.data.ts = len(self.data.structure.timestep_info) - 1 # Initialize matrices num_dof = self.data.structure.num_dof.value FullMglobal = np.zeros((num_dof, num_dof), dtype=ct.c_double, order='F') FullKglobal = np.zeros((num_dof, num_dof), dtype=ct.c_double, order='F') FullCglobal = np.zeros((num_dof, num_dof), dtype=ct.c_double, order='F') # Obtain the matrices from the fortran library xbeamlib.cbeam3_solv_modal(self.data.structure, self.settings, self.data.ts, FullMglobal, FullCglobal, FullKglobal) # Print matrices if self.settings['print_matrices'].value: np.savetxt(self.folder + "Mglobal.dat", FullMglobal, fmt='%.12f', delimiter='\t', newline='\n') np.savetxt(self.folder + "Cglobal.dat", FullCglobal, fmt='%.12f', delimiter='\t', newline='\n') np.savetxt(self.folder + "Kglobal.dat", FullKglobal, fmt='%.12f', delimiter='\t', newline='\n') # Check if the damping matrix is zero (issue working) if self.settings['use_undamped_modes'].value: zero_FullCglobal = True for i, j in itertools.product(range(num_dof), range(num_dof)): if (np.absolute(FullCglobal[i, j]) > np.finfo(float).eps): zero_FullCglobal = False warnings.warn( 'Projecting a system with damping on undamped modal shapes' ) break # Check if the damping matrix is skew-symmetric # skewsymmetric_FullCglobal = True # for i in range(num_dof): # for j in range(i:num_dof): # if((i==j) and (np.absolute(FullCglobal[i, j]) > np.finfo(float).eps)): # skewsymmetric_FullCglobal = False # elif(np.absolute(FullCglobal[i, j] + FullCglobal[j, i]) > np.finfo(float).eps): # skewsymmetric_FullCglobal = False NumLambda = min(self.data.structure.num_dof.value, self.settings['NumLambda'].value) if self.settings['use_undamped_modes'].value: # Solve for eigenvalues (with unit eigenvectors) eigenvalues, eigenvectors = np.linalg.eig( np.linalg.solve(FullMglobal, FullKglobal)) eigenvectors_left = None # Define vibration frequencies and damping freq_natural = np.sqrt(eigenvalues) order = np.argsort(freq_natural)[:NumLambda] freq_natural = freq_natural[order] #freq_damped = freq_natural eigenvalues = eigenvalues[order] eigenvectors = eigenvectors[:, order] damping = np.zeros((NumLambda, )) else: # State-space model Minv_neg = -np.linalg.inv(FullMglobal) A = np.zeros((2 * num_dof, 2 * num_dof), dtype=ct.c_double, order='F') A[range(num_dof), range(num_dof, 2 * num_dof)] = 1. A[num_dof:, :num_dof] = np.dot(Minv_neg, FullKglobal) A[num_dof:, num_dof:] = np.dot(Minv_neg, FullCglobal) # Solve the eigenvalues problem eigenvalues, eigenvectors_left, eigenvectors = \ sc.linalg.eig(A,left=True,right=True) freq_damped = np.abs(eigenvalues) damping = np.zeros_like(freq_damped) iiflex = freq_damped > 1e-16 * np.mean(freq_damped) damping[iiflex] = eigenvalues[iiflex].real / freq_damped[iiflex] # Order & downselect complex conj: # this algorithm assumes that complex conj eigenvalues appear consecutively # in eigenvalues. For symmetrical systems, this relies on the fact that: # - complex conj eigenvalues have the same absolute value (to machine # precision) # - couples of eigenvalues with moltiplicity higher than 1, show larger # numerical difference order = np.argsort(freq_damped)[:2 * NumLambda] freq_damped = freq_damped[order] eigenvalues = eigenvalues[order] include = np.ones((2 * NumLambda, ), dtype=np.bool) ii = 0 tol_rel = np.finfo(float).eps * freq_damped[ii] while ii < 2 * NumLambda: # check complex if np.abs(eigenvalues[ii].imag) > 0.: if np.abs(eigenvalues[ii+1].real-eigenvalues[ii].real) > tol_rel or\ np.abs(eigenvalues[ii+1].imag+eigenvalues[ii].imag) > tol_rel: raise NameError( 'Complex conjugate expected but not found!') ii += 1 try: include[ii] = False except IndexError: pass ii += 1 freq_damped = freq_damped[include] eigenvalues = eigenvalues[include] if self.settings['continuous_eigenvalues']: if self.settings['dt'].value == 0.: raise ValueError( 'Cannot compute the continuous eigenvalues without a dt value' ) eigenvalues = np.log(eigenvalues) / self.settings['dt'].value order = order[include] damping = damping[order] eigenvectors = eigenvectors[:, order] eigenvectors_left = eigenvectors_left[:, order].conj() # Scaling if self.settings['use_undamped_modes']: # mass normalise (diagonalises M and K) dfact = np.diag( np.dot(eigenvectors.T, np.dot(FullMglobal, eigenvectors))) eigenvectors = (1. / np.sqrt(dfact)) * eigenvectors else: # unit normalise (diagonalises A) for ii in range(NumLambda): fact = 1. / np.sqrt( np.dot(eigenvectors_left[:, ii], eigenvectors[:, ii])) eigenvectors_left[:, ii] = fact * eigenvectors_left[:, ii] eigenvectors[:, ii] = fact * eigenvectors[:, ii] # Other terms required for state-space realisation # non-zero damping matrix if self.settings['use_undamped_modes'] and not (zero_FullCglobal): Ccut = np.dot(eigenvectors.T, np.dot(FullCglobal, eigenvectors)) else: Ccut = None # forces gain matrix (nodal -> modal) if not self.settings['use_undamped_modes']: Kin_damp = np.dot(eigenvectors_left[num_dof:, :].T, -Minv_neg) else: Kin_damp = None # # plot eigenvalues # fig = plt.figure() # plt.scatter(eigenvalues.real, eigenvalues.imag) # plt.show() # plt.savefig(self.folder + 'eigenvalues.png', transparent=True, bbox_inches='tight') # Write dat files if self.settings['write_dat'].value: np.savetxt(self.folder + "eigenvalues.dat", eigenvalues, fmt='%.12f', delimiter='\t', newline='\n') np.savetxt(self.folder + "eigenvectors.dat", eigenvectors[:num_dof].real, fmt='%.12f', delimiter='\t', newline='\n') try: np.savetxt(self.folder + 'frequencies.dat', freq_damped[:NumLambda], fmt='%e', delimiter='\t', newline='\n') except NameError: np.savetxt(self.folder + 'frequencies.dat', freq_natural[:NumLambda], fmt='%e', delimiter='\t', newline='\n') np.savetxt(self.filename_damp, damping[:NumLambda], fmt='%e', delimiter='\t', newline='\n') # Write vtk if self.settings['write_modes_vtk'].value: write_modes_vtk(self.data, eigenvectors[:num_dof], NumLambda, self.filename_shapes, self.settings['max_rotation_deg'], self.settings['max_displacement']) outdict = dict() if self.settings['use_undamped_modes']: outdict['modes'] = 'undamped' outdict['freq_natural'] = freq_natural if not zero_FullCglobal: outdict['warning'] =\ 'system with damping: mode shapes and natural frequencies do not account for damping!' else: outdict['modes'] = 'damped' outdict['freq_damped'] = freq_damped outdict['damping'] = damping outdict['eigenvalues'] = eigenvalues outdict['eigenvectors'] = eigenvectors if Ccut is not None: outdict['Ccut'] = Ccut if Kin_damp is not None: outdict['Kin_damp'] = Kin_damp if not self.settings['use_undamped_modes']: outdict['eigenvectors_left'] = eigenvectors_left if self.settings['keep_linear_matrices'].value: outdict['M'] = FullMglobal outdict['C'] = FullCglobal outdict['K'] = FullKglobal self.data.structure.timestep_info[self.data.ts].modal = outdict return self.data