Exudyn documentation
- Exudyn
- Installation and Getting Started
- Installation and Getting Started
- Getting started
- Installation instructions
- Requirements for Exudyn ?
- Install Exudyn with PIP INSTALLER (pypi.org)
- Install from specific Wheel (Ubuntu and Windows)
- Build and install Exudyn under Windows 10?
- Build and install Exudyn under Mac OS X?
- Build and install Exudyn under Ubuntu?
- Uninstall Exudyn
- How to install Exudyn and use the C++ source code (advanced)?
- Further notes
- Run a simple example in Python
- Trouble shooting and FAQ
- Overview on Exudyn
- Overview on Exudyn
- Module structure
- Items: Nodes, Objects, Loads, Markers, Sensors, …
- Mapping between local and global coordinate indices
- Exudyn Basics
- Interaction with the Exudyn module
- Simulation settings
- Generating output and results
- Renderer and 3D graphics
- Visualization settings dialog
- Execute Command and Help
- Graphics pipeline
- Storing the model view
- Graphics user functions via Python
- Color, RGBA and alpha-transparency
- Solution viewer
- Generating animations
- Examples, test models and test suite
- Removing convergence problems and solver failures
- Performance and ways to speed up computations
- Advanced topics
- C++ Code
- Tutorial
- Graphics and visualization
- Notation
- Theory and formulations
- Theory and formulations
- Introduction to multibody systems
- Historical development
- Simulation tools in computational engineering
- Components of a multibody system
- Kinematics basics
- Euler’s and Chasles’s Theorems
- Degree of freedom – DOF
- Non-holonomic constraints
- Dependent and independent coordinates
- Chebychev-Grübler-Kutzbach criterion
- Generalized coordinates
- Reference and current coordinates
- Dynamics: Mechanical principles
- Frames, rotations and coordinate systems
- Integration Points
- Model order reduction and component mode synthesis
- Solvers
- Python-C++ command interface
- Python Utility Functions
- Python Utility Functions
- Module: advancedUtilities
- Function: PlotLineCode
- Function: FindObjectIndex
- Function: FindNodeIndex
- Function: IsListOrArray
- Function: RaiseTypeError
- Function: IsNone
- Function: IsNotNone
- Function: IsValidBool
- Function: IsValidRealInt
- Function: IsValidPRealInt
- Function: IsValidURealInt
- Function: IsReal
- Function: IsInteger
- Function: IsVector
- Function: IsIntVector
- Function: IsSquareMatrix
- Function: IsValidObjectIndex
- Function: IsValidNodeIndex
- Function: IsValidMarkerIndex
- Function: IsEmptyList
- Function: FillInSubMatrix
- Function: SweepSin
- Function: SweepCos
- Function: FrequencySweep
- Function: SmoothStep
- Function: SmoothStepDerivative
- Function: IndexFromValue
- Function: RoundMatrix
- Function: ConvertFunctionToSymbolic
- Function: CreateSymbolicUserFunction
- CLASS ExpectedType(Enum) (in module advancedUtilities)
- Module: artificialIntelligence
- CLASS OpenAIGymInterfaceEnv(Env) (in module artificialIntelligence)
- Class function: __init__
- Class function: CreateMBS
- Class function: SetupSpaces
- Class function: MapAction2MBS
- Class function: Output2StateAndDone
- Class function: State2InitialValues
- Class function: TestModel
- Class function: SetSolver
- Class function: PreInitializeSolver
- Class function: IntegrateStep
- Class function: step
- Class function: reset
- Class function: render
- Class function: close
- Module: basicUtilities
- Module: beams
- Module: FEM
- Function: CompressedRowSparseToDenseMatrix
- Function: MapSparseMatrixIndices
- Function: VectorDiadicUnitMatrix3D
- Function: CyclicCompareReversed
- Function: AddEntryToCompressedRowSparseArray
- Function: CSRtoRowsAndColumns
- Function: CSRtoScipySparseCSR
- Function: SparseTripletsToScipySparseCSR
- Function: ScipySparseCSRtoCSR
- Function: ResortIndicesOfCSRmatrix
- Function: ResortIndicesOfNGvector
- Function: ResortIndicesExudyn2NGvector
- Function: ConvertHexToTrigs
- Function: ConvertTetToTrigs
- Function: ConvertDenseToCompressedRowMatrix
- Function: ReadMatrixFromAnsysMMF
- Function: ReadMatrixDOFmappingVectorFromAnsysTxt
- Function: ReadNodalCoordinatesFromAnsysTxt
- Function: ReadElementsFromAnsysTxt
- Function: CMSObjectComputeNorm
- CLASS MaterialBaseClass (in module FEM)
- CLASS KirchhoffMaterial(MaterialBaseClass) (in module FEM)
- Class function: Strain2Stress
- Class function: StrainVector2StressVector
- Class function: StrainVector2StressVector2D
- Class function: LameParameters
- CLASS FiniteElement (in module FEM)
- CLASS Tet4(FiniteElement) (in module FEM)
- CLASS ObjectFFRFinterface (in module FEM)
- Class function: __init__
- Class function: AddObjectFFRF
- Class function: UFforce
- Class function: UFmassGenericODE2
- CLASS ObjectFFRFreducedOrderInterface (in module FEM)
- Class function: __init__
- Class function: SaveToFile
- Class function: LoadFromFile
- Class function: AddObjectFFRFreducedOrderWithUserFunctions
- Class function: UFmassFFRFreducedOrder
- Class function: UFforceFFRFreducedOrder
- Class function: AddObjectFFRFreducedOrder
- CLASS HCBstaticModeSelection(Enum) (in module FEM)
- CLASS FEMinterface (in module FEM)
- Class function: __init__
- Class function: SaveToFile
- Class function: LoadFromFile
- Class function: ImportFromAbaqusInputFile
- Class function: ReadMassMatrixFromAbaqus
- Class function: ReadStiffnessMatrixFromAbaqus
- Class function: ImportMeshFromNGsolve
- Class function: ComputeEigenmodesNGsolve
- Class function: ComputeHurtyCraigBamptonModesNGsolve
- Class function: ComputePostProcessingModesNGsolve
- Class function: GetMassMatrix
- Class function: GetStiffnessMatrix
- Class function: NumberOfNodes
- Class function: GetNodePositionsAsArray
- Class function: GetNodePositionsMean
- Class function: NumberOfCoordinates
- Class function: GetNodeAtPoint
- Class function: GetNodesInPlane
- Class function: GetNodesInCube
- Class function: GetNodesOnLine
- Class function: GetNodesOnCylinder
- Class function: GetNodesOnCircle
- Class function: GetNodeWeightsFromSurfaceAreas
- Class function: GetSurfaceTriangles
- Class function: VolumeToSurfaceElements
- Class function: GetGyroscopicMatrix
- Class function: ScaleMassMatrix
- Class function: ScaleStiffnessMatrix
- Class function: AddElasticSupportAtNode
- Class function: AddNodeMass
- Class function: CreateLinearFEMObjectGenericODE2
- Class function: CreateNonlinearFEMObjectGenericODE2NGsolve
- Class function: ComputeEigenmodes
- Class function: ComputeEigenModesWithBoundaryNodes
- Class function: ComputeHurtyCraigBamptonModes
- Class function: GetEigenFrequenciesHz
- Class function: ComputePostProcessingModes
- Class function: ComputeCampbellDiagram
- Class function: CheckConsistency
- Class function: ReadMassMatrixFromAnsys
- Class function: ReadStiffnessMatrixFromAnsys
- Class function: ReadNodalCoordinatesFromAnsys
- Class function: ReadElementsFromAnsys
- Module: graphics
- Function: Sphere
- Function: Lines
- Function: Circle
- Function: Text
- Function: Cuboid
- Function: BrickXYZ
- Function: Brick
- Function: Cylinder
- Function: RigidLink
- Function: SolidOfRevolution
- Function: Arrow
- Function: Basis
- Function: Frame
- Function: Quad
- Function: CheckerBoard
- Function: SolidExtrusion
- Function: FromPointsAndTrigs
- Function: ToPointsAndTrigs
- Function: Move
- Function: MergeTriangleLists
- Function: FromSTLfileASCII
- Function: FromSTLfile
- Function: AddEdgesAndSmoothenNormals
- Function: ExportSTL
- Module: graphicsDataUtilities
- Function: SwitchTripletOrder
- Function: ComputeTriangleNormal
- Function: ComputeTriangleArea
- Function: RefineMesh
- Function: ShrinkMeshNormalToSurface
- Function: ComputeTriangularMesh
- Function: SegmentsFromPoints
- Function: CirclePointsAndSegments
- Function: GraphicsDataRectangle
- Function: GraphicsDataOrthoCubeLines
- Module: GUI
- Module: interactive
- Function: AnimateModes
- Function: SolutionViewer
- CLASS InteractiveDialog (in module interactive)
- Class function: __init__
- Class function: OnQuit
- Class function: StartSimulation
- Class function: ProcessWidgetStates
- Class function: ContinuousRunFunction
- Class function: InitializePlots
- Class function: UpdatePlots
- Class function: InitializeSolver
- Class function: FinalizeSolver
- Class function: RunSimulationPeriod
- Module: kinematicTree
- Function: MassCOMinertia2T66
- Function: Inertia2T66
- Function: Inertia66toMassCOMinertia
- Function: JointTransformMotionSubspace66
- Function: JointTransformMotionSubspace
- Function: CRM
- Function: CRF
- CLASS KinematicTree33 (in module kinematicTree)
- Class function: __init__
- Class function: Size
- Class function: XL
- Class function: ForwardDynamicsCRB
- Class function: ComputeMassMatrixAndForceTerms
- CLASS KinematicTree66 (in module kinematicTree)
- Class function: __init__
- Class function: Size
- Class function: XL
- Class function: ForwardDynamicsCRB
- Class function: ComputeMassMatrixAndForceTerms
- Class function: AddExternalForces
- Module: lieGroupBasics
- Function: Sinc
- Function: Cot
- Function: R3xSO3Matrix2RotationMatrix
- Function: R3xSO3Matrix2Translation
- Function: R3xSO3Matrix
- Function: ExpSO3
- Function: ExpS3
- Function: LogSO3
- Function: TExpSO3
- Function: TExpSO3Inv
- Function: ExpSE3
- Function: LogSE3
- Function: TExpSE3
- Function: TExpSE3Inv
- Function: ExpR3xSO3
- Function: TExpR3xSO3
- Function: TExpR3xSO3Inv
- Function: CompositionRuleDirectProductR3AndS3
- Function: CompositionRuleSemiDirectProductR3AndS3
- Function: CompositionRuleDirectProductR3AndR3RotVec
- Function: CompositionRuleSemiDirectProductR3AndR3RotVec
- Function: CompositionRuleDirectProductR3AndR3RotXYZAngles
- Function: CompositionRuleSemiDirectProductR3AndR3RotXYZAngles
- Function: CompositionRuleForEulerParameters
- Function: CompositionRuleForRotationVectors
- Function: CompositionRuleRotXYZAnglesRotationVector
- Module: mainSystemExtensions
- Module: physics
- Module: plot
- Module: processing
- Module: rigidBodyUtilities
- Function: ComputeOrthonormalBasisVectors
- Function: ComputeOrthonormalBasis
- Function: GramSchmidt
- Function: Skew
- Function: Skew2Vec
- Function: ComputeSkewMatrix
- Function: EulerParameters2G
- Function: EulerParameters2GLocal
- Function: EulerParameters2RotationMatrix
- Function: RotationMatrix2EulerParameters
- Function: AngularVelocity2EulerParameters_t
- Function: RotationVector2RotationMatrix
- Function: RotationMatrix2RotationVector
- Function: ComputeRotationAxisFromRotationVector
- Function: RotationVector2G
- Function: RotationVector2GLocal
- Function: RotXYZ2RotationMatrix
- Function: RotationMatrix2RotXYZ
- Function: RotXYZ2G
- Function: RotXYZ2G_t
- Function: RotXYZ2GLocal
- Function: RotXYZ2GLocal_t
- Function: AngularVelocity2RotXYZ_t
- Function: RotXYZ2EulerParameters
- Function: RotationMatrix2RotZYZ
- Function: RotationMatrixX
- Function: RotationMatrixY
- Function: RotationMatrixZ
- Function: HomogeneousTransformation
- Function: HTtranslate
- Function: HTtranslateX
- Function: HTtranslateY
- Function: HTtranslateZ
- Function: HT0
- Function: HTrotateX
- Function: HTrotateY
- Function: HTrotateZ
- Function: HT2translation
- Function: HT2rotationMatrix
- Function: InverseHT
- Function: RotationX2T66
- Function: RotationY2T66
- Function: RotationZ2T66
- Function: Translation2T66
- Function: TranslationX2T66
- Function: TranslationY2T66
- Function: TranslationZ2T66
- Function: T66toRotationTranslation
- Function: InverseT66toRotationTranslation
- Function: RotationTranslation2T66
- Function: RotationTranslation2T66Inverse
- Function: T66toHT
- Function: HT2T66Inverse
- Function: InertiaTensor2Inertia6D
- Function: Inertia6D2InertiaTensor
- Function: StrNodeType2NodeType
- Function: GetRigidBodyNode
- Function: AddRigidBody
- Function: AddRevoluteJoint
- Function: AddPrismaticJoint
- CLASS RigidBodyInertia (in module rigidBodyUtilities)
- Class function: __init__
- Class function: __add__
- Class function: __iadd__
- Class function: SetWithCOMinertia
- Class function: Inertia
- Class function: InertiaCOM
- Class function: COM
- Class function: Mass
- Class function: Translated
- Class function: Rotated
- Class function: Transformed
- Class function: GetInertia6D
- CLASS InertiaCuboid(RigidBodyInertia) (in module rigidBodyUtilities)
- Class function: __init__
- CLASS InertiaRodX(RigidBodyInertia) (in module rigidBodyUtilities)
- Class function: __init__
- CLASS InertiaMassPoint(RigidBodyInertia) (in module rigidBodyUtilities)
- Class function: __init__
- CLASS InertiaSphere(RigidBodyInertia) (in module rigidBodyUtilities)
- Class function: __init__
- CLASS InertiaHollowSphere(RigidBodyInertia) (in module rigidBodyUtilities)
- Class function: __init__
- CLASS InertiaCylinder(RigidBodyInertia) (in module rigidBodyUtilities)
- Class function: __init__
- Module: robotics
- Function: StdDH2HT
- Function: ModDHKK2HT
- Function: projectAngleToPMPi
- CLASS VRobotLink (in module robotics)
- Class function: __init__
- CLASS RobotLink (in module robotics)
- Class function: __init__
- Class function: SetPDcontrol
- Class function: HasPDcontrol
- Class function: GetPDcontrol
- CLASS VRobotTool (in module robotics)
- Class function: __init__
- CLASS RobotTool (in module robotics)
- Class function: __init__
- CLASS VRobotBase (in module robotics)
- Class function: __init__
- CLASS RobotBase (in module robotics)
- Class function: __init__
- CLASS Robot (in module robotics)
- Class function: __init__
- Class function: AddLink
- Class function: IsSerialRobot
- Class function: GetLink
- Class function: HasParent
- Class function: GetParentIndex
- Class function: NumberOfLinks
- Class function: GetBaseHT
- Class function: GetToolHT
- Class function: LinkHT
- Class function: JointHT
- Class function: COMHT
- Class function: StaticTorques
- Class function: Jacobian
- Class function: CreateKinematicTree
- Class function: CreateRedundantCoordinateMBS
- Class function: GetKinematicTree66
- Class function: GetLinkGraphicsData
- Class function: BuildFromDictionary
- CLASS InverseKinematicsNumerical() (in module robotics)
- Class function: __init__
- Class function: GetCurrentRobotHT
- Class function: InterpolateHTs
- Class function: SolveSafe
- Class function: Solve
- Module: robotics.rosInterface
- Module: robotics.future
- Module: robotics.models
- Module: robotics.mobile
- Module: robotics.motion
- CLASS ProfileConstantAcceleration (in module robotics.motion)
- Class function: __init__
- Class function: GetBasicProfile
- CLASS ProfileLinearAccelerationsList (in module robotics.motion)
- Class function: __init__
- Class function: GetBasicProfile
- CLASS ProfilePTP (in module robotics.motion)
- Class function: __init__
- Class function: GetBasicProfile
- CLASS Trajectory (in module robotics.motion)
- Class function: __init__
- Class function: GetFinalCoordinates
- Class function: Add
- Class function: GetTimes
- Class function: Initialize
- Class function: Evaluate
- Class function: EvaluateCoordinate
- Class function: __iter__
- Class function: __getitem__
- Class function: __len__
- Class function: __repr__
- Module: robotics.special
- Module: robotics.utilities
- Module: signalProcessing
- Module: solver
- Module: utilities
- Function: ShowOnlyObjects
- Function: HighlightItem
- Function: __UFsensorDistance
- Function: CreateDistanceSensorGeometry
- Function: CreateDistanceSensor
- Function: UFsensorRecord
- Function: AddSensorRecorder
- Function: LoadSolutionFile
- Function: NumpyInt8ArrayToString
- Function: BinaryReadIndex
- Function: BinaryReadReal
- Function: BinaryReadString
- Function: BinaryReadArrayIndex
- Function: BinaryReadRealVector
- Function: LoadBinarySolutionFile
- Function: RecoverSolutionFile
- Function: InitializeFromRestartFile
- Function: SetSolutionState
- Function: AnimateSolution
- Function: DrawSystemGraph
- Function: CreateTCPIPconnection
- Function: TCPIPsendReceive
- Function: CloseTCPIPconnection
- CLASS TCPIPdata (in module utilities)
- Items reference manual
- Node
- Object (Body)
- Object (SuperElement)
- Object (Object)
- Object (FiniteElement)
- Object (Connector)
- ObjectConnectorSpringDamper
- ObjectConnectorCartesianSpringDamper
- ObjectConnectorRigidBodySpringDamper
- ObjectConnectorLinearSpringDamper
- ObjectConnectorTorsionalSpringDamper
- ObjectConnectorCoordinateSpringDamper
- ObjectConnectorCoordinateSpringDamperExt
- ObjectConnectorGravity
- ObjectConnectorHydraulicActuatorSimple
- ObjectConnectorReevingSystemSprings
- ObjectConnectorRollingDiscPenalty
- ObjectContactConvexRoll
- ObjectContactCoordinate
- ObjectContactCircleCable2D
- ObjectContactFrictionCircleCable2D
- Object (Constraint)
- Object (Joint)
- Marker
- MarkerBodyMass
- MarkerBodyPosition
- MarkerBodyRigid
- MarkerNodePosition
- MarkerNodeRigid
- MarkerNodeCoordinate
- MarkerNodeCoordinates
- MarkerNodeODE1Coordinate
- MarkerNodeRotationCoordinate
- MarkerSuperElementPosition
- MarkerSuperElementRigid
- MarkerKinematicTreeRigid
- MarkerObjectODE2Coordinates
- MarkerBodyCable2DShape
- MarkerBodyCable2DCoordinates
- Load
- Sensor
- Structures and Settings
- Simulation settings
- Visualization settings
- VSettingsGeneral
- VSettingsContour
- VSettingsNodes
- VSettingsBeams
- VSettingsKinematicTree
- VSettingsBodies
- VSettingsConnectors
- VSettingsMarkers
- VSettingsLoads
- VSettingsSensorTraces
- VSettingsSensors
- VSettingsContact
- VSettingsWindow
- VSettingsDialogs
- VSettingsOpenGL
- VSettingsExportImages
- VSettingsOpenVR
- VSettingsInteractive
- VisualizationSettings
- Solver substructures
- MainSolverStatic
- MainSolverImplicitSecondOrder
- MainSolverExplicit
- Structures for structural elements
- BeamSectionGeometry
- List of Abbreviations
- Examples
- 3SpringsDistance.py
- addPrismaticJoint.py
- addRevoluteJoint.py
- ALEANCFpipe.py
- ANCFALEtest.py
- ANCFcableCantilevered.py
- ANCFcantileverTest.py
- ANCFcantileverTestDyn.py
- ANCFcontactCircle.py
- ANCFcontactCircle2.py
- ANCFmovingRigidbody.py
- ANCFrotatingCable2D.py
- ANCFslidingJoint2D.py
- ANCFslidingJoint2Drigid.py
- ANCFswitchingSlidingJoint2D.py
- ANCFtestHalfcircle.py
- ANCFtests2.py
- basicTutorial2024.py
- beamTutorial.py
- beltDriveALE.py
- beltDriveReevingSystem.py
- beltDrivesComparison.py
- bicycleIftommBenchmark.py
- bungeeJump.py
- cartesianSpringDamper.py
- cartesianSpringDamperUserFunction.py
- chatGPTupdate.py
- chatGPTupdate2.py
- CMSexampleCourse.py
- ComputeSensitivitiesExample.py
- coordinateSpringDamper.py
- craneReevingSystem.py
- dispyParameterVariationExample.py
- doublePendulum2D.py
- finiteSegmentMethod.py
- flexiblePendulumANCF.py
- flexibleRotor3Dtest.py
- fourBarMechanism3D.py
- geneticOptimizationSliderCrank.py
- graphicsDataExample.py
- gyroStability.py
- humanRobotInteraction.py
- HydraulicActuator2Arms.py
- HydraulicActuatorStaticInitialization.py
- HydraulicsUserFunction.py
- interactiveTutorial.py
- InverseKinematicsNumericalExample.py
- kinematicTreeAndMBS.py
- kinematicTreePendulum.py
- lavalRotor2Dtest.py
- leggedRobot.py
- lugreFrictionODE1.py
- lugreFrictionTest.py
- massSpringFrictionInteractive.py
- minimizeExample.py
- mobileMecanumWheelRobotWithLidar.py
- mouseInteractionExample.py
- mpi4pyExample.py
- multiMbsTest.py
- multiprocessingTest.py
- myFirstExample.py
- netgenSTLtest.py
- NGsolveCMStutorial.py
- NGsolveCraigBampton.py
- NGsolveGeometry.py
- NGsolveLinearFEM.py
- NGsolvePistonEngine.py
- NGsolvePostProcessingStresses.py
- nMassOscillator.py
- nMassOscillatorEigenmodes.py
- nMassOscillatorInteractive.py
- ObjectFFRFconvergenceTestBeam.py
- ObjectFFRFconvergenceTestHinge.py
- objectFFRFreducedOrderNetgen.py
- openAIgymInterfaceTest.py
- openAIgymNLinkAdvanced.py
- openAIgymNLinkContinuous.py
- openAIgymTriplePendulum.py
- openVRengine.py
- parameterVariationExample.py
- particleClusters.py
- particlesSilo.py
- particlesTest.py
- particlesTest3D.py
- particlesTest3D2.py
- pendulum.py
- pendulum2Dconstraint.py
- pendulumGeomExactBeam2D.py
- pendulumGeomExactBeam2Dsimple.py
- pendulumIftommBenchmark.py
- pendulumVerify.py
- performanceMultiThreadingNG.py
- pistonEngine.py
- plotSensorExamples.py
- reevingSystem.py
- reevingSystemOpen.py
- reinforcementLearningRobot.py
- rigid3Dexample.py
- rigidBodyIMUtest.py
- rigidBodyTutorial.py
- rigidBodyTutorial2.py
- rigidBodyTutorial3.py
- rigidBodyTutorial3withMarkers.py
- rigidPendulum.py
- rigidRotor3DbasicBehaviour.py
- rigidRotor3DFWBW.py
- rigidRotor3Dnutation.py
- rigidRotor3Drunup.py
- ROSMassPoint.py
- ROSMobileManipulator.py
- ROSTurtle.py
- serialRobotFlexible.py
- serialRobotInteractiveLimits.py
- serialRobotInverseKinematics.py
- serialRobotKinematicTree.py
- serialRobotKinematicTreeDigging.py
- serialRobotTSD.py
- shapeOptimization.py
- simple4linkPendulumBing.py
- simulateInteractively.py
- SliderCrank.py
- sliderCrank3DwithANCFbeltDrive.py
- sliderCrank3DwithANCFbeltDrive2.py
- slidercrankWithMassSpring.py
- solutionViewerMultipleSimulations.py
- solutionViewerTest.py
- solverFunctionsTestEigenvalues.py
- SpringDamperMasspointSystem.py
- SpringDamperMassUserFunction.py
- springDamperTutorial.py
- springDamperTutorialNew.py
- springDamperUserFunctionNumbaJIT.py
- springMassFriction.py
- springsDeactivateConnectors.py
- SpringWithConstraints.py
- stiffFlyballGovernor2.py
- stiffFlyballGovernorKT.py
- stlFileImport.py
- switchingConstraintsPendulum.py
- symbolicUserFunctionMasses.py
- TCPIPclientTest.py
- TCPIPexudynMatlab.py
- TCPIPserverTest.py
- testGymCartpole.py
- testGymCartpoleEnv.py
- testGymDoublePendulum.py
- testGymDoublePendulumEnv.py
- tippeTop.py
- tutorialNeuralNetwork.py
- universalJoint.py
- TestModels
- abaqusImportTest.py
- ANCFBeamTest.py
- ANCFcable2DuserFunction.py
- ANCFcontactCircleTest.py
- ANCFcontactFrictionTest.py
- ANCFgeneralContactCircle.py
- ANCFmovingRigidBodyTest.py
- ANCFslidingAndALEjointTest.py
- bricardMechanism.py
- carRollingDiscTest.py
- compareAbaqusAnsysRotorEigenfrequencies.py
- compareFullModifiedNewton.py
- complexEigenvaluesTest.py
- computeODE2AEeigenvaluesTest.py
- computeODE2EigenvaluesTest.py
- connectorGravityTest.py
- connectorRigidBodySpringDamperTest.py
- contactCoordinateTest.py
- ConvexContactTest.py
- coordinateSpringDamperExt.py
- coordinateVectorConstraint.py
- coordinateVectorConstraintGenericODE2.py
- distanceSensor.py
- driveTrainTest.py
- explicitLieGroupIntegratorPythonTest.py
- explicitLieGroupIntegratorTest.py
- fourBarMechanismTest.py
- fourBarMechanismIftomm.py
- generalContactCylinderTest.py
- generalContactCylinderTrigsTest.py
- generalContactFrictionTests.py
- generalContactSpheresTest.py
- genericJointUserFunctionTest.py
- genericODE2test.py
- geneticOptimizationTest.py
- geometricallyExactBeam2Dtest.py
- geometricallyExactBeamTest.py
- gridGeomExactBeam2D.py
- heavyTop.py
- hydraulicActuatorSimpleTest.py
- kinematicTreeAndMBStest.py
- kinematicTreeConstraintTest.py
- kinematicTreeTest.py
- laserScannerTest.py
- linearFEMgenericODE2.py
- LShapeGeomExactBeam2D.py
- mainSystemExtensionsTests.py
- manualExplicitIntegrator.py
- matrixContainerTest.py
- mecanumWheelRollingDiscTest.py
- objectFFRFreducedOrderAccelerations.py
- objectFFRFreducedOrderTest.py
- objectFFRFTest.py
- objectFFRFTest2.py
- objectGenericODE2Test.py
- PARTS_ATEs_moving.py
- pendulumFriction.py
- plotSensorTest.py
- postNewtonStepContactTest.py
- reevingSystemSpringsTest.py
- rigidBodyAsUserFunctionTest.py
- rigidBodyCOMtest.py
- rigidBodySpringDamperIntrinsic.py
- rollingCoinTest.py
- rollingDiscTangentialForces.py
- rollingCoinPenaltyTest.py
- rotatingTableTest.py
- scissorPrismaticRevolute2D.py
- sensorUserFunctionTest.py
- serialRobotTest.py
- sliderCrank3Dtest.py
- sliderCrankFloatingTest.py
- solverExplicitODE1ODE2test.py
- sparseMatrixSpringDamperTest.py
- sphericalJointTest.py
- springDamperUserFunctionTest.py
- stiffFlyballGovernor.py
- superElementRigidJointTest.py
- symbolicUserFunctionTest.py
- symbolicModuleTest.py
- taskmanagerTest.py
- velocityVerletTest.py
- Issue tracker
Indices and tables
Theory: Contact
See according section in theDoc.pdf
Further information
SEE Exudyn documentation : theDoc.pdf